Fix bounds calculation for rolling costmaps in StaticLayer#6064
Fix bounds calculation for rolling costmaps in StaticLayer#6064SteveMacenski merged 1 commit intoros-navigation:mainfrom
Conversation
Signed-off-by: Tony Najjar <tony.najjar@dexory.com>
|
@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 |
|
@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) |
There was a problem hiding this comment.
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.
|
Is this related / to be addressed as well? #4911 |
Definitely looks like it yes
I don't know for sure but I don't think so |
|
LMK when you're ready to merge |
Basic Info
I have the issue that my rolling local costmap doesn't seem to get fully populated with data:
My setup (roughly):
According to my investigation, here is what is happening:
The
StaticLayer::updateBounds()method usesmapToWorld()to compute the region that needs updating. InCostmap2D, 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. TheLayeredCostmapinterprets the bounds reported byupdateBounds()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 toupdateCosts().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:
backport-*.