Skip to content

Commit 0629ff3

Browse files
Update theta_star_planner.cpp (ros-navigation#3918)
1 parent 4b4465d commit 0629ff3

File tree

1 file changed

+2
-0
lines changed

1 file changed

+2
-0
lines changed

nav2_theta_star_planner/src/theta_star_planner.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,8 @@ nav_msgs::msg::Path ThetaStarPlanner::createPlan(
9191
nav_msgs::msg::Path global_path;
9292
auto start_time = std::chrono::steady_clock::now();
9393

94+
std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(planner_->costmap_->getMutex()));
95+
9496
// Corner case of start and goal beeing on the same cell
9597
unsigned int mx_start, my_start, mx_goal, my_goal;
9698
if (!planner_->costmap_->worldToMap(

0 commit comments

Comments
 (0)