Skip to content

Fix bounds calculation for rolling costmaps in StaticLayer#6064

Merged
SteveMacenski merged 1 commit intoros-navigation:mainfrom
botsandus:fix-static-layer-frame
Apr 7, 2026
Merged

Fix bounds calculation for rolling costmaps in StaticLayer#6064
SteveMacenski merged 1 commit intoros-navigation:mainfrom
botsandus:fix-static-layer-frame

Conversation

@tonynajjar
Copy link
Copy Markdown
Contributor

@tonynajjar tonynajjar commented Apr 4, 2026


Basic Info

Info Please fill out this column
Ticket(s) this addresses (add tickets here #1)
Primary OS tested on (Ubuntu, MacOS, Windows)
Robotic platform tested on (Steve's Robot, gazebo simulation of Tally, hardware turtlebot)
Does this PR contain AI generated software? (No; Yes and it is marked inline in the code)
Was this PR description generated by AI software? Out of respect for maintainers, AI for human-to-human communications are banned

I have the issue that my rolling local costmap doesn't seem to get fully populated with data:

image

My setup (roughly):

  • Launching loopback simulation with custom map and no amcl (map->odom set and odom->base_link by loopback node
  • I set initial pose somewhere on the map
  • I see an incompletely rendered local costmap

According to my investigation, here is what is happening:

The StaticLayer::updateBounds() method uses mapToWorld() to compute the region that needs updating. In Costmap2D, mapToWorld() converts grid cell indices to metric coordinates using the costmap instance's own origin: wx = origin_x + mx * resolution. This function has no awareness of TF frames — the output is implicitly in whatever frame the costmap's origin was defined in.

For the static layer's internal costmap, the origin comes from the map YAML file, so mapToWorld() produces coordinates in the map frame. However, the local costmap is a rolling window whose global_frame is odom. The LayeredCostmap interprets the bounds reported by updateBounds() as being in its global_frame (odom), then converts them to grid cell ranges (min_i, min_j, max_i, max_j) that are passed to updateCosts().

When map → odom is non-identity (which happens as soon as an initial pose is set at a non-origin location), the map-frame bounds returned by the static layer are misinterpreted as odom-frame coordinates. This causes the update region to be offset, resulting in only a portion of the rolling window being populated with static map data — or none at all if the offset is large enough.

The updateCosts() method already handles the frame difference correctly by doing a per-cell TF lookup from odom to map, but it only iterates over the cells within the (incorrect) bounds, so the correct transform logic is applied to the wrong region.

Description of contribution in a few bullet points

Fix: When rolling, compute bounds relative to the robot pose (which is already in the odom frame) spanning the full rolling window, instead of using mapToWorld():

Description of documentation updates required from your changes

Description of how this change was tested


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
  • Should this be backported to current distributions? If so, tag with backport-*.

Signed-off-by: Tony Najjar <tony.najjar@dexory.com>
@tonynajjar
Copy link
Copy Markdown
Contributor Author

tonynajjar commented Apr 4, 2026

@SteveMacenski this fixes the issue but please check my logic in detail here, I'm not 100% sure of the diagnosis (as is usually the case with nav2_costmap_2d code).

@tonynajjar tonynajjar marked this pull request as ready for review April 4, 2026 22:31
@SteveMacenski
Copy link
Copy Markdown
Member

@tonynajjar is this a modern PR to address what #5194 did (and the author just never followed up)?

You mentioned not sure about the approach, if this is the case, here's another example method (which may or may not be better)

Copy link
Copy Markdown
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.

This does seem at face value to work well - I'd just check the edge details on what if or is it possible for the min/maxes to be out of bounds or miss a bit. I think (?) its correct, but double checking the types and that everything are exact values and not being cast to/from unsigned int / ints that could cause truncation or approximation by the cell sizes.

@SteveMacenski
Copy link
Copy Markdown
Member

Is this related / to be addressed as well? #4911

@tonynajjar
Copy link
Copy Markdown
Contributor Author

@tonynajjar is this a modern PR to address what #5194 did (and the author just never followed up)?

Definitely looks like it yes

Is this related / to be addressed as well? #4911

I don't know for sure but I don't think so

@SteveMacenski
Copy link
Copy Markdown
Member

LMK when you're ready to merge

@SteveMacenski SteveMacenski merged commit 65b8d22 into ros-navigation:main Apr 7, 2026
23 of 24 checks passed
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