Skip to content

Commit b0abc78

Browse files
adding mutex lock around map resizing due to dynamic parameter changes and associated processes (ros-navigation#4373)
1 parent 1f26900 commit b0abc78

File tree

2 files changed

+6
-0
lines changed

2 files changed

+6
-0
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -371,6 +371,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode
371371
std::atomic<bool> stop_updates_{false};
372372
std::atomic<bool> initialized_{false};
373373
std::atomic<bool> stopped_{true};
374+
std::mutex _dynamic_parameter_mutex;
374375
std::unique_ptr<std::thread> map_update_thread_; ///< @brief A thread for updating the map
375376
rclcpp::Time last_publish_{0, 0, RCL_ROS_TIME};
376377
rclcpp::Duration publish_cycle_{1, 0};

nav2_costmap_2d/src/costmap_2d_ros.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -511,6 +511,9 @@ Costmap2DROS::mapUpdateLoop(double frequency)
511511

512512
// Execute after start() will complete plugins activation
513513
if (!stopped_) {
514+
// Lock while modifying layered costmap and publishing values
515+
std::scoped_lock<std::mutex> lock(_dynamic_parameter_mutex);
516+
514517
// Measure the execution time of the updateMap method
515518
timer.start();
516519
updateMap();
@@ -711,6 +714,7 @@ Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameter
711714
{
712715
auto result = rcl_interfaces::msg::SetParametersResult();
713716
bool resize_map = false;
717+
std::lock_guard<std::mutex> lock_reinit(_dynamic_parameter_mutex);
714718

715719
for (auto parameter : parameters) {
716720
const auto & type = parameter.get_type();
@@ -806,6 +810,7 @@ Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameter
806810
layered_costmap_->resizeMap(
807811
(unsigned int)(map_width_meters_ / resolution_),
808812
(unsigned int)(map_height_meters_ / resolution_), resolution_, origin_x_, origin_y_);
813+
updateMap();
809814
}
810815

811816
result.successful = true;

0 commit comments

Comments
 (0)