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

Fix Misplaced Footprint on Static Layer #4911

Open
wants to merge 2 commits into
base: main
Choose a base branch
from

Conversation

HovorunBh
Copy link
Contributor


Basic Info

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

Description of contribution in a few bullet points

I noticed that the robot footprint clearing is clearing the wrong spot on the local costmap. The offset is exactly odom->map TF
My static_layer on local costmap (rolling_window=True) subscribes to occupancy grid in 'map' frame
Screenshot from 2025-02-10 02-38-32

The robot pose received by the static layer is in the costmap's global frame, but it should be in the frame of the map it subscribes to, because otherwise the static layer is transformed by odom->map TF and the footprint ends up in the wrong place:

Description of how this change was tested

  • Drive into static_layer's lethal space, see if the footprint is cleared in the correct place, and it is

Screenshot from 2025-02-10 02-35-13


Future work that may be required in bullet points

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

@HovorunBh HovorunBh force-pushed the fix_misplaced_footprint_on_static_layer branch from b0a3fe5 to 8552eec Compare February 10, 2025 10:01
Copy link
Contributor

mergify bot commented Feb 10, 2025

@HovorunBh, 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).

Signed-off-by: HovorunBh <[email protected]>
Copy link

codecov bot commented Feb 10, 2025

Codecov Report

Attention: Patch coverage is 50.00000% with 5 lines in your changes missing coverage. Please review.

Files with missing lines Patch % Lines
nav2_costmap_2d/plugins/static_layer.cpp 50.00% 5 Missing ⚠️
Files with missing lines Coverage Δ
...ostmap_2d/include/nav2_costmap_2d/static_layer.hpp 100.00% <ø> (ø)
nav2_costmap_2d/plugins/static_layer.cpp 73.99% <50.00%> (-1.24%) ⬇️

... and 6 files with indirect coverage changes

@SteveMacenski
Copy link
Member

SteveMacenski commented Feb 11, 2025

A few questions from a quick review to motivate discussion:

Should anything in updateBounds also be updated?

If the costmap is rolling, we find the TF lookup from map to global frame in updateCosts. To keep this time synchronized, should we find the transforms at the same stamp for the footprint and have this all stored for use later? Or, should we be using the robot pose given (x,y,yaw) to transform that pose from the global_frame into the map_frame rather than getting a new raw robot pose itself with getCurrentPose -- it seems like we should use the inputs instead of overriding them?

Finally, should the condition also be if the costmap is rolling or only when it is different?

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.

2 participants