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 @@ -351,18 +351,23 @@ NavfnPlanner::smoothApproachToGoal(
351351 const geometry_msgs::msg::Pose & goal,
352352 nav_msgs::msg::Path & plan)
353353{
354- // Replace the last pose of the computed path if it's actually further away
355- // to the second to last pose than the goal pose.
356354 if (plan.poses .size () >= 2 ) {
357355 auto second_to_last_pose = plan.poses .end ()[-2 ];
358356 auto last_pose = plan.poses .back ();
357+ // Replace the last pose of the computed path if it's actually further away
358+ // to the second to last pose than the goal pose.
359359 if (
360360 squared_distance (last_pose.pose , second_to_last_pose.pose ) >
361361 squared_distance (goal, second_to_last_pose.pose ))
362362 {
363363 plan.poses .back ().pose = goal;
364364 return ;
365365 }
366+ // Replace the last pose of the computed path if its position matches but orientation differs
367+ if (squared_distance (last_pose.pose , goal) < 1e-6 ) {
368+ plan.poses .back ().pose = goal;
369+ return ;
370+ }
366371 }
367372 geometry_msgs::msg::PoseStamped goal_copy;
368373 goal_copy.pose = goal;
You can’t perform that action at this time.
0 commit comments