File tree Expand file tree Collapse file tree 1 file changed +7
-2
lines changed Expand file tree Collapse file tree 1 file changed +7
-2
lines changed Original file line number Diff line number Diff line change @@ -353,18 +353,23 @@ NavfnPlanner::smoothApproachToGoal(
353
353
const geometry_msgs::msg::Pose & goal,
354
354
nav_msgs::msg::Path & plan)
355
355
{
356
- // Replace the last pose of the computed path if it's actually further away
357
- // to the second to last pose than the goal pose.
358
356
if (plan.poses .size () >= 2 ) {
359
357
auto second_to_last_pose = plan.poses .end ()[-2 ];
360
358
auto last_pose = plan.poses .back ();
359
+ // Replace the last pose of the computed path if it's actually further away
360
+ // to the second to last pose than the goal pose.
361
361
if (
362
362
squared_distance (last_pose.pose , second_to_last_pose.pose ) >
363
363
squared_distance (goal, second_to_last_pose.pose ))
364
364
{
365
365
plan.poses .back ().pose = goal;
366
366
return ;
367
367
}
368
+ // Replace the last pose of the computed path if its position matches but orientation differs
369
+ if (squared_distance (last_pose.pose , goal) < 1e-6 ) {
370
+ plan.poses .back ().pose = goal;
371
+ return ;
372
+ }
368
373
}
369
374
geometry_msgs::msg::PoseStamped goal_copy;
370
375
goal_copy.pose = goal;
You can’t perform that action at this time.
0 commit comments