-
Notifications
You must be signed in to change notification settings - Fork 1.7k
New Goal checker: AxisGoalChecker #5746
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
New Goal checker: AxisGoalChecker #5746
Conversation
SteveMacenski
left a comment
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Beyond anything else; I think this configuration guide entry will need a graphic to explain the value / when it should be used. I don't think this is immediately clear and could be easily misunderstood, so I think that element more than most is key.
I agree on naming. How about (and maybe not any better):
segment_axis_goal_tolerance-> Why not just leave as goal_tolerance or whatever it is now? It just has a different meaning for this critic (i.e. computed differently)AxisGoalChecker-> PathApproachAngleGoalChecker?
Renamed
Still not sure about that one, I will get started with the documentation and see if I get more inspired (I still want to reflect that we check the pregression along an axis or line) |
|
Also: maybe instead of giving it the second-to-last point and modifying the API for just that information, how about giving the path in general to the goal checker so that it can use the full path instead (and this particular one just uses the second to last). It also pushes the changes into the specific new plugin rather than the core server - which I like from a separation of concerns perspective. ... I think there's a PR somewhere that actually was making that change some time ago for the goal checker to check on the path length as part of goal checking to deal with path looping. So this is very much aligned. #5446 |
|
PS @mini-1235 |
Oh that would be much better indeed !
Nice! Let me know the progress. And I will pick up this PR once #5446 will be done then. Putting it to draft in the meantime. Also because there may be some trigonometry edge cases. |
|
(Please ignore any shenanigans happening on this branch until further notice) |
60a16b6 to
257100a
Compare
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Pull request overview
This PR introduces a new goal checker plugin called AxisGoalChecker, designed specifically for validating goals in line path scenarios. The checker validates goal achievement based on the robot's projected distance along the axis formed by the last two poses of the path, rather than using standard Euclidean distance.
Key Changes:
- New
AxisGoalCheckerplugin that projects robot position onto the path's final segment axis - Configurable overshoot behavior via
is_overshoot_validparameter for handling localization jumps - Fallback to standard distance checking for single-pose paths
Reviewed changes
Copilot reviewed 4 out of 4 changed files in this pull request and generated 9 comments.
| File | Description |
|---|---|
| nav2_controller/plugins/axis_goal_checker.cpp | Implementation of the new goal checker with axis-based projection logic |
| nav2_controller/include/nav2_controller/plugins/axis_goal_checker.hpp | Header file defining the AxisGoalChecker class interface |
| nav2_controller/CMakeLists.txt | Build configuration for the new axis_goal_checker library |
| nav2_controller/plugins.xml | Plugin registration for the AxisGoalChecker |
nav2_controller/include/nav2_controller/plugins/axis_goal_checker.hpp
Outdated
Show resolved
Hide resolved
nav2_controller/include/nav2_controller/plugins/axis_goal_checker.hpp
Outdated
Show resolved
Hide resolved
| pose_tolerance.orientation = | ||
| nav2_util::geometry_utils::orientationAroundZAxis(M_PI_2); |
Copilot
AI
Jan 5, 2026
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
The orientation tolerance is set to M_PI_2 (90 degrees), which doesn't align with the goal checker's design that ignores orientation entirely. For consistency with PositionGoalChecker (which also doesn't check orientation), this should be set to an identity quaternion (x=0, y=0, z=0, w=1) to indicate that orientation is not checked, rather than using an arbitrary angle value.
| pose_tolerance.orientation = | |
| nav2_util::geometry_utils::orientationAroundZAxis(M_PI_2); | |
| // Identity quaternion indicates that orientation is not checked | |
| pose_tolerance.orientation.x = 0.0; | |
| pose_tolerance.orientation.y = 0.0; | |
| pose_tolerance.orientation.z = 0.0; | |
| pose_tolerance.orientation.w = 1.0; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
pose_tolerance.orientation isn't actually used anywhere but conceptually shouldn't it be nav2_util::geometry_utils::orientationAroundZAxis(M_PI) to indicate that orientation is completely unconstrained. @doisyg
Codecov Report✅ All modified and coverable lines are covered by tests.
... and 30 files with indirect coverage changes 🚀 New features to boost your workflow:
|
|
Send me a note on slack when you want me to take a look at this |
|
Today I rebased it on main, adapting it to the centralizing of the path handler. Tomorrow I'll look into it more in details for polishing. You can however already take a look - it was already tested by @doisyg and in use since some months |
|
It generally look fine to me, I just think some illustrations and/or expanded doxygen description (which can be used in the nav2 docs later as well) to explain how / why this is useful are necessary. |
|
Some quick test here would be nice. Otherwise, make sure it still works for your needs after recent changes but LGTM |
Yes, they're written but some fail. Probably tomorrow |
|
Fix DCO as well :-) Then we can merge the pair |
Signed-off-by: Tony Najjar <[email protected]>
Co-authored-by: Copilot <[email protected]> Signed-off-by: Tony Najjar <[email protected]> Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
e5791f9 to
e4b4352
Compare
|
@doisyg ready to take a look |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Pull request overview
Copilot reviewed 6 out of 6 changed files in this pull request and generated 12 comments.
nav2_controller/include/nav2_controller/plugins/axis_goal_checker.hpp
Outdated
Show resolved
Hide resolved
Co-authored-by: Copilot <[email protected]> Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Co-authored-by: Copilot <[email protected]> Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Pull request overview
Copilot reviewed 6 out of 6 changed files in this pull request and generated 7 comments.
| double cross_track_distance = distance_to_goal * sin(projection_angle); | ||
|
|
||
| if (is_overshoot_valid_) { | ||
| return along_path_distance < along_path_tolerance_ && |
Copilot
AI
Jan 7, 2026
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
The overshoot validation logic appears to have a bug. When is_overshoot_valid_ is true, the condition along_path_distance < along_path_tolerance_ will always be true for any overshoot (negative along_path_distance), regardless of how far past the goal the robot is. This means the test at line 350-353 which expects any overshoot to be valid is actually revealing a bug rather than correct behavior. The condition should likely be along_path_distance < along_path_tolerance_ && along_path_distance > -along_path_tolerance_ to constrain overshoots within the tolerance range, or simply remove the absolute value check but keep a reasonable bounds check.
| return along_path_distance < along_path_tolerance_ && | |
| return along_path_distance < along_path_tolerance_ && | |
| along_path_distance > -along_path_tolerance_ && |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
intended behavior but FYI @doisyg
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Pull request overview
Copilot reviewed 6 out of 6 changed files in this pull request and generated 14 comments.
* Add axis goal checker Signed-off-by: Tony Najjar <[email protected]> * Apply suggestion from @Copilot Co-authored-by: Copilot <[email protected]> Signed-off-by: Tony Najjar <[email protected]> Signed-off-by: Tony Najjar <[email protected]> * PR comments Signed-off-by: Tony Najjar <[email protected]> * revert Signed-off-by: Tony Najjar <[email protected]> * rename + add param Signed-off-by: Tony Najjar <[email protected]> * rename Signed-off-by: Tony Najjar <[email protected]> * simplify Signed-off-by: Tony Najjar <[email protected]> * remove import Signed-off-by: Tony Najjar <[email protected]> * add tests Signed-off-by: Tony Najjar <[email protected]> * Apply suggestions from code review Co-authored-by: Copilot <[email protected]> Signed-off-by: Tony Najjar <[email protected]> * add path_length_tolerance as dynamic param Signed-off-by: Tony Najjar <[email protected]> * Apply suggestion from @Copilot Co-authored-by: Copilot <[email protected]> Signed-off-by: Tony Najjar <[email protected]> * handle case where points are very close Signed-off-by: Tony Najjar <[email protected]> * handle atan2(0,0) and add tests Signed-off-by: Tony Najjar <[email protected]> * fix params Signed-off-by: Tony Najjar <[email protected]> * PR fixes Signed-off-by: Tony Najjar <[email protected]> --------- Signed-off-by: Tony Najjar <[email protected]> Signed-off-by: Tony Najjar <[email protected]> Co-authored-by: Tony Najjar <[email protected]> Co-authored-by: Tony Najjar <[email protected]> Co-authored-by: Copilot <[email protected]>
* Add axis goal checker Signed-off-by: Tony Najjar <[email protected]> * Apply suggestion from @Copilot Co-authored-by: Copilot <[email protected]> Signed-off-by: Tony Najjar <[email protected]> Signed-off-by: Tony Najjar <[email protected]> * PR comments Signed-off-by: Tony Najjar <[email protected]> * revert Signed-off-by: Tony Najjar <[email protected]> * rename + add param Signed-off-by: Tony Najjar <[email protected]> * rename Signed-off-by: Tony Najjar <[email protected]> * simplify Signed-off-by: Tony Najjar <[email protected]> * remove import Signed-off-by: Tony Najjar <[email protected]> * add tests Signed-off-by: Tony Najjar <[email protected]> * Apply suggestions from code review Co-authored-by: Copilot <[email protected]> Signed-off-by: Tony Najjar <[email protected]> * add path_length_tolerance as dynamic param Signed-off-by: Tony Najjar <[email protected]> * Apply suggestion from @Copilot Co-authored-by: Copilot <[email protected]> Signed-off-by: Tony Najjar <[email protected]> * handle case where points are very close Signed-off-by: Tony Najjar <[email protected]> * handle atan2(0,0) and add tests Signed-off-by: Tony Najjar <[email protected]> * fix params Signed-off-by: Tony Najjar <[email protected]> * PR fixes Signed-off-by: Tony Najjar <[email protected]> --------- Signed-off-by: Tony Najjar <[email protected]> Signed-off-by: Tony Najjar <[email protected]> Co-authored-by: Tony Najjar <[email protected]> Co-authored-by: Tony Najjar <[email protected]> Co-authored-by: Copilot <[email protected]> Signed-off-by: lotusymt <[email protected]>
Basic Info
Description of contribution in a few bullet points
This pull request adds a new goal checker plugin called AxisGoalChecker to the nav2_controller package. The AxisGoalChecker checks if the robot has reached the goal by evaluating progress along the axis defined by the last segment of the path, with configurable tolerances and an option to allow overshoot.
Description of documentation updates required from your changes
ros-navigation/docs.nav2.org#838
Description of how this change was tested
Multiple days running straight paths ("segments") in a huge warehouses. And then rebased on
main.Future work that may be required in bullet points
For Maintainers:
backport-*.