Skip to content

Commit ff88c48

Browse files
adding mutex lock around map resizing due to dynamic parameter changes and associated processes (#4373) (#4377)
(cherry picked from commit b0abc78) Co-authored-by: Steve Macenski <[email protected]>
1 parent 4cb6aba commit ff88c48

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
@@ -348,6 +348,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode
348348
std::atomic<bool> stop_updates_{false};
349349
std::atomic<bool> initialized_{false};
350350
std::atomic<bool> stopped_{true};
351+
std::mutex _dynamic_parameter_mutex;
351352
std::unique_ptr<std::thread> map_update_thread_; ///< @brief A thread for updating the map
352353
rclcpp::Time last_publish_{0, 0, RCL_ROS_TIME};
353354
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
@@ -508,6 +508,9 @@ Costmap2DROS::mapUpdateLoop(double frequency)
508508

509509
// Execute after start() will complete plugins activation
510510
if (!stopped_) {
511+
// Lock while modifying layered costmap and publishing values
512+
std::scoped_lock<std::mutex> lock(_dynamic_parameter_mutex);
513+
511514
// Measure the execution time of the updateMap method
512515
timer.start();
513516
updateMap();
@@ -708,6 +711,7 @@ Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameter
708711
{
709712
auto result = rcl_interfaces::msg::SetParametersResult();
710713
bool resize_map = false;
714+
std::lock_guard<std::mutex> lock_reinit(_dynamic_parameter_mutex);
711715

712716
for (auto parameter : parameters) {
713717
const auto & type = parameter.get_type();
@@ -803,6 +807,7 @@ Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameter
803807
layered_costmap_->resizeMap(
804808
(unsigned int)(map_width_meters_ / resolution_),
805809
(unsigned int)(map_height_meters_ / resolution_), resolution_, origin_x_, origin_y_);
810+
updateMap();
806811
}
807812

808813
result.successful = true;

0 commit comments

Comments
 (0)