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

Use mutex to protect costmap reads. (backport #3877) #3896

Merged
merged 1 commit into from
Oct 23, 2023
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
5 changes: 4 additions & 1 deletion nav2_mppi_controller/src/controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,9 +83,12 @@ geometry_msgs::msg::TwistStamped MPPIController::computeVelocityCommands(
auto start = std::chrono::system_clock::now();
#endif

std::lock_guard<std::mutex> lock(*parameters_handler_->getLock());
std::lock_guard<std::mutex> param_lock(*parameters_handler_->getLock());
nav_msgs::msg::Path transformed_plan = path_handler_.transformPath(robot_pose);

nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> costmap_lock(*(costmap->getMutex()));

geometry_msgs::msg::TwistStamped cmd =
optimizer_.evalControl(robot_pose, robot_speed, transformed_plan, goal_checker);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -157,6 +157,9 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
{
std::lock_guard<std::mutex> lock_reinit(param_handler_->getMutex());

nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));

// Update for the current goal checker's state
geometry_msgs::msg::Pose pose_tolerance;
geometry_msgs::msg::Twist vel_tolerance;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,9 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands
nav2_core::GoalChecker * goal_checker)
{
if (path_updated_) {
nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));

std::lock_guard<std::mutex> lock_reinit(mutex_);
try {
geometry_msgs::msg::Pose sampled_pt_base = transformPoseToBaseFrame(getSampledPathPt());
Expand Down