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

@mergify
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

@mergify
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!

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?

Copy link
Member

Choose a reason for hiding this comment

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

Correct!

@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

@mergify
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

@mergify
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

Copy link
Member

Choose a reason for hiding this comment

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

@mini-1235 is this still open?

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 don't think so, I have added in ControllerServer L424

@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

Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
@mini-1235
Copy link
Contributor Author

Oops, forgot to format files

Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
@mini-1235
Copy link
Contributor Author

mini-1235 commented Oct 17, 2025

I think ament_uncrustify --reformat . automatically inserts newlines and indents 4 spaces whenever a line exceeds 100 characters. It would be great if we could have an uncrustify.cfg that only enforces 2-space indentation instead of 4

@SteveMacenski
Copy link
Member

SteveMacenski commented Oct 21, 2025

It didn't used to do that ... I wonder if the ament_uncrustify format got corrupted in that case. it didn't used to do that and that was the profile in use.

is there anything above you want me to take a look at (except that last comment)? I wasn't sure if I was waiting or you wanted me to take a look again.

@mergify
Copy link
Contributor

mergify bot commented Oct 21, 2025

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

@mini-1235
Copy link
Contributor Author

It didn't used to do that ... I wonder if the ament_uncrustify format got corrupted in that case. it didn't used to do that and that was the profile in use.

I am not familiar with uncrustify, will take a look when I have time. For this PR, I will just update it manually.

I wasn't sure if I was waiting or you wanted me to take a look again.

Yes, please take another look when you have time. I have updated things accordingly

Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
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.

Also check out CI, a number of tests don't have results or have failures

There are a number of open items above (make sure to expand the hidden topics since this is so long) and I commented on all of them with responses (if not closing due to completion).

params_file = os.path.join(nav2_bringup_dir, 'params/nav2_params.yaml')

# Replace the `use_astar` setting on the params file
param_substitutions = {
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 change?

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 substitutes the parameter prune_distance and forward_prune_distance in DWB. Since we are centralizing it in controller server, I don't think we have these two parameters anymore in DWB

xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
path_handler:
plugin: "nav2_controller::SimplePathHandler"
Copy link
Member

Choose a reason for hiding this comment

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

Add some params to this to be fully described? (here, other similar files in nav2 tests + Nav2 bringup)

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 in next update

row_3_label_layout_->addWidget(new QLabel("Progress Checker"));
row_3_layout_->addWidget(progress_checker_);
row_3_label_layout_->addWidget(new QLabel("Path Handler"));
row_3_layout_->addWidget(path_handler_);
Copy link
Member

Choose a reason for hiding this comment

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

Does the layout need to adapt due to the additional field (i.e. larger size?)

Copy link
Contributor Author

Choose a reason for hiding this comment

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

image

I don't think so, this looks fine for me

results4);
}

class TransformGlobalPlanTest : public ::testing::Test
Copy link
Member

Choose a reason for hiding this comment

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

Were all the relevant tests for full coverage of the new plugin transferred?

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 in next update

double SimplePathHandler::getCostmapMaxExtent() const
{
const double max_costmap_dim_meters = std::max(
costmap_ros_->getCostmap()->getSizeInCellsX(),
Copy link
Member

Choose a reason for hiding this comment

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

I don't think that semantic difference is really being used here -- I think you can simply use the Meters API

*/
~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.

@mini-1235 is this still open?

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.

Correct!

current_path_ = path;
primary_controller_->setPlan(path);
path_updated_ = rotate_to_heading_once_ ? isGoalChanged(raw_global_path) : true;
current_path_ = raw_global_path;
Copy link
Member

Choose a reason for hiding this comment

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

Should we use the new computeVelocityCommands for this instead for setting the current path?

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 this is a special case where the controller needs the full global plan, no?

// Find the first point at least sampling distance away
for (unsigned int i = 1; i != current_path_.poses.size(); i++) {
dx = current_path_.poses[i].pose.position.x - start.position.x;
dy = current_path_.poses[i].pose.position.y - start.position.y;
if (hypot(dx, dy) >= forward_sampling_distance_) {
current_path_.poses[i].header.frame_id = current_path_.header.frame_id;
current_path_.poses[i].header.stamp = clock_->now(); // Get current time transformation
return current_path_.poses[i];
}

auto transformed_plan = path_handler_->transformGlobalPlan(
pose, params_->max_robot_pose_search_dist, params_->interpolate_curvature_after_goal);
global_path_pub_->publish(transformed_plan);
// Transform the plan from costmap's global frame to robot base frame
Copy link
Member

Choose a reason for hiding this comment

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

This process seems like it might be a nice utility to have in the path handler plugin itself. Given a path, convert it to another frame (i.e. the base frame) at a timestamp. If not in the path handler class, then maybe as a path utils for nav2_utils

goal_dist_tolerance_ = pose_tolerance.position.x;
}

// Transform the plan from costmap's global frame to robot base frame
Copy link
Member

Choose a reason for hiding this comment

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

That util / path handler API could then be used here too!

Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
@codecov
Copy link

codecov bot commented Oct 25, 2025

Codecov Report

❌ Patch coverage is 88.83827% with 49 lines in your changes missing coverage. Please review.

Files with missing lines Patch % Lines
nav2_controller/plugins/simple_path_handler.cpp 84.54% 17 Missing ⚠️
nav2_controller/src/controller_server.cpp 81.48% 15 Missing ⚠️
nav2_controller/src/parameter_handler.cpp 90.00% 12 Missing ⚠️
...m_controller/src/nav2_rotation_shim_controller.cpp 66.66% 2 Missing ⚠️
...ehavior_tree/plugins/action/follow_path_action.cpp 75.00% 1 Missing ⚠️
...v2_graceful_controller/src/graceful_controller.cpp 75.00% 1 Missing ⚠️
...ntroller/src/regulated_pure_pursuit_controller.cpp 75.00% 1 Missing ⚠️
Files with missing lines Coverage Δ
...ehavior_tree/plugins/action/follow_path_action.hpp 100.00% <100.00%> (ø)
...tree/plugins/action/path_handler_selector_node.hpp 100.00% <100.00%> (ø)
...tree/plugins/action/path_handler_selector_node.cpp 100.00% <100.00%> (ø)
...ller/include/nav2_controller/controller_server.hpp 100.00% <100.00%> (ø)
...ller/include/nav2_controller/parameter_handler.hpp 100.00% <100.00%> (ø)
.../nav2_controller/plugins/position_goal_checker.hpp 100.00% <ø> (ø)
...de/nav2_controller/plugins/simple_path_handler.hpp 100.00% <100.00%> (ø)
nav2_controller/plugins/position_goal_checker.cpp 100.00% <100.00%> (+40.00%) ⬆️
nav2_controller/plugins/simple_goal_checker.cpp 100.00% <100.00%> (ø)
nav2_controller/plugins/stopped_goal_checker.cpp 100.00% <100.00%> (ø)
... and 28 more

... and 17 files with indirect coverage changes

🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.

Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
@mini-1235 mini-1235 mentioned this pull request Oct 31, 2025
8 tasks
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