diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index af28b1b1eb0..de239b3587e 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -400,7 +400,10 @@ void PlannerServer::computePlanThroughPoses() if (i == 0) { curr_start = start; } else { - curr_start = goal->goals[i - 1]; + // pick the end of the last planning task as the start for the next one + // to allow for path tolerance deviations + curr_start = concat_path.poses.back(); + curr_start.header = concat_path.header; } curr_goal = goal->goals[i]; @@ -644,8 +647,8 @@ void PlannerServer::isPathValid( /** * The lethal check starts at the closest point to avoid points that have already been passed - * and may have become occupied. The method for collision detection is based on the shape of - * the footprint. + * and may have become occupied. The method for collision detection is based on the shape of + * the footprint. */ std::unique_lock lock(*(costmap_->getMutex())); unsigned int mx = 0;