Skip to content

Costmap lock while copying data in navfn planner #1913

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

Merged
merged 2 commits into from
Aug 5, 2020
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
8 changes: 8 additions & 0 deletions nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -325,6 +325,9 @@ DWBLocalPlanner::computeVelocityCommands(

prepareGlobalPlan(pose, transformed_plan, goal_pose);

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

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This isn't the controller_server, this is a specific plugin. We should have this in the controller_server the way we have it in the planner_server

Copy link
Member

@SteveMacenski SteveMacenski Aug 5, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

See the nav2_controller package, its pretty much analog to the nav2_planner package

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I put the lock, not in nav2_planner but nav2_navfn_planner because if we put it in nav2_planner it will lock up not only while accessing costmap but also while calculating plans.

So, I put the lock here not in nav2_controller, considering performance.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, we can do that. I'll file tickets on other plugins to implement this.


for (TrajectoryCritic::Ptr critic : critics_) {
if (critic->prepare(pose.pose, velocity, goal_pose.pose, transformed_plan) == false) {
RCLCPP_WARN(rclcpp::get_logger("DWBLocalPlanner"), "A scoring function failed to prepare");
Expand All @@ -344,6 +347,8 @@ DWBLocalPlanner::computeVelocityCommands(
critic->debrief(cmd_vel.velocity);
}

lock.unlock();

pub_->publishLocalPlan(pose.header, best.traj);
pub_->publishCostGrid(costmap_ros_, critics_);

Expand All @@ -355,6 +360,9 @@ DWBLocalPlanner::computeVelocityCommands(
for (TrajectoryCritic::Ptr critic : critics_) {
critic->debrief(empty_cmd);
}

lock.unlock();

pub_->publishLocalPlan(pose.header, empty_traj);
pub_->publishCostGrid(costmap_ros_, critics_);

Expand Down
4 changes: 4 additions & 0 deletions nav2_navfn_planner/src/navfn_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,13 +174,17 @@ NavfnPlanner::makePlan(
// clear the starting cell within the costmap because we know it can't be an obstacle
clearRobotCell(mx, my);

std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap_->getMutex()));

// make sure to resize the underlying array that Navfn uses
planner_->setNavArr(
costmap_->getSizeInCellsX(),
costmap_->getSizeInCellsY());

planner_->setCostmap(costmap_->getCharMap(), true, allow_unknown_);

lock.unlock();

int map_start[2];
map_start[0] = mx;
map_start[1] = my;
Expand Down