Skip to content
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

[RotationShimController] rotate also on short paths #4290

Merged
merged 1 commit into from
May 2, 2024

Conversation

gennartan
Copy link
Contributor

When the path is shorter than ´forward_sampling_distance´ the rotatitonShimController would directly give control to the primary controller to navigate to the goal. This would lead to the exact behavior that was tried to be fixed by the rotationShimController: "The result is an awkward, stuttering, or whipping around behavior" [1]. It often resulted in navigation failure.

In this case, the controller should try to rotate towards the last point of the path, so that the primary controller can have a better starting orientation.

[1] https://navigation.ros.org/tuning/index.html#rotate-in-place-behavior


Basic Info

Info Please fill out this column
Ticket(s) this addresses #4281
Primary OS tested on Ubuntu 20.04 / 22.04
Robotic platform tested on Gazebo simulation - custom hardware
Does this PR contain AI generated software? No

Description of contribution in a few bullet points

  • Let the rotationShimController rotate the robot when the path length is shorter than ´forward_sampling_distance´ (this allow the robot to have the correct orientation when the requested goal is really close)

Description of documentation updates required from your changes

Future work that may be required in bullet points

For Maintainers:

  • Check that any new parameters added are updated in navigation.ros.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

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.

Would it be sensible in L179 to consider increasing the minimum size of path to 3 or 4?

When the path is shorter than ´forward_sampling_distance´ the
rotatitonShimController would directly give control to the primary
controller to navigate to the goal. This would lead to the exact
behavior that was tried to be fixed by the rotationShimController: "The
result is an awkward, stuttering, or whipping around behavior" [1]. It
often resulted in navigation failure.

In this case, the controller should try to rotate towards the last point
of the path, so that the primary controller can have a better starting
orientation.

[1] https://navigation.ros.org/tuning/index.html#rotate-in-place-behavior
@gennartan
Copy link
Contributor Author

Would it be sensible in L179 to consider increasing the minimum size of path to 3 or 4?

I think it makes sense to keep to 2.
If the path resolution is low, two points can still be far from each other in a path. As an example, my current project was using a path resolution of 0.2m. And we don't want the path resolution to change the behavior of this node.

@gennartan gennartan closed this May 2, 2024
@gennartan gennartan reopened this May 2, 2024
@SteveMacenski
Copy link
Member

Sorry about the toggled CI, I was testing some changes to the CI bots for the org change. Once CI comes back happy I can merge

@SteveMacenski SteveMacenski merged commit de19a7b into ros-navigation:main May 2, 2024
12 of 14 checks passed
@SteveMacenski
Copy link
Member

@gennartan, a bug was identified by @NikolasE in 94d3a9d

double angular_distance_to_heading = std::abs(goal_yaw - pose_yaw);

I think this will fail if goal_yaw is -pi and pose_yaw pi. Robot is already aligned, but I assume this could trigger a full rotation on the spot.

This could help:
https://github.com/ros/angles/blob/54ad72b0ce473a2e1d98da447898bf2fcd36519f/angles/include/angles/angles.h#L104C72-L104C73

enricosutera pushed a commit to enricosutera/navigation2 that referenced this pull request May 19, 2024
)

When the path is shorter than ´forward_sampling_distance´ the
rotatitonShimController would directly give control to the primary
controller to navigate to the goal. This would lead to the exact
behavior that was tried to be fixed by the rotationShimController: "The
result is an awkward, stuttering, or whipping around behavior" [1]. It
often resulted in navigation failure.

In this case, the controller should try to rotate towards the last point
of the path, so that the primary controller can have a better starting
orientation.

[1] https://navigation.ros.org/tuning/index.html#rotate-in-place-behavior

Signed-off-by: enricosutera <[email protected]>
SteveMacenski pushed a commit that referenced this pull request May 23, 2024
When the path is shorter than ´forward_sampling_distance´ the
rotatitonShimController would directly give control to the primary
controller to navigate to the goal. This would lead to the exact
behavior that was tried to be fixed by the rotationShimController: "The
result is an awkward, stuttering, or whipping around behavior" [1]. It
often resulted in navigation failure.

In this case, the controller should try to rotate towards the last point
of the path, so that the primary controller can have a better starting
orientation.

[1] https://navigation.ros.org/tuning/index.html#rotate-in-place-behavior
SteveMacenski added a commit that referenced this pull request May 23, 2024
* Scale cost critic's weight when dynamically updated (#4246)

* Scale cost critic's weight when dynamically updated

Signed-off-by: pepisg <[email protected]>

* sign off

Signed-off-by: pepisg <[email protected]>

---------

Signed-off-by: pepisg <[email protected]>

* Add expanding the ~/ to the full home dir of user in the path to the map yaml.  (#4258)

* Add user home expander of home sequence

Signed-off-by: Wiktor Bajor <[email protected]>

* Add passing home dir as string instead of const char*

Signed-off-by: Wiktor Bajor <[email protected]>

* Add docs

Signed-off-by: Wiktor Bajor <[email protected]>

* Fix function declaration

Signed-off-by: Wiktor Bajor <[email protected]>

* Fix linter issues

Signed-off-by: Wiktor Bajor <[email protected]>

* Uncrustify linter

Signed-off-by: Wiktor Bajor <[email protected]>

* Uncrustify linter

Signed-off-by: Wiktor Bajor <[email protected]>

* Uncrustify linter: remove remove whitespace

Signed-off-by: Wiktor Bajor <[email protected]>

---------

Signed-off-by: Wiktor Bajor <[email protected]>

* Implement Critic for Velocity Deadband Hardware Constraints (#4256)

* Adding new velocity deadband critic.

- add some tests
- cast double to float
- add new features from "main" branch

- fix formating

- add cost test
- fix linting issue
- add README

Signed-off-by: Denis Sokolov <[email protected]>

* Remove velocity deadband critic from defaults

Signed-off-by: Denis Sokolov <[email protected]>

* remove old weight

Signed-off-by: Denis Sokolov <[email protected]>

* fix velocity deadband critic tests

Signed-off-by: Denis Sokolov <[email protected]>

---------

Signed-off-by: Denis Sokolov <[email protected]>

* removing clearable layer param (unused) (#4280)

* provide message validation check API (#4276)

* provide validation_message.hpp

Signed-off-by: goes <[email protected]>

* fix typo

Signed-off-by: goes <[email protected]>

* add test_validation_messages.cpp

Signed-off-by: goes <[email protected]>

* change include-order

Signed-off-by: goes <[email protected]>

* reformat

Signed-off-by: goes <[email protected]>

* update test

Signed-off-by: goes <[email protected]>

---------

Signed-off-by: goes <[email protected]>
Co-authored-by: goes <[email protected]>

* [RotationShimController] rotate also on short paths (#4290)

When the path is shorter than ´forward_sampling_distance´ the
rotatitonShimController would directly give control to the primary
controller to navigate to the goal. This would lead to the exact
behavior that was tried to be fixed by the rotationShimController: "The
result is an awkward, stuttering, or whipping around behavior" [1]. It
often resulted in navigation failure.

In this case, the controller should try to rotate towards the last point
of the path, so that the primary controller can have a better starting
orientation.

[1] https://navigation.ros.org/tuning/index.html#rotate-in-place-behavior

* Add footprint clearing for static layer (#4282)

* Add footprint clearing for static layer

Signed-off-by: Tony Najjar <[email protected]>

* fix flckering

---------

Signed-off-by: Tony Najjar <[email protected]>

* Fix #4268 (#4296)

Signed-off-by: Steve Macenski <[email protected]>

* Fix undefined symbols in `libpf_lib.so` (#4312)

When I build `nav2_amcl` with `-Wl,--no-undefined` I noticed
`libpf_lib.so` has undefined symbols. This PR correctly links
`libpf_lib.so` to `libm` so all symbols can be found.

You can verify this by executing the following command:
```
ldd -r ./build/nav2_amcl/src/pf/libpf_lib.so
	linux-vdso.so.1 (0x00007ffd1f8c0000)
	libc.so.6 => /lib/x86_64-linux-gnu/libc.so.6 (0x000074e909a00000)
	/lib64/ld-linux-x86-64.so.2 (0x000074e909e60000)
undefined symbol: ceil	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: atan2	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: sin	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: hypot	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: cos	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: log	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: sqrt	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: floor	(./build/nav2_amcl/src/pf/libpf_lib.so)
```

Signed-off-by: Ramon Wijnands <[email protected]>

* msg validation check for `/initialpose`  in `nav2_amcl` (#4301)

* add validation check for PoseWithCovarianceStamped

Signed-off-by: goes <[email protected]>

* remove rebundant check before

Signed-off-by: goes <[email protected]>

* reformat

Signed-off-by: goes <[email protected]>

* typo fixed

Signed-off-by: goes <[email protected]>

* change the type-name

Signed-off-by: goes <[email protected]>

* update test

Signed-off-by: goes <[email protected]>

* reformat

Signed-off-by: goes <[email protected]>

* .

Signed-off-by: goes <[email protected]>

* add comment

Signed-off-by: goes <[email protected]>

* update comment

Signed-off-by: goes <[email protected]>

* change header

Signed-off-by: goes <[email protected]>

* update test

Signed-off-by: goes <[email protected]>

* typo fixed

Signed-off-by: goes <[email protected]>

---------

Signed-off-by: goes <[email protected]>
Co-authored-by: goes <[email protected]>

* 4320: Changed precision of calculations of the HybridNode MotionTable::getClosestAngularBin. (#4324)

Signed-off-by: Krzysztof Pawełczyk <[email protected]>
Co-authored-by: Krzysztof Pawełczyk <[email protected]>

* [LifecycleNode] add bond_heartbeat_period (#4342)

* add bond_heartbeat_period


Signed-off-by: Guillaume Doisy <[email protected]>

* lint

Signed-off-by: Guillaume Doisy <[email protected]>

---------

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* Update path_longer_on_approach.cpp (#4344)

Fix the bug that isPathUpdated function will return false for the reason that it compare the timestaped between new path and old path's last pose

Signed-off-by: StetroF <[email protected]>

* [LifecycleManagerClient] clean set_initial_pose and navigate_to_pose (#4346)

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* Move projectState after getPointsInside (#4356)

* Modify test to check fix

Signed-off-by: Brice <[email protected]>

* Add static polygon check before simulation

Signed-off-by: Brice <[email protected]>

---------

Signed-off-by: Brice <[email protected]>

* adding final pose in analytic expansion to check (#4353)

* bump iron to 1.2.8

* fix merge conflict resolution

---------

Signed-off-by: pepisg <[email protected]>
Signed-off-by: Wiktor Bajor <[email protected]>
Signed-off-by: Denis Sokolov <[email protected]>
Signed-off-by: goes <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Ramon Wijnands <[email protected]>
Signed-off-by: Krzysztof Pawełczyk <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
Signed-off-by: StetroF <[email protected]>
Signed-off-by: Brice <[email protected]>
Co-authored-by: Pedro Alejandro González <[email protected]>
Co-authored-by: Wiktor Bajor <[email protected]>
Co-authored-by: Sokolov Denis <[email protected]>
Co-authored-by: GoesM <[email protected]>
Co-authored-by: goes <[email protected]>
Co-authored-by: Saitama <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Ramon Wijnands <[email protected]>
Co-authored-by: AzaelCicero <[email protected]>
Co-authored-by: Krzysztof Pawełczyk <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: StetroF <[email protected]>
Co-authored-by: BriceRenaudeau <[email protected]>
Manos-G pushed a commit to Manos-G/navigation2 that referenced this pull request Aug 1, 2024
)

When the path is shorter than ´forward_sampling_distance´ the
rotatitonShimController would directly give control to the primary
controller to navigate to the goal. This would lead to the exact
behavior that was tried to be fixed by the rotationShimController: "The
result is an awkward, stuttering, or whipping around behavior" [1]. It
often resulted in navigation failure.

In this case, the controller should try to rotate towards the last point
of the path, so that the primary controller can have a better starting
orientation.

[1] https://navigation.ros.org/tuning/index.html#rotate-in-place-behavior
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

RotationShimController does not rotate when goal is closer than forward_sampling_distance
2 participants