Skip to content

Commit

Permalink
use unique_ptr for map_update_thread (#2977)
Browse files Browse the repository at this point in the history
* use unique_ptr for map_update_thread

Signed-off-by: zhenpeng ge <[email protected]>

* update

Signed-off-by: zhenpeng ge <[email protected]>
  • Loading branch information
gezp authored Jun 1, 2022
1 parent 3bd773c commit bd31820
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 8 deletions.
2 changes: 1 addition & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -329,7 +329,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode
bool stop_updates_{false};
bool initialized_{false};
bool stopped_{true};
std::thread * map_update_thread_{nullptr}; ///< @brief A thread for updating the map
std::unique_ptr<std::thread> map_update_thread_; ///< @brief A thread for updating the map
rclcpp::Time last_publish_{0, 0, RCL_ROS_TIME};
rclcpp::Duration publish_cycle_{1, 0};
pluginlib::ClassLoader<Layer> plugin_loader_{"nav2_costmap_2d", "nav2_costmap_2d::Layer"};
Expand Down
9 changes: 2 additions & 7 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,10 +238,8 @@ Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/)
stopped_ = true; // to active plugins
stop_updates_ = false;
map_update_thread_shutdown_ = false;

map_update_thread_ = new std::thread(
std::bind(
&Costmap2DROS::mapUpdateLoop, this, map_update_frequency_));
map_update_thread_ = std::make_unique<std::thread>(
std::bind(&Costmap2DROS::mapUpdateLoop, this, map_update_frequency_));

start();

Expand All @@ -264,11 +262,8 @@ Costmap2DROS::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
stop();

// Map thread stuff
// TODO(mjeronimo): unique_ptr
map_update_thread_shutdown_ = true;
map_update_thread_->join();
delete map_update_thread_;
map_update_thread_ = nullptr;

return nav2_util::CallbackReturn::SUCCESS;
}
Expand Down

0 comments on commit bd31820

Please sign in to comment.