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 af93f4c7e0..f4f365e848 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 @@ -333,6 +333,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode std::atomic stop_updates_{false}; std::atomic initialized_{false}; std::atomic stopped_{true}; + std::mutex _dynamic_parameter_mutex; 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}; diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 6c57949062..98bcb0ff36 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -430,6 +430,9 @@ Costmap2DROS::mapUpdateLoop(double frequency) // Execute after start() will complete plugins activation if (!stopped_) { + // Lock while modifying layered costmap and publishing values + std::scoped_lock lock(_dynamic_parameter_mutex); + // Measure the execution time of the updateMap method timer.start(); updateMap(); @@ -619,6 +622,7 @@ Costmap2DROS::dynamicParametersCallback(std::vector parameter { auto result = rcl_interfaces::msg::SetParametersResult(); bool resize_map = false; + std::lock_guard lock_reinit(_dynamic_parameter_mutex); for (auto parameter : parameters) { const auto & type = parameter.get_type(); @@ -714,6 +718,7 @@ Costmap2DROS::dynamicParametersCallback(std::vector parameter layered_costmap_->resizeMap( (unsigned int)(map_width_meters_ / resolution_), (unsigned int)(map_height_meters_ / resolution_), resolution_, origin_x_, origin_y_); + updateMap(); } result.successful = true;