Skip to content
Snippets Groups Projects
Commit cc50e2e6 authored by bpwilcox's avatar bpwilcox
Browse files

set first_map_received to false when cleaning up

parent 030a0e1d
No related branches found
No related tags found
No related merge requests found
......@@ -86,7 +86,7 @@ protected:
map_t * map_{nullptr};
map_t * convertMap(const nav_msgs::msg::OccupancyGrid & map_msg);
bool first_map_only_{true};
bool first_map_received_{false};
std::atomic<bool> first_map_received_{false};
amcl_hyp_t * initial_pose_hyp_;
std::recursive_mutex configuration_mutex_;
rclcpp::Subscription<nav_msgs::msg::OccupancyGrid>::ConstSharedPtr map_sub_;
......
......@@ -285,6 +285,7 @@ AmclNode::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
// Map
map_free(map_);
map_ = nullptr;
first_map_received_ = false;
free_space_indices.resize(0);
// Transforms
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment