Skip to content

Commit

Permalink
Use mutex to protect costmap reads. (ros-navigation#3877)
Browse files Browse the repository at this point in the history
* 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 <leif@peanutrobotics.com>
  • Loading branch information
LeifHookedWireless and Leif Terry authored Oct 18, 2023
1 parent 7009ffb commit a1c9fd5
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 1 deletion.
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

0 comments on commit a1c9fd5

Please sign in to comment.