Skip to content

Conversation

mini-1235
Copy link
Contributor

@mini-1235 mini-1235 commented Aug 12, 2025

This PR continues the work in #4789
Fixes #4757
Fixes #4304

This is a continuation of work started by @ottojo in draft PR #4593

I'll quote their introduction and, expand a bit afterwards, and update any fields that have changed.

The controller server uses a configurable goal checker to determine if the robot has completed its current path as defined by the global plan. Current goal checkers compare the goal (end of path) pose and twist to the current robot state, but that is not sufficient in all cases.
In some use cases, the path will visit the goal multiple times, and the goal might coincide with the starting position. It is still desired that the robot follows the entire path, instead of immediately ending navigation once the goal pose is reached.
This PR adds a parameter to the GoalChecker interface to inform the goal checker of the current path, which enables building more sophisticated goal checkers that (for example) take progress along the path into account.
We already use such a goal checker internally, which just subscribes to the global plan via the appropriate ROS topic, but i think this here is the cleaner solution (and also avoids race conditions of checking against an old path in the goal checker...)
I don't have a nice testing setup and a goal checker using this interface yet (other than our own robot and the mentioned goal checker), which is why I mark this as draft for now.

I've cherry-picked @ottojo 's commit on top of the latest main branch, then added a new basic goal checker PathCompleteGoalChecker, which is a subclass of SimpleGoalChecker, but has an additional parameter (path_length_tolerance, default=1), and checks that the current path has <= path_length_tolerance waypoints before allowing the normal SimpleGoalChecker completion logic to take its course.

The result is a trivial extension of SimpleGoalChecker that should be immune to the current_pose = goal_pose short-circuit problem/bug. Rather than try to create an elaborate unit test that navigates a course, I stuck to first principles to ensure that the new plugin behaves the same as SimpleGoalChecker with <= path_length_tolerance waypoints, and that it does not complete with > path_length_tolerance waypoints.

Basic Info

Info Please fill out this column
Ticket(s) this addresses #4304
Primary OS tested on Ubuntu
Robotic platform tested on (WIP)
Does this PR contain AI generated software? No

Description of contribution in a few bullet points

  • Extend GoalChecker::isGoalReached interface with argument for current path
  • Add this argument to the in-tree goal checker implementations
  • Add a goal checker which checks for path-completion
  • [] Define a test-scenario with global plan that returns to start pose

Description of documentation updates required from your changes

  • Migration guide for out-of-tree goal checkers

Future work that may be required in bullet points

  • Implementing more sophisticated goal checkers

For Maintainers:

  • Check that any new parameters added are updated in docs.nav2.org
  • Check that any significant change is added to the migration guide
  • Check that any new features OR changes to existing behaviors are reflected in the tuning guide
  • Check that any new functions have Doxygen added
  • Check that any new features have test coverage
  • Check that any new plugins is added to the plugins page
  • If BT Node, Additionally: add to BT's XML index of nodes for groot, BT package's readme table, and BT library lists

@mini-1235
Copy link
Contributor Author

@SteveMacenski before I go too far, can you take a quick look to make sure I am on the right track? I have only pushed the changes in nav2_controller, graceful_controller and RPP

Copy link
Contributor

mergify bot commented Aug 12, 2025

@mini-1235, your PR has failed to build. Please check CI outputs and resolve issues.
You may need to rebase or pull in main due to API changes (or your contribution genuinely fails).

@mini-1235
Copy link
Contributor Author

I have spent some time reading into MPPI's path handler, I can see there are some improvements like #3659, #3443. Also, there is a related PR for RPP in #4763, maybe we need to check if these changes are applicable to all controllers? If yes, I guess it will be easier to move them in Controller Server

I also noticed that the DWB/MPPI need the path from planner to find its goal, should we pass this plan via the setplan api or a new argument in computevelocitycommands?

@mamariomiamo
Copy link

Hi, sorry to jump in here but just sharing my two cents:
Alternatively, is it possible to modify the end_pose_ to be the end of the pruned and transformed global path from the path_handler_? This way we do not need to add the additional PathCompleteGoalChecker since we will no longer be using the end of the global path for isGoalReached check. As the robot progresses along the global path, the pruned and transformed global path will eventually cover until the end of the global path and thus we will still be using the actual navigation goal as the final isGoalReached check.

@mamariomiamo
Copy link

I have spent some time reading into MPPI's path handler, I can see there are some improvements like #3659, #3443. Also, there is a related PR for RPP in #4763, maybe we need to check if these changes are applicable to all controllers? If yes, I guess it will be easier to move them in Controller Server

I also noticed that the DWB/MPPI need the path from planner to find its goal, should we pass this plan via the setplan api or a new argument in computevelocitycommands?

I think path_handler implementation from MPPI is more comprehensive as it also considers path up to inversion point. This would also be helpful when user uses Hybrid A* with reeds-shepp as the global planner.

@mini-1235
Copy link
Contributor Author

Hi, sorry to jump in here but just sharing my two cents: Alternatively, is it possible to modify the end_pose_ to be the end of the pruned and transformed global path from the path_handler_? This way we do not need to add the additional PathCompleteGoalChecker since we will no longer be using the end of the global path for isGoalReached check. As the robot progresses along the global path, the pruned and transformed global path will eventually cover until the end of the global path and thus we will still be using the actual navigation goal as the final isGoalReached check.

Thanks for sharing, I will try to implement this and compare with my current method

Copy link
Contributor

mergify bot commented Aug 16, 2025

@mini-1235, your PR has failed to build. Please check CI outputs and resolve issues.
You may need to rebase or pull in main due to API changes (or your contribution genuinely fails).

Copy link
Member

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sorry it took so long!

// Current path container
nav_msgs::msg::Path current_path_;
nav_msgs::msg::Path local_path_;
bool interpolate_curvature_after_goal_;
Copy link
Member

@SteveMacenski SteveMacenski Aug 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this really a controller-server specific parameter? This feels specific to a given control algorithm plugin. Does the path handler need to know about this?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think path handler needs to, this is used as the reject_unit_path in rpp's path handler

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe I should rename it as reject unit path in my new path handler?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This comment is still valid, any suggestions? @SteveMacenski

goal_checker_loader_("nav2_core", "nav2_core::GoalChecker"),
default_goal_checker_ids_{"goal_checker"},
default_goal_checker_types_{"nav2_controller::SimpleGoalChecker"},
default_goal_checker_types_{"nav2_controller::PathCompleteGoalChecker"},
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think by 'default' I mean that this should just be built into the simple goal checker so that this just given to everyone 'for free'

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So I should remove this new plugin and add the path_length_tolerance to simple goal checker, do I understand this correctly?


odom_sub_ = std::make_unique<nav2_util::OdomSmoother>(node, odom_duration, odom_topic);
vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node, "cmd_vel");
global_path_pub_ = node->create_publisher<nav_msgs::msg::Path>("received_global_plan");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why this? We in other contexts publish out the path after its been pruned and converted into the odom frame for the local_path publisher so that we have a sense of what the controller is working with. Why directly publish out the global plan?

auto transformed_plan = path_handler_->transformGlobalPlan(
pose, max_robot_pose_search_dist_, interpolate_curvature_after_goal_);
// RCLCPP_INFO(get_logger(), "compute remaining distance %lf ",nav2_util::geometry_utils::calculate_path_length(transformed_plan));
global_path_pub_->publish(transformed_plan);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think if this is pruned, in the odom frame, and such, this is a local plan

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Also, make this into a unique pointer make_unique<nav_msgs::msg::Path>(local_path_)

@SteveMacenski
Copy link
Member

SteveMacenski commented Aug 28, 2025

I think path_handler implementation from MPPI is more comprehensive as it also considers path up to inversion point.

I agree with this general sentiment. I think it would be nice to review all the path handlers and make sure the key features of all are being respected in the server's implementation.

There's a number of CI failures that should also be looked at, but I'm sure you know :-)

@mini-1235
Copy link
Contributor Author

There's a number of CI failures that should also be looked at, but I'm sure you know :-)

Yes, I will continue this PR once #5496 and other future PRs targeting path handler are done

Copy link
Contributor

mergify bot commented Sep 24, 2025

@mini-1235, your PR has failed to build. Please check CI outputs and resolve issues.
You may need to rebase or pull in main due to API changes (or your contribution genuinely fails).

@mini-1235 mini-1235 changed the title Add path goal checker plugin Centralize path handler logic in controller server Sep 25, 2025
@mini-1235
Copy link
Contributor Author

mini-1235 commented Sep 25, 2025

@SteveMacenski I think you can start reviewing this when you have time, in the following days I plan to:

  • Finish DWB (Some logics are not handled yet)
  • Test Graceful/MPPI/RPP/DWB on different platform (Ackermann, Differential) with different params
  • Handle dynamic params in controller server
  • Fix & Add unit tests

Things to debate:

  1. Alternatively, is it possible to modify the end_pose_ to be the end of the pruned and transformed global path from the path_handler_? This way we do not need to add the additional PathCompleteGoalChecker since we will no longer be using the end of the global path for isGoalReached check

I think this becomes problematic when enforce_path_inversion is set to true. In that case, the local goal ends up being the cusping point, and the robot may stop there once it satisfies the XY and yaw tolerances. Because of this, I believe we still need the global goal for the goal checker. But as @SteveMacenski suggested, we could add this directly into the simple goal checker, so by default the simple goal checker is checking both the global goal and local path length. Do you agree with this approach? @mamariomiamo

  1. This PR has moved the following parameters from the plugin level to controller level:
transform_tolerance
prune_distance
max_robot_pose_search_dist
enforce_path_inversion
inversion_xy_tolerance
inversion_yaw_tolerance

Previously, the transform tolerance in the controller server was obtained from costmap->getTransformTolerance. I think it makes more sense for the server and its plugins to share the same tolerance, so I moved this to the controller level.

  1. We have different pruned_plan_end for MPPI and RPP,
    //TODO: For RPP and graceful we don't have prune distance, maybe we need to support two kinds of pruned_plan_end here
    // by parameter?
    if (1){
    pruned_plan_end = nav2_util::geometry_utils::first_after_integrated_distance(
    closest_point, global_plan_up_to_inversion_.poses.end(), params_->prune_distance);
    }
    else{
    pruned_plan_end = std::find_if(
    closest_point, global_plan_up_to_inversion_.poses.end(),
    [&](const auto & global_plan_pose) {
    return euclidean_distance(global_plan_pose, robot_pose) > max_costmap_extent;
    });
    }

    I am not sure how do we want to handle this, since only MPPI & DWB has the prune_distance parameter. Maybe adding a new parameter here will work?

Before merging this, I also need to:

  • Update nav2 tutorial with the new controller server API
  • Update docs, including migration guide, writing a new controller plugin, configuration guides

Copy link
Contributor

mergify bot commented Sep 25, 2025

@mini-1235, your PR has failed to build. Please check CI outputs and resolve issues.
You may need to rebase or pull in main due to API changes (or your contribution genuinely fails).

@SteveMacenski
Copy link
Member

OK will do! This is admittedly alot so this next round is going to be more high level.

... the local goal ends up being the cusping point, and the robot may stop there once it satisfies the XY and yaw tolerances ... we could add this directly into the simple goal checker, so by default the simple goal checker is checking both the global goal and local path length

Ah ok. That makes sense for the goal checker, though probably not the other elements right? When enforcing inversions is off, its the same either way since we just prune to the prune distance / costmap bounds. When is it enabled, then we prune to that which we want from the control algorithm's perspective, but not the goal checker.

Previously, the transform tolerance in the controller server was obtained from costmap->getTransformTolerance. I think it makes more sense for the server and its plugins to share the same tolerance, so I moved this to the controller level.

Why not have it still acquire it from costmap2D, just stored and used at the controller server level? I suppose I prefer less parameters to more, but I'm OK either way.

We have different pruned_plan_end for MPPI and RPP,

Do both - first after the integrated distance, as long as that distance is within the costmap bounds.

*/
~ParameterHandler();

std::mutex & getMutex() {return mutex_;}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this being properly locked when needed in the main function(s) so that dynamic parameters aren't being updated during execution?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes I forgot to add this, will add it in the next update

@mini-1235
Copy link
Contributor Author

Ah ok. That makes sense for the goal checker, though probably not the other elements right? When enforcing inversions is off, its the same either way since we just prune to the prune distance / costmap bounds. When is it enabled, then we prune to that which we want from the control algorithm's perspective, but not the goal checker.

Yes, when it is on, the distance to the local goal can become very small. That's why I think this local goal is not suitable to use in the goal checker

Why not have it still acquire it from costmap2D,

For the controller plugins as well?

Do both - first after the integrated distance, as long as that distance is within the costmap bounds.

Not sure if I understand this, can you elaborate?

@SteveMacenski
Copy link
Member

For the controller plugins as well?

Isn't that in effect what is done today?

Not sure if I understand this, can you elaborate?

Basically combine the two:

//TODO: For RPP and graceful we don't have prune distance, maybe we need to support two kinds of pruned_plan_end here
// by parameter?
if (1){
pruned_plan_end = nav2_util::geometry_utils::first_after_integrated_distance(
closest_point, global_plan_up_to_inversion_.poses.end(), params_->prune_distance);
}
else{
pruned_plan_end = std::find_if(
closest_point, global_plan_up_to_inversion_.poses.end(),
[&](const auto & global_plan_pose) {
return euclidean_distance(global_plan_pose, robot_pose) > max_costmap_extent;
});
}
. Find the first after the integrated distance. If its outside of the costmap bounds, then wind back until its within the costmap bounds. If its off the local costmap, then we cannot consider them for control since they're not validly known

@SteveMacenski
Copy link
Member

A good suggestion I received today: It would be great to make the path handler itself a plugin so that other users can replace this implementation if they see fit. A nice side effect is it makes us have to think a bit more about the API interfaces for it to make sure its generally good for a broad range of purposes and include all the information for the APIs other implementations may want that we have access to.

Another would be possibly changing the pruning distance to be proportional to time instead, to prune the distance set out by that time by the maximum velocity. That way it wasn't something that needed to be tuned for changing velocity limits.

Finally, maybe it would be good to provide feedback about the current idx of the path we're on to use in the BT Navigator for computing ETA, path length remaining, and so forth. That way we handle the issue of path looping using the wrong index globally

@mini-1235
Copy link
Contributor Author

I will think about it and reply tomorrow

Copy link
Member

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think you have some settings for 4 spaces rather than 2 which have affected a number of file's indentations

* @brief Creates list of BT ports
* @return BT::PortsList Containing basic ports along with node-specific ports
*/
static BT::PortsList providedPorts()
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Per usual: new BT nodes, parameters, etc should have configuration guide updates and migration guide entries. For new BT nodes and plugins, add them to the Navigation Plugins table

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Will add when this PR is close to merge

* @param velocity Current robot velocity
* @param goal_checker Pointer to the current goal checker the task is utilizing
* @param transformed_global_plan The global plan after being processed by the path handler
* @param goal The last pose of the global plan
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd call this 'global_goal' and offer a PoseStamped so the frame information is retained.

* path segments the robot has already traversed and transforming the remaining,
* relevant portion of the path into the costmap's global or base frame.
*/
class PathHandler
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe ControllerPathHandler since if this is outside of hte context of the controller server, it would be good to make sure its clear the intent of how this is to be used

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think PathHandler is better here, as we only have GoalChecker, ProgressChecker instead of ControllerGoalChecker and ControllerProgressChecker, it would be strange to see something like

controller_server:
  ros__parameters:
    goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
    controller_path_handler_plugins: ["path_handler"]

(?)

}

/** @brief Returns the delay in transform (tf) data that is tolerable in seconds */
double getTransformTolerance() const
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd leave this as is in case others are using this.

Copy link
Contributor Author

@mini-1235 mini-1235 Oct 12, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I noticed #4907 when refactoring the dynamic parameters in controller server. I think my current approach is problematic since the server and the plugin share the same parameter (similar to controller frequency we removed in #4907). I guess your suggestion earlier is better in this case for both server and plugin?

Why not have it still acquire it from costmap2D, just stored and used at the controller server level?

string controller_id
string goal_checker_id
string progress_checker_id
string path_handler_id
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Make sure to expose this in the Simple Commander API as well

Also in the example uses of the FollowPath BT node + in the Nav2 default BT XMLs (where ever existing ones have the other Progress Checker / Goal Checker Selectors)

@mini-1235
Copy link
Contributor Author

mini-1235 commented Oct 10, 2025

I think you have some settings for 4 spaces rather than 2 which have affected a number of file's indentations

Probably happened when I copy + paste some old files, maybe I should open another PR to format them all first?

Copy link
Contributor

mergify bot commented Oct 12, 2025

This pull request is in conflict. Could you fix it @mini-1235?

Signed-off-by: mini-1235 <[email protected]>
Signed-off-by: mini-1235 <[email protected]>
Copy link
Contributor

mergify bot commented Oct 12, 2025

@mini-1235, your PR has failed to build. Please check CI outputs and resolve issues.
You may need to rebase or pull in main due to API changes (or your contribution genuinely fails).

Copy link
Contributor

mergify bot commented Oct 13, 2025

@mini-1235, your PR has failed to build. Please check CI outputs and resolve issues.
You may need to rebase or pull in main due to API changes (or your contribution genuinely fails).

@mini-1235
Copy link
Contributor Author

mini-1235 commented Oct 15, 2025

Test Graceful/MPPI/RPP/DWB on different platform (Ackermann, Differential) with different params

I have been testing this PR for a few days, updating my result here:

  1. For Navigate through poses terminates pre-maturely when incidentally passing over final poses #4304:
  • I think DWB does not work well with navthroughposes mode, but this is not the target of this PR, so I am going to ignore it
  • RPP/Graceful/MPPI never "terminate pre-maturely when incidentally passing over final poses" when configured correctly
  • However, when configured incorrectly, e.g. Navfn + Enable enforce_path_inversion in path handler, we might detect a cusp according to the condition here
    if (dot_product < 0.0f) {
    return idx + 1;
    }
    , I tried to log the pose:
[component_container_isolated-10] [idx-1] 9.55 7.8
[component_container_isolated-10] [idx] 9.55092 7.77662 (first goal)
[component_container_isolated-10] [idx + 1] 9.6 7.8 (first pose after goal)

Note that this only happens in NavThroughPoses mode

  1. When pairing with feasible planners, RPP/Graceful/MPPI works fine. (Previously, RPP/Graceful did not have this feature, this PR adds it).

  2. When having looping path like [MPPI] Fix transformed path oscillations #3443, Graceful/RPP used to oscillate before this PR, since I am using integrated distance in simple path handler, this PR fixes the issue. However, when navigating with MPPI, I am unable to reach the goal. I suspect the issue is more related to the critics than the path handler, I will check again tomorrow

Signed-off-by: mini-1235 <[email protected]>
std::bind(
&ParameterHandler::validateParameterUpdatesCallback,
this, std::placeholders::_1));
post_set_params_handler_ = node->add_post_set_parameters_callback(
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Create the post- callback first so that it is ready anytime the on-set callback could be triggered (could cause a really rare race condition issue)

@SteveMacenski
Copy link
Member

For #4304:

Why so on DWB? If the goal checker / path given is restricted to the local time horizon, it shouldn't know anything about far away loops and so forth once a path segment leaves the local costmap bounds / search distance (like MPPI, RPP, etc).

However, when configured incorrectly, e.g. Navfn + Enable enforce_path_inversion in path handler, we might detect a cusp according to the condition here

Yeah that is true. Setting enforce_path_inversion to false by default and making an note about that in the configuration guide and in the Nav2 yaml file would be good since that's an annoying one.

@mini-1235
Copy link
Contributor Author

Why so on DWB? If the goal checker / path given is restricted to the local time horizon, it shouldn't know anything about far away loops and so forth once a path segment leaves the local costmap bounds / search distance (like MPPI, RPP, etc).

Let me clarify, consider the following situation:

Oct.16.2025.Video.mp4

where the first goal overlaps with the third goal. When the robot reaches the final goal, the path handler still generates a local plan (blue path), and the goal checker doesn’t report that the goal has been reached. However, due to the goal critic, the robot can’t move further

@SteveMacenski
Copy link
Member

SteveMacenski commented Oct 16, 2025

Oh. Can we add that similar constraint from the goal checker for the path length into DWB? That should be a 3 liner easy enough to resolve, no?

When you have a chance, comment on any open review items. I think some are done / irrelevant now, but might be good to see what's still open and if they're still important to think about.

Super happy and excited by this! This is a great refactor and going to fix a pretty long-standing issue with NavigateThroughPoses that I'm really excited for ❤️

@mini-1235
Copy link
Contributor Author

mini-1235 commented Oct 16, 2025

Oh. Can we add that similar constraint from the goal checker for the path length into DWB? That should be a 3 liner easy enough to resolve, no?

I think we have 3 critics that are related to goal:

  • RotateToGoal
  • GoalAlign
  • GoalDist

I added an if condition in those critics:

if (local_path_length > path_length_tolerance)
    skip this critic

However, the robot ends up staying still instead of navigating toward the goal. From my understanding, the GoalAlign and GoalDist are the critics that incentivizes the robot to make progress, so I shouldn't add the condition in these critic. I also tried adding this condition only to RotateToGoal, which works and resolves my issue above. Is my understanding correct here?

When you have a chance, comment on any open review items. I think some are done / irrelevant now, but might be good to see what's still open and if they're still important to think about.

I left a comment here #5446 (comment). For other comments, I believe I have replied to your questions as well, could you please check and see if I have addressed your concerns?

I will do a self-review tomorrow to make sure I didn't miss anything, and also format the files :)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

3 participants