Skip to content

Commit

Permalink
adding mutex lock around map resizing due to dynamic parameter change…
Browse files Browse the repository at this point in the history
…s and associated processes (ros-navigation#4373)
  • Loading branch information
SteveMacenski committed May 29, 2024
1 parent 1f26900 commit b0abc78
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 0 deletions.
1 change: 1 addition & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -371,6 +371,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode
std::atomic<bool> stop_updates_{false};
std::atomic<bool> initialized_{false};
std::atomic<bool> stopped_{true};
std::mutex _dynamic_parameter_mutex;
std::unique_ptr<std::thread> 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};
Expand Down
5 changes: 5 additions & 0 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -511,6 +511,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<std::mutex> lock(_dynamic_parameter_mutex);

// Measure the execution time of the updateMap method
timer.start();
updateMap();
Expand Down Expand Up @@ -711,6 +714,7 @@ Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameter
{
auto result = rcl_interfaces::msg::SetParametersResult();
bool resize_map = false;
std::lock_guard<std::mutex> lock_reinit(_dynamic_parameter_mutex);

for (auto parameter : parameters) {
const auto & type = parameter.get_type();
Expand Down Expand Up @@ -806,6 +810,7 @@ Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> 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;
Expand Down

0 comments on commit b0abc78

Please sign in to comment.