Skip to content

Commit 00a9066

Browse files
Use mutex to protect costmap reads. (#3877) (#3896)
* Use mutex to protect costmap reads. Otherwise costmap can be read during a map update and return 0. * Revert "Use mutex to protect costmap reads." This reverts commit e16a44c. * Lock costmap before running MPPI controller. * Fix typo. * Protect against costmap updates in MPP and RotationShim controllers. --------- Co-authored-by: Leif Terry <[email protected]> (cherry picked from commit a1c9fd5) Co-authored-by: LeifHookedWireless <[email protected]>
1 parent 446283c commit 00a9066

File tree

3 files changed

+10
-1
lines changed

3 files changed

+10
-1
lines changed

nav2_mppi_controller/src/controller.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -83,9 +83,12 @@ geometry_msgs::msg::TwistStamped MPPIController::computeVelocityCommands(
8383
auto start = std::chrono::system_clock::now();
8484
#endif
8585

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

89+
nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
90+
std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> costmap_lock(*(costmap->getMutex()));
91+
8992
geometry_msgs::msg::TwistStamped cmd =
9093
optimizer_.evalControl(robot_pose, robot_speed, transformed_plan, goal_checker);
9194

nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -157,6 +157,9 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
157157
{
158158
std::lock_guard<std::mutex> lock_reinit(param_handler_->getMutex());
159159

160+
nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
161+
std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
162+
160163
// Update for the current goal checker's state
161164
geometry_msgs::msg::Pose pose_tolerance;
162165
geometry_msgs::msg::Twist vel_tolerance;

nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -140,6 +140,9 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands
140140
nav2_core::GoalChecker * goal_checker)
141141
{
142142
if (path_updated_) {
143+
nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
144+
std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
145+
143146
std::lock_guard<std::mutex> lock_reinit(mutex_);
144147
try {
145148
geometry_msgs::msg::Pose sampled_pt_base = transformPoseToBaseFrame(getSampledPathPt());

0 commit comments

Comments
 (0)