Skip to content

Commit f1957a1

Browse files
mergify[bot]SteveMacenski
authored andcommitted
adding mutex lock around map resizing due to dynamic parameter changes and associated processes (ros-navigation#4373) (ros-navigation#4378)
(cherry picked from commit b0abc78) Co-authored-by: Steve Macenski <[email protected]>
1 parent fb08059 commit f1957a1

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
@@ -333,6 +333,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode
333333
std::atomic<bool> stop_updates_{false};
334334
std::atomic<bool> initialized_{false};
335335
std::atomic<bool> stopped_{true};
336+
std::mutex _dynamic_parameter_mutex;
336337
std::unique_ptr<std::thread> map_update_thread_; ///< @brief A thread for updating the map
337338
rclcpp::Time last_publish_{0, 0, RCL_ROS_TIME};
338339
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
@@ -430,6 +430,9 @@ Costmap2DROS::mapUpdateLoop(double frequency)
430430

431431
// Execute after start() will complete plugins activation
432432
if (!stopped_) {
433+
// Lock while modifying layered costmap and publishing values
434+
std::scoped_lock<std::mutex> lock(_dynamic_parameter_mutex);
435+
433436
// Measure the execution time of the updateMap method
434437
timer.start();
435438
updateMap();
@@ -619,6 +622,7 @@ Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameter
619622
{
620623
auto result = rcl_interfaces::msg::SetParametersResult();
621624
bool resize_map = false;
625+
std::lock_guard<std::mutex> lock_reinit(_dynamic_parameter_mutex);
622626

623627
for (auto parameter : parameters) {
624628
const auto & type = parameter.get_type();
@@ -714,6 +718,7 @@ Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameter
714718
layered_costmap_->resizeMap(
715719
(unsigned int)(map_width_meters_ / resolution_),
716720
(unsigned int)(map_height_meters_ / resolution_), resolution_, origin_x_, origin_y_);
721+
updateMap();
717722
}
718723

719724
result.successful = true;

0 commit comments

Comments
 (0)