Skip to content

Commit

Permalink
Make mapUpdateLoop() indicator variables to be thread-safe (ros-navig…
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexeyMerzlyakov authored and Joshua Wallace committed Dec 14, 2022
1 parent 6143295 commit c119017
Showing 1 changed file with 4 additions and 3 deletions.
7 changes: 4 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#ifndef NAV2_COSTMAP_2D__COSTMAP_2D_ROS_HPP_
#define NAV2_COSTMAP_2D__COSTMAP_2D_ROS_HPP_

#include <atomic>
#include <memory>
#include <string>
#include <vector>
Expand Down Expand Up @@ -342,9 +343,9 @@ class Costmap2DROS : public nav2_util::LifecycleNode
*/
void mapUpdateLoop(double frequency);
bool map_update_thread_shutdown_{false};
bool stop_updates_{false};
bool initialized_{false};
bool stopped_{true};
std::atomic<bool> stop_updates_{false};
std::atomic<bool> initialized_{false};
std::atomic<bool> stopped_{true};
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};
Expand Down

0 comments on commit c119017

Please sign in to comment.