Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adding mutex lock around map resizing due to dynamic parameter changes and associated processes (backport #4373) #4378

Merged
merged 1 commit into from
May 29, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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 @@ -333,6 +333,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 @@ -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<std::mutex> lock(_dynamic_parameter_mutex);

// Measure the execution time of the updateMap method
timer.start();
updateMap();
Expand Down Expand Up @@ -619,6 +622,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 @@ -714,6 +718,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