From 9009bd204a2d8fca44977496e031976a5e75fba9 Mon Sep 17 00:00:00 2001 From: Alexey Merzlyakov <60094858+AlexeyMerzlyakov@users.noreply.github.com> Date: Tue, 6 Dec 2022 21:45:41 +0300 Subject: [PATCH] Make mapUpdateLoop() indicator variables to be thread-safe (#3308) --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index a5dfc6182a..af93f4c7e0 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -38,6 +38,7 @@ #ifndef NAV2_COSTMAP_2D__COSTMAP_2D_ROS_HPP_ #define NAV2_COSTMAP_2D__COSTMAP_2D_ROS_HPP_ +#include #include #include #include @@ -329,9 +330,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 stop_updates_{false}; + std::atomic initialized_{false}; + std::atomic stopped_{true}; std::unique_ptr 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};