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

Costmap lock while copying data in navfn planner #1913

Merged
merged 2 commits into from
Aug 5, 2020
Merged
Changes from 1 commit
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
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