Skip to content

Commit 2b02d7d

Browse files
committed
Fix early termination bug
Signed-off-by: mini-1235 <[email protected]>
1 parent 2fb6d1e commit 2b02d7d

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

nav2_controller/plugins/feasible_path_handler.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -202,7 +202,7 @@ nav_msgs::msg::Path FeasiblePathHandler::transformLocalPlan(
202202
if (!costmap_ros_->getCostmap()->worldToMap(
203203
costmap_plan_pose.pose.position.x, costmap_plan_pose.pose.position.y, mx, my))
204204
{
205-
return transformed_plan;
205+
break;
206206
}
207207

208208
// Filling the transformed plan to return with the transformed pose

0 commit comments

Comments
 (0)