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 for robot footprint collision in obstacles critic #3878

Conversation

LeifHookedWireless
Copy link
Contributor


Basic Info

Info Please fill out this column
Ticket(s) this addresses No known tickets
Primary OS tested on Ubuntu
Robotic platform tested on Peanut's in-house robot (sim)

Description of contribution in a few bullet points

  • Inscribed/Circumscribed costs must be updated to take into account the current shape of the robot.
  • ObstaclesCritic::findCircumscribedCost() was only being called once, in initialize()
  • in initialize(), findCircumscribedCost() uses placeholder inner/outer radius values which come from robot_radius.
  • findCircumscribedCost() was never called again, and the circumscribed cost was never updated based on the footprint.
  • depending on the value of robot_radius, this could cause too much or too little footprint checking in costAtPose()

Description of documentation updates required from your changes

  • No documentation changes.

Future work that may be required in bullet points

  • The SMAC planner may have a similar problem. I will investigate when I have time.

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

current shape of the robot.
Was previous only being called once in initialize().
@LeifHookedWireless
Copy link
Contributor Author

This was the main reason our robot was driving through walls. robot_radius was smaller than the actual footprint, so the footprint was effectively ignored in the controller, even though consider_footprint_ was true.

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.

I approve, I’m waiting until I’m in front of a computer again this evening to test the runtime considerations.

@codecov
Copy link

codecov bot commented Oct 13, 2023

Codecov Report

All modified and coverable lines are covered by tests ✅

Comparison is base (0756ee1) 90.36% compared to head (fa09c78) 90.28%.
Report is 2 commits behind head on main.

❗ Current head fa09c78 differs from pull request most recent head c201121. Consider uploading reports for the commit c201121 to get more accurate results

Additional details and impacted files
@@            Coverage Diff             @@
##             main    #3878      +/-   ##
==========================================
- Coverage   90.36%   90.28%   -0.09%     
==========================================
  Files         415      413       -2     
  Lines       18446    18311     -135     
==========================================
- Hits        16669    16532     -137     
- Misses       1777     1779       +2     
Files Coverage Δ
...2_mppi_controller/src/critics/obstacles_critic.cpp 81.33% <100.00%> (+0.25%) ⬆️

... and 31 files with indirect coverage changes

☔ View full report in Codecov by Sentry.
📢 Have feedback on the report? Share it here.

@LeifHookedWireless
Copy link
Contributor Author

LeifHookedWireless commented Oct 13, 2023

I think my description is slightly wrong: it will almost always cause less footprint checking than should be.
The placeholder inner/outer radii are based on a poly of robot_radius. The inscribed and circumscribed radii of a regular polygon are always going to be pretty close to each other, compared to a non-round robot.

@SteveMacenski
Copy link
Member

Actually- can you test if this issue is resolved if we change these to references? Get once, have forever. The function that obtains the values may need to be updated to return references not copies. But that would completely mitigate additional runtime costs to get the most current state

@BriceRenaudeau
Copy link
Contributor

I had similar issues with the obstacles_critic. and that's why we developed a similar critic.

The radii are not updated correctly as @LeifHookedWireless mentioned. This modification will help with dynamic footprint.

But there is still several issues with the obstacles_critic:

  • The obstacles_critic is using the cost from inflate layer to compute distances by using the invert function of the cost. It makes inflation_layer cost_scaling_factor tunning useless, its good because it reduces tunning and it may be dangerous as it has a quantization effect on the distance).
  • The score is computed differently when the robot is far from obstacles and when it is close.
    https://github.com/ros-planning/navigation2/blob/7009ffba5f85c50ac97fd0057924b0f1447c5e85/nav2_mppi_controller/src/critics/obstacles_critic.cpp#L147-L151
    Why is the inflation radius used in the obstacle score? There is an X20 scale difference as collision_margin_distance_ ~ 0.1 and inflation_radius_ ~ 2.
  • If the footprint has some points in the inscribed area, the score is the same regardless of the distance to the obstacle. Because footprintCostAtPose returns the highest cost which will be "INSCRIBED" whatever the distance to the obstacle, distanceToObstacle(cost) will return the same distance so the score will be the same in a situation where it is important to evade obstacles.

@SteveMacenski
Copy link
Member

SteveMacenski commented Oct 24, 2023

I won't argue that this is perfect, but I'll say that I tested alot of formulations that didn't work nearly as well as this one. I'm not stuck to it what so ever if we have some alternatives that would be better / faster / stronger.

that's why we developed a similar critic

Plz share what you have that works better?

The obstacles_critic is using the cost from inflate layer to compute distances by using the invert function of the cost. It makes inflation_layer cost_scaling_factor tunning useless, its good because it reduces tunning and it may be dangerous as it has a quantization effect on the distance).

That's intentional. Decoupling the potential field so that the critic can decide what to do using the same units (meters) as the other critics to keep things proportionate so that the tuning weights are the only difference is a nice to have thing. Mostly though, I did this because when trying to use raw costs and normalizing them, I could never really get good performance and made the tuning way-way-way-way too sensitive to minuscule changes in the cost scaling factor and inflation radius. It was absolutely insane the degree that which you had to tune to get even remotely reasonable results. It was untenable in the formulations I tried.

The score is computed differently when the robot is far from obstacles and when it is close.

Of course, I don't see why you mention this is a 'bad' thing. We need to have very high cost for things that basically in collision, but you don't want to necessarily have high cost when you're further away from things. Decoupling "nice to have" behavior from "critical" behavior allows you to tune more finely. If we could find a mathematical model that gave us both of those at the same time, I'd be more than happy to test / use it. I think this is a really nice behavior to be able to tune how we act in "normal" situations separately from how we penalize near-obstacle behavior.

There is an X20 scale difference

Yes, but they're all in meters, like all other critics using SI units to keep the scales consistent between critics. The critical weight should just be 20x larger. That seems completely normal and reasonable. We weight things more highly when we care about them or they're smaller. See the defaults, its set as higher, just as other critic are set to higher when their SI unit formation is proportionately lower to others.

If the footprint has some points in the inscribed area, the score is the same regardless of the distance to the obstacle. Because footprintCostAtPose returns the highest cost which will be "INSCRIBED" whatever the distance to the obstacle, distanceToObstacle(cost) will return the same distance so the score will be the same in a situation where it is important to evade obstacles.

This is a fair point. There's a reason why TSDF is on my potential improvements list


I'm very open to suggestions. This is, as I mentioned in my ROSCon talk, one of the bigger quirks of MPPI and I would really like to improve this critic in pretty much every regard and very open to your thoughts on what is better to replace it with. Please share more about your implementation if it works better 😄

@BriceRenaudeau
Copy link
Contributor

Thans for you detailed reply.
I think it is beyond to this issue now so I will keep it short and I will be happy to discuss in another thread.

The critic we are using is a simplified version of the obstacles_critcs. It uses inflation costs directly as the exponential creates the behavior we want (close = very detailed high scores and far = low scores). There is no distance computation (m). It works well enough and allow custom inflations to be taken into acount.

@SteveMacenski
Copy link
Member

@BriceRenaudeau can you share a branch or open a ticket to chat?

@LeifHookedWireless did you try the references item so we don't recompute every iteration? I know you were at ROSCon like I, so I don't expect yet, just jogging our collective memories

@LeifHookedWireless
Copy link
Contributor Author

LeifHookedWireless commented Oct 26, 2023

@LeifHookedWireless did you try the references item so we don't recompute every iteration? I know you were at ROSCon like I, so I don't expect yet, just jogging our collective memories

@SteveMacenski Sorry, been busy. I'll look into it soon.

@LeifHookedWireless
Copy link
Contributor Author

I'm not seeing any way to use references here.
The CircumscribedCost needs to be recalculated whenever the costmap or footprint changes, which will happen at least once between ObstaclesCritic::initialize() and ObsctacleCritics::score().
It's not stored anywhere.

It's not trivial to keep track of when those two have changed.
Since it is a fairly lightweight calculation, I suggest just computing it before score() every time.

@SteveMacenski
Copy link
Member

Can you show that its a lightweight operation with some timers? How long is this taking?

@LeifHookedWireless
Copy link
Contributor Author

If we assume that the costmap resolution and inflation layer parameters don't change during navigation, then we only have to recalculate the cost if getCircumscribedRadius() changes, so that could be an optimization.

@SteveMacenski
Copy link
Member

Seems reasonable, can you just put a timer around that function and benchmark it to know that this isn't going to be some big performance hit?

@LeifHookedWireless
Copy link
Contributor Author

I added some timers and ran some tests in my simulated hallway including passing through a narrow doorway.
With consider_footprint: false, I saw ObstaclesCritc:score() take about 4ms on average (7ms max) in the hallway and doorway.
With consider_footprint: true I was ObstaclesCritc:score() take about 4ms on average (8ms max) in the hallway, and over 100ms passing through the doorway.
findCircumscribedCost is less than 1% of the cost in any case.

@LeifHookedWireless
Copy link
Contributor Author

I have a suggestion to address the high cost of collision detection when using the footprint.
Since the footprint code is only active near obstacles, a lot of the checks are very close to each other and I suspect that many are effectively identical to each other.
Caching results in the FootprintCollisionChecker may result in a dramatic speed-up.
I'm interested in trying this, though it may be a week or two away depending on how busy I am.

@SteveMacenski
Copy link
Member

SteveMacenski commented Nov 6, 2023

Sorry, maybe I should have been more explicit. Put a timer only around that findCircumscribedCost in score and let me know specifically how long that takes alone.

Caching results in the FootprintCollisionChecker may result in a dramatic speed-up.

Perhaps, but how do you plan to cache anything if we're working in continuous coordinates? There will be almost guaranteed to be no 2 identical poses in any of the trajectories being scored. They might be similar, but not the same. You'd have to bin both the orientation and the cells to approximately collision check, so you'd have to decide how it is you'd want to do that binning.

We do something related in the Smac Planner, where its version of the collision checker precomputes the footprints at the binned orientations so that we're not owning sin/cos operations in the checks and are simply translating the footprints to the current position to check at the right angle for each bin. You could do something like that for approximate checks so that you have a cache of x,y in costmap cells and yaw of precomputed angular quantizations. I don't do a cache in the Smac Planner just due to the framework its not possible to overlap in the same way it is here.

I think one could get a similar result by having the option to skip every-other trajectory point for collision checking -- which is also on my mind as a potential option to speed things up (but not ideal, obviously). That seems like the 80/20 solution but caching would be more a complete solution -- but the angular bins would need to be relatively small to make sure the approximate check isn't "substantially" worse / inaccurate. The overlap between samples would really only exist for the first ~10-30% of the trajectories. After that, the divergence due to the noise distributions would make overlaps increasingly rare, especially if you have small quantizations to make sure the accuracy remains high.

Overall, its something that I've thought about / thinking about, but there are some real open questions about its efficacy. It very well would improve performance, but I don't think its a silver bullet. I suspect for the full collision checking improvements, its going to have to be a few things like this, where caching plays a role alongside others.

Something of that matter is also on my mind if one had a GPU: where it might make sense to literally brute force the entire costmap at every cell / angle its collision state using the GPU and doing lookups here from that computed cache.

@LeifHookedWireless
Copy link
Contributor Author

Sorry, maybe I should have been more explicit. Put a timer only around that findCircumscribedCost in score and let me know specifically how long that takes alone.

I did, but the numbers were so small I didn't think they were worth mentioning.
I measured ~6 microseconds worst case and ~1 microsecond in the typical case.
Compared to several milliseconds for score().

Caching results in the FootprintCollisionChecker may result in a dramatic speed-up.

Perhaps, but how do you plan to cache anything if we're working in continuous coordinates?

I wasn't planning on working in continuous coordinates. The footprint costmap collision uses discrete coordinates. e.g. FootprintCollisionChecker::lineCost(int x0, int x1, int y0, int y1)
You can hash those 4 ints as a key and use it to cache the results.
Even thought the (x,y,yaw) all vary slightly, I'm seeing a large number of repeated edges. Seems like we should be able to take advantage of that.
I'll let you know if I come up with anything.

@SteveMacenski
Copy link
Member

SteveMacenski commented Nov 6, 2023

You can hash those 4 ints as a key and use it to cache the results.

I think that's unlikely to result in major improvements, but I could be wrong! I doubt there are that many redundant checks for the exact same line segment. But hey, I'm happy to be surprised. Just remember that hashtable lookups are O(1), but that doesn't mean they're fast. I've found from experience with the Smac Planner and others in Nav2 that creating a storage semantic in std::vector is far, far faster for lookup-heavy operations.

@SteveMacenski SteveMacenski merged commit 98af3b9 into ros-navigation:main Nov 6, 2023
3 of 5 checks passed
mergify bot pushed a commit that referenced this pull request Nov 6, 2023
* Inscribed/Circumscribed costs must be updated to take into account the
current shape of the robot.
Was previous only being called once in initialize().

* Add early return to avoid calculations if footprint has not changed.

* Only update radius if using footprint.
Add perf timers.

* Remove perf timers.

* Update comments.

---------

Co-authored-by: Leif Terry <[email protected]>
(cherry picked from commit 98af3b9)
mergify bot pushed a commit that referenced this pull request Nov 6, 2023
* Inscribed/Circumscribed costs must be updated to take into account the
current shape of the robot.
Was previous only being called once in initialize().

* Add early return to avoid calculations if footprint has not changed.

* Only update radius if using footprint.
Add perf timers.

* Remove perf timers.

* Update comments.

---------

Co-authored-by: Leif Terry <[email protected]>
(cherry picked from commit 98af3b9)
SteveMacenski pushed a commit that referenced this pull request Nov 6, 2023
* Inscribed/Circumscribed costs must be updated to take into account the
current shape of the robot.
Was previous only being called once in initialize().

* Add early return to avoid calculations if footprint has not changed.

* Only update radius if using footprint.
Add perf timers.

* Remove perf timers.

* Update comments.

---------

Co-authored-by: Leif Terry <[email protected]>
(cherry picked from commit 98af3b9)

Co-authored-by: LeifHookedWireless <[email protected]>
SteveMacenski pushed a commit that referenced this pull request Nov 6, 2023
* Inscribed/Circumscribed costs must be updated to take into account the
current shape of the robot.
Was previous only being called once in initialize().

* Add early return to avoid calculations if footprint has not changed.

* Only update radius if using footprint.
Add perf timers.

* Remove perf timers.

* Update comments.

---------

Co-authored-by: Leif Terry <[email protected]>
(cherry picked from commit 98af3b9)

Co-authored-by: LeifHookedWireless <[email protected]>
@LeifHookedWireless
Copy link
Contributor Author

I think that's unlikely to result in major improvements, but I could be wrong! I doubt there are that many redundant checks for the exact same line segment. But hey, I'm happy to be surprised. Just remember that hashtable lookups are O(1), but that doesn't mean they're fast. I've found from experience with the Smac Planner and others in Nav2 that creating a storage semantic in std::vector is far, far faster for lookup-heavy operations.

I implemented a cache with a std:map and I'm seeing a large number of cache hits for segments and even entire footprints. (And this is with a small 2.5cm grid size)
However the performance is not great. The costmap checks are pretty fast and, as you say, the lookups are pretty slow. So I'm getting something that's roughly a wash, performance wise.
I still think there might be something here though. I will try your std::vector suggestion next.

RBT22 pushed a commit to EnjoyRobotics/navigation2 that referenced this pull request Nov 16, 2023
…#3878) (ros-navigation#3947)

* Inscribed/Circumscribed costs must be updated to take into account the
current shape of the robot.
Was previous only being called once in initialize().

* Add early return to avoid calculations if footprint has not changed.

* Only update radius if using footprint.
Add perf timers.

* Remove perf timers.

* Update comments.

---------

Co-authored-by: Leif Terry <[email protected]>
(cherry picked from commit 98af3b9)

Co-authored-by: LeifHookedWireless <[email protected]>
RBT22 pushed a commit to EnjoyRobotics/navigation2 that referenced this pull request Nov 16, 2023
…#3878) (ros-navigation#3947)

* Inscribed/Circumscribed costs must be updated to take into account the
current shape of the robot.
Was previous only being called once in initialize().

* Add early return to avoid calculations if footprint has not changed.

* Only update radius if using footprint.
Add perf timers.

* Remove perf timers.

* Update comments.

---------

Co-authored-by: Leif Terry <[email protected]>
(cherry picked from commit 98af3b9)

Co-authored-by: LeifHookedWireless <[email protected]>
redvinaa pushed a commit to EnjoyRobotics/navigation2 that referenced this pull request Nov 20, 2023
…#3878) (ros-navigation#3947)

* Inscribed/Circumscribed costs must be updated to take into account the
current shape of the robot.
Was previous only being called once in initialize().

* Add early return to avoid calculations if footprint has not changed.

* Only update radius if using footprint.
Add perf timers.

* Remove perf timers.

* Update comments.

---------

Co-authored-by: Leif Terry <[email protected]>
(cherry picked from commit 98af3b9)

Co-authored-by: LeifHookedWireless <[email protected]>
jwallace42 pushed a commit to jwallace42/navigation2 that referenced this pull request Jan 3, 2024
…#3878)

* Inscribed/Circumscribed costs must be updated to take into account the
current shape of the robot.
Was previous only being called once in initialize().

* Add early return to avoid calculations if footprint has not changed.

* Only update radius if using footprint.
Add perf timers.

* Remove perf timers.

* Update comments.

---------

Co-authored-by: Leif Terry <[email protected]>
Signed-off-by: gg <[email protected]>
pepisg added a commit to kiwicampus/navigation2 that referenced this pull request Apr 24, 2024
* bump to 1.2.0 for iron release

* Iron sync June 9: 1.2.1 (ros-navigation#3615)

* Improve usability of PWAs in Dev Containers (ros-navigation#3576)

* Add WIP icons

* Add WIP icons for gzweb

* Add WIP icons for glances

* Set cross origin to use credentials
ensuring auth cookie is included in request header
when requesting for web app manifest file
thus avoiding CORS policy violations in browser
when accessing forwarded codespaces ports from the web

> The request for the manifest is made without credentials (even if it's on the same domain), thus if the manifest requires credentials, you must include `crossorigin="use-credentials"` in the manifest tag.

- https://web.dev/add-manifest/
- https://stackoverflow.com/a/57184506/2577586

* Use ReqHost variable in templates
to account for X-Forwarded-Host value in header

* Delete duplicate manifest

* Set id property in app manifests
so we can address them independently from their start_url
- https://developer.chrome.com/blog/pwa-manifest-id/

* Ensure apps are uniquely identifies
by adding trailing slash to id
and thus different URI directories

* Refactor root landing page into nav2 app
by moving page file into nav2 sub folder
adding root redirect pointing to /nav2/
and updating html, markdown, manifest files respectively

* Fix https detection for Caddy reverse proxies
by also checking X-Forwarded-Proto in request header

* Remove unnecessary files

* Prune smaller images

* Prune duplicate icon

* Clean up html tags

* Update manifest icons

* Rename icons

* Revert "Prune duplicate icon"

This reverts commit 5710401.

* Add back favicon for shortcut

* Add self index for completeness and bookmarking

* Simplify icon linking

* Delete binary files

* Fix hyperlink path

* Include image files using gitattributes
to track these binary files via git LFS

* Add icons using git lfs

* Standardized all icon paths

* Use external links for icons
to avoid the need for using git LFS
although this is a bit of a hack

* Stage any and maskable icons

* Use any and masked icons

* Set colors to match maskable icon colors

* Update icon

* Use lossless compression
without removing background
- https://shortpixel.com/online-image-compression

* Use WebP instead of PNG
for smaller file sizes
- https://en.wikipedia.org/wiki/WebP

* Move icons into icons folder

* Use _SRV environment variables for service paths

* Download media files from github
during docker image build
to avoid adding always online dependencies
when creating or starting dev containers

* Delete media icons from git repo
now that we download media from anonymized URLs on github
- https://docs.github.com/en/get-started/writing-on-github/working-with-advanced-formatting/attaching-files

* Add comments

* Enable file browsing for non app paths
for remote debugging of media and asset files

* Consolidate assets into single folder

* Add links for file browser paths
to Server Diagnostics

* Delete unused symlink

* Update landing page to match manifest
by including same shortcuts and start url

* Patch gzweb to disable modelList
avoiding 404s for thumbnails
as they are hardcoded into js

* Update comments

* Simplify Caddyfile by reverting to symlinking
but add ROOT_SRV env for custom overriding

* Loop over nav2 srv folders when symlinking
to generalize over folder names

* Add matcher for file browsing root directory
while still redirecting to nav2 app by default

* Use placeholders for root variable
to consolidate env default fallback settings
e.g `:/srv`

* Promote file browser in Nav2 app shortcuts

* Fix and update SRV envs

* Postpone symlinking for Nav2 web app
to when post-create-command script then runs
given full repo is not copied into builder stage in Dockerfile.
While this could be postponed to update-content-command
leaving it here avoids blowing user changes
after the container has been created or modified.

* Add guard to check if srv folder exists

* Add refresh rate shortcuts to glances

* Add file browser shortcut to nav2

* Set scope for nav2 PWA to root
to allow for opening child apps inside nav2 app

* Display child apps in fullscreen mode by default
as users can still open them in standalone via nav2 app
given the nav2 app's scope is the parent root path

* Update shortcuts and landing page

* Document PWA scope and installation order
when using Nav2 PWA scoped as root

* Revert setting scope for nav2 PWA to root path
as adding file browser shortcut to nav2 PWA is not worth the trouble
of having to explain installation order caveats and URL launch behavior.
File browser shortcut is still accessible from inside nav2 pwa launcher
but merely displays in browser preview
given root / is out of scope for /nav2/

* Update server diagnostics for troubleshooting

* Verify checksum of archive before extraction
incase anonymized URL changes expected archive

* Fix the condition in ackerman motion model constraints (ros-navigation#3581)

* Fix the condition in ackerman motion model constraints

* Fix ackerman motion model tests

* Fix another ackerman motion model test

* Add viz_expansions parameter for debug (ros-navigation#3577)

* viz_expansions

* lint

* switch to unique_ptr

* readme update

---------

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

* Fix broken symlink for gzweb (ros-navigation#3585)

to load world models

* (collision monitor) add limit polygon type (ros-navigation#3519)

* add LIMIT polygon type

* fix unit tests

* Fix MIN_POINT doesn't exist

* Fix Action type enum

* FIX velocity used

* FIX unit test point distance

increase point distance to not be in limit field

* Update collision_monitor_node_test.cpp

* fix status name not updated

* [MOD] only single linear limit

* Apply review comments

* Update nav2_collision_monitor/include/nav2_collision_monitor/types.hpp

---------

Co-authored-by: Steve Macenski <[email protected]>

* Fix broken link to contributing guidelines (ros-navigation#3587)

The original URL (https://navigation.ros.org/contribute/index.html) seems not to exist, returning an HTTP 404. Hence, I've replaced the link with a page that seems most relevant.

* Adding Our Sponsors - May 2023 (ros-navigation#3593)

* adding our sponsors - may 2023

* adding blurb

* adding links

* adding links

* adding links

* adding Open Nav

* Fix dynamic polygons vertices not updated for different frame (ros-navigation#3591)

* Fix dynamic polygons vertices not updated for different frame

* Update nav2_collision_monitor/src/collision_monitor_node.cpp

---------

Co-authored-by: Steve Macenski <[email protected]>

* Fixing 3586: rviz panel operating in multiple non-standard frames (ros-navigation#3595)

* Fixes ros-navigation#3586 on rviz time stamping

* removing timing from rviz testing panel

* Add CostmapFilterInfoServer as a component (ros-navigation#3596)

* adding iron to the readme table statuses (ros-navigation#3598)

* adding iron to the readme table statuses

* collapsing table

* adding citation RPP

* Resolve ros-navigation#3532: reset i (ros-navigation#3597)

* [MPPI] empty path_follow_critic proper fix (ros-navigation#3599)

* [MPPI] empty path_follow_critic proper fix

* fix linting issue

---------

Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* Refactor sim_time and composable node usage in Collision Monitor (ros-navigation#3604)

* Refactor sim_time and composable node usage in Collision Monitor launch script

* Added namespace support

* Fix comment

* Fix costmap 2D test failures (ros-navigation#3611)

* costmap test without action

* test2

* try just printing first thing

* Update test_costmap_2d_publisher.cpp

* Compile flags non-virtual-destructor (ros-navigation#3609)

* added compile flags

* cleanup

* cleanup

* cleanup

* add virtual destructors

* uncrusify

* updating to 1.2.1 for release

---------

Co-authored-by: Ruffin <[email protected]>
Co-authored-by: Alexandr Buyval <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: BriceRenaudeau <[email protected]>
Co-authored-by: Hyung-Taik Choi <[email protected]>
Co-authored-by: Alexey Merzlyakov <[email protected]>
Co-authored-by: Filipe Cerveira <[email protected]>
Co-authored-by: Joshua Wallace <[email protected]>

* remove non-virtual-dtor flag from nav2_package()

* WIP: Merge segmentation layer and GPS wpf

* WIP: remove wrong whitespace

* WIP: Bring back ffollow gps waypoints

* WIP: error codes to gps waypoint follwer

* Fix GPS waypoint follower error codes

* Fixing build warning (ros-navigation#3667) (ros-navigation#3672)

(cherry picked from commit 7d4b199)

Co-authored-by: Steve Macenski <[email protected]>

* Install nav2_behavior_tree utils outside of BUILD_TESTING (ros-navigation#3692) (ros-navigation#3697)

(cherry picked from commit abf3e85)

Co-authored-by: Aaditya Ravindran <[email protected]>

* Fix segfault on relaunch of controller server

* Fix the velocity smoother being stuck when the deadband is too high (ros-navigation#3690) (ros-navigation#3714)

* Move last_cmd update before deadband

* fix lint

(cherry picked from commit cb34d0c)

Co-authored-by: BriceRenaudeau <[email protected]>

* Iron sync 2, Aug 4, 1.2.2 (ros-navigation#3740)

* Only apply Wnon-virtual-dtor if the compile language is CXX (ros-navigation#3614)

* https://stackoverflow.com/questions/25525047/cmake-generator-expression-differentiate-c-c-code

Signed-off-by: Ryan Friedman <[email protected]>

* Fix map not showing on rviz when navigation is launched with namespace (ros-navigation#3620)

* Fix Wshadow errors and enforce it (ros-navigation#3617)

* Fix Wshadow errors and enforce it

Signed-off-by: Ryan Friedman <[email protected]>

* Remove workaround for pluginlib

* This was only needed because it was included transitively
* By finding and linking properly, the compiler flags get propogated as SYSTEM
  correctly

Signed-off-by: Ryan Friedman <[email protected]>

---------

Signed-off-by: Ryan Friedman <[email protected]>

* add-Wnull-dereference and fix warnings (ros-navigation#3622)

Signed-off-by: Ryan Friedman <[email protected]>

* updating mppi's path angle critic for optional bidirectionality (ros-navigation#3624)

* updating mppi's path angle critic for optional bidirectionality

* Update README.md

* correct error message (ros-navigation#3631)

* correct error message

* clean up

* cleanup

* remove header

* Let Navigators have different error codes (ros-navigation#3642)

* Change ERROR to DEBUG

* INFO message on init

* format code

* Replace newlines with spaces

* fixing path angle critic's non-directional bias (ros-navigation#3632)

* fixing path angle critic's non-directional bias

* adding reformat

* adapting goal critic for speed to goal (ros-navigation#3641)

* adapting goal critic for speed to goal

* retuning goal critic

* add readme entries

* Update critics_tests.cpp

* Fix uninitialized value (ros-navigation#3651)

* In NAV2, this warning is treated as an error

Signed-off-by: Ryan Friedman <[email protected]>

* Fix rviz panel node arguments (ros-navigation#3655)

Signed-off-by: Nick Lamprianidis <[email protected]>

* Reduce out-of-range log to DEBUG (ros-navigation#3656)

* Adding nan twist rejection for velocity smoother and collision monitor (ros-navigation#3658)

* adding nan twist rejection for velocity smoother and collision monitor

* deref

* Ceres exposes a namespaced export and recommends it in their docs (ros-navigation#3652)

Signed-off-by: Ryan Friedman <[email protected]>

* Enable multiple MPPI path angle modes depending on preferences in behavior (ros-navigation#3650)

* fixing path angle critic's non-directional bias

* adding reformat

* handle linting

* add utility unit tests

* adding unit tests for path angle

* MPPI: Support Exact Path Following For Feasible Plans (ros-navigation#3659)

* alternative to path align critic for inversion control

* fix default behavior (enforce_path_inversion: false) (ros-navigation#3643)

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

* adding dyaw option for path alignment to incentivize following the path's intent where necessary

* add docs for use path orientations

* fix typo

---------

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

* Resolves 3646: Update CMAKE_COMPILER_IS_GNUCXX (ros-navigation#3662)

* Resolves 3646: Update CMAKE_COMPILER_IS_GNUCXX

* Update CMakeLists.txt

* Fix smoother server tests (ros-navigation#3663)

* Fix smoother server tests

* Update test_smoother_server.cpp

* fix some new build warnings from sync (ros-navigation#3674)

* fix some new build warnings

* fixing last issue

* Update navigate_through_poses_action.hpp

* adding unsigned int to tests

* all to unsigned shorts

* test new warning resolution

* Update

* convert unsigned shorts to uint16_t for linter

* Fix costmap publisher test (ros-navigation#3679)

* added printouts

* ignore system tests

* fix

* cleanup

* Update test_costmap_2d_publisher.cpp

remove space

* remove empty message (ros-navigation#3691)

* Collision Monitor fixups (ros-navigation#3696)

* Fix max_points -> min_points in parameters
* Move robot_utils.hpp include to source where it actually using
* Remove double-description of getTransform()

* Use ParameterFile (allow_substs) (ros-navigation#3706)

Signed-off-by: ymd-stella <[email protected]>

* nav2_bt_navigator: log current location on navigate_to_pose action initialization (ros-navigation#3720)

It is very useful to know the current location considered by the
bt_navigator for debug purposes.

* nav2_behaviors: export all available plugins (ros-navigation#3716)

It allows external packages to include those headers and create child
classes through inheritance.

* changing costmap layers private to protected (ros-navigation#3722)

* Update costmap_2d_ros.cpp (ros-navigation#3687)

* updated nav2_behavior_tree test util install path (ros-navigation#3718)

* launch linting (ros-navigation#3729)

* adding error warnings around incorrect inflation layer setups in MPPI and Smac which impact performance substantially (ros-navigation#3728)

* adding error warnings around incorrect inflation layer setups in MPPI and Smac which impact performance substantially

* fix test failures

* Update RewrittenYaml to support list rewrites (ros-navigation#3727)

* allowing leaf key rewrites that aren't dcits (ros-navigation#3730)

* adding checks on config and dynamic parameters for proper velocity and acceleration limits (ros-navigation#3731)

* Fix Goal updater QoS (ros-navigation#3719)

* Fix GoalUpdater QoS

* Fixes

* adding tolerance back in for smac lattice and hybrid-A* planners (ros-navigation#3734)

* Completing Hybrid-A* visualization of expansion footprints PR (ros-navigation#3733)

* smach_planner_hybrid: add support visualization for hybrid Astar

* smac_planner_hyrid: revert some

* smach_planner_hybrid: improving code quality

* utils: add some useful functions

* utils: fix mistake

* nav2_smac_planner: fix format problem

* utils: fix format and revise functions

* smach_planner_hybrid: delete _viz_expansion parameter

* smac_planner_hybrid: fix format

* README: update parameter

* utils: corrct mistake return

* utils: make timestamp a const reference

* nav2_smac_planner: correct format problem

* add unit test functions

* further detection of element equality

* test_utils: add non-trival translation and rotation

* smac_planner_hybrid: pass value instead of references

* completing hybrid A* visualization

---------

Co-authored-by: xianglunkai <[email protected]>

* Update README.md (ros-navigation#3736)

* Update README.md

* Update README.md

* sync iron to 1.2.2 to release

---------

Signed-off-by: Ryan Friedman <[email protected]>
Signed-off-by: Nick Lamprianidis <[email protected]>
Signed-off-by: ymd-stella <[email protected]>
Co-authored-by: Ryan <[email protected]>
Co-authored-by: Filipe Cerveira <[email protected]>
Co-authored-by: Joshua Wallace <[email protected]>
Co-authored-by: RBT22 <[email protected]>
Co-authored-by: Nick Lamprianidis <[email protected]>
Co-authored-by: BriceRenaudeau <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Alexey Merzlyakov <[email protected]>
Co-authored-by: ymd-stella <[email protected]>
Co-authored-by: DylanDeCoeyer-Quimesis <[email protected]>
Co-authored-by: Aaditya Ravindran <[email protected]>
Co-authored-by: gyaanantia <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: xianglunkai <[email protected]>

* nav2_collision_monitor: collision detector (ros-navigation#3500) (Iron backport) (ros-navigation#3758)

* nav2_collision_monitor: collision detector (ros-navigation#3500)

* fix

* mppi: return NO_INFORMATION when the checked point is outside the costmap (ros-navigation#3816) (ros-navigation#3817)

otherwise the controller crashes at ObstaclesCritic::costAtPose
because x_i and y_i isn't initialized.

(cherry picked from commit 6b250a7)

Co-authored-by: Chuanhong Guo <[email protected]>

* Iron Sync 3 - Sept 25 (ros-navigation#3837)

* Same orientation of coordinate frames in rviz ang gazebo (ros-navigation#3751)

* rviz view straight in default xy orientation

Signed-off-by: Christian Henkel <[email protected]>

* gazebo orientation to match rviz

Signed-off-by: Christian Henkel <[email protected]>

* rotating in direction of view

---------

Signed-off-by: Christian Henkel <[email protected]>

* Fix flaky costmap filters tests: (ros-navigation#3754)

1. Set forward_prune_distance to 1.0 to robot not getting lost
2. Correct map name for costmap filter tests

* Update smac_planner_hybrid.cpp (ros-navigation#3760)

* Fix missing mutex in PlannerServer::isPathValid (ros-navigation#3756)

Signed-off-by: ymd-stella <[email protected]>

* Rename PushRosNamespace to PushROSNamespace (ros-navigation#3763)

* Rewrite the scan topic costmap plugins for multi-robot(namespace) before launch navigation. (ros-navigation#3572)

* Make it possible to launch namspaced robot which rewrites `<robot_namespace>` to namespace.
- It allows to apply namespace automatically on specific target topic path in costmap plugins.

Add new nav2 params file for multi-robot(rewriting `<robot_namespace>`) as an example.
- nav2_multirobot_params_all.yaml

Modify nav2_common.ReplaceString
- add condition argument

* Update nav2_bringup/launch/bringup_launch.py

Co-authored-by: Steve Macenski <[email protected]>

* Add new luanch script for multi-robot bringup

Rename luanch script for multi-robot simulation bringup

Add new nav2_common script
- Parse argument
- Parse multirobot pose

Update README.md

* Update README.md

Apply suggestions from code review

Fix pep257 erors

Co-authored-by: Steve Macenski <[email protected]>

---------

Co-authored-by: Steve Macenski <[email protected]>

* use ros clock for wait (ros-navigation#3782)

* use ROS clock for wait

* fix backport issue

---------

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

* fixing external users of the BT action node template (ros-navigation#3792)

* fixing external users of the BT action node template

* Update nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

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

---------

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

* Fixing typo in compute path through poses error codes (ros-navigation#3799)

Signed-off-by: Mannucci, Anna (Bosch (CR)) <[email protected]>
Co-authored-by: Mannucci, Anna (Bosch (CR)) <[email protected]>

* Fixes for flaky WPF test (ros-navigation#3785)

* Fixes for flaky WPF test:
* New RewrittenYaml ability to add non-existing parameters
* Prune distance fix for WPF test
* Treat UNKNOWN status as error in WPF
* Clear error codes after BT run
* Remove unnecessary setInitialPose() from WPF test

* Update nav2_waypoint_follower/src/waypoint_follower.cpp

Co-authored-by: Steve Macenski <[email protected]>

* Clean error code in any situation

* Fix UNKNOWN WPF status handling

---------

Co-authored-by: Steve Macenski <[email protected]>

* Fix `min_points` comparison check (ros-navigation#3795)

* Fix min_points checking

* Expose action server result timeout as a parameter in bt navigator servers (ros-navigation#3787)

* Expose action server default timeout in bt navigator servers

* typo

* duplicated comment

* Expose result timeout in other actions

* Proper timeout in bt node

* Change default timeouts and remove comments

* Remove comment in params file

* uncrustify controller server

* Using Simple Commander API for multi robot systems (ros-navigation#3803)

* support multirobot namespaces

* add docs

* adding copy all params primitive for BT navigator (to ingest into rclcpp) (ros-navigation#3804)

* adding copy all params primitive

* fix linting

* lint

* I swear to god, this better be the last linting issue

* allowing params to be declared from yaml

* Update bt_navigator.cpp

* Fix CD configuration link reference (ros-navigation#3811)

* Fix CD configuration page reference

* Add CM work on 6th ROS Developers Day reference

* some minor optimizations (ros-navigation#3821)

* fix broken behaviortree doc link (ros-navigation#3822)

Signed-off-by: Anton Kesy <[email protected]>

* [MPPI] complete minor optimaization with floating point calculations (ros-navigation#3827)

* floating point calculations

* Update optimizer_unit_tests.cpp

* Update critics_tests.cpp

* Update critics_tests.cpp

* 25% speed up of goal critic; 1% speed up from vy striding when not in use

* Add nav2_gps_waypoint_follower (ros-navigation#2814)

* Add nav2_gps_waypoint_follower

* use correct client node while calling it to spin

* changed after 1'st review

* apply requested changes

* nav2_util::ServiceClient instead of CallbackGroup

* another  iteration to adress issues

* update poses with function in the follower logic

* add deps of robot_localization: diagnostics

* fix typo in underlay.repo

* add deps of robot_localization: geographic_info

* minor clean-ups

* bond_core version has been updated

* rotation should also be considered in GPS WPFing

* use better namings related to gps wpf orientation

* handle cpplint errors

* tf_listener needs to be initialized

* apply requested changes

* apply requested changes 3.0/3.0

* fix misplaced ";"

* use run time param for gps transform timeout

* change timeout var name

* make use of stop_on_failure for GPS too

* passing emptywaypont vectors are seen as failure

* update warning for empty requests

* consider utm -> map yaw offset

* fix missed RCLCPP info

* reorrect action;s name

* waypoint stamps need to be updated

* Fix segmentation fault on waypoint follower

* Parametric frames and matrix multiplications

* Replace oriented navsatfix for geographic_msgs/geopose

* Remove deprecated oriented  navsatfix message

* Update branch name on robot_localization dependency

* Fix parametric frames logic

* Rename functions and adress comments

* fix style in underlay.repos

* remove duplicate word in underlay.repos

* update dependency version of ompl

* Template ServiceClient class to accept lifecycle node

* Remove link to stackoverflow answer

* Remove yaw offset compensation

* Fix API change

* Fix styling

* Minor docs fixes

* Fix style divergences

* Style fixes

* Style fixes v2

* Style fixes v3

* Remove unused variables and timestam overrides

* restore goal timestamp override

* WIP: Add follow gps waypoints test

* Style fixes and gazebo world inertia fix

* Reduce velocity smoother timeout

* empty commit to rerun tests

* Increment circle ci cache idx

* Remove extra space in cmakelists.txt

* Fix wrong usage of the global action server

* update follow gps waypoints action definition

* Fix action definition and looping

* update params for the unit testing

* WIP: update tests

* fix tests

* fixes to nav2 simple commander

* add robot_localization localizer

* Bring back from LL client

* Update nav2_simple_commander/nav2_simple_commander/robot_navigator.py

Co-authored-by: Steve Macenski <[email protected]>

* missing argument in test function

* small test error

* style fixes nav2 simple commander

* rename cartesian action server

---------

Co-authored-by: jediofgever <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>

* bumping iron from 1.2.2 to 1.2.3 for release

* Update waypoint_follower.cpp

---------

Signed-off-by: Christian Henkel <[email protected]>
Signed-off-by: ymd-stella <[email protected]>
Signed-off-by: Mannucci, Anna (Bosch (CR)) <[email protected]>
Signed-off-by: Anton Kesy <[email protected]>
Co-authored-by: Christian Henkel <[email protected]>
Co-authored-by: Alexey Merzlyakov <[email protected]>
Co-authored-by: ymd-stella <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Hyunseok <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Anna Mannucci <[email protected]>
Co-authored-by: Mannucci, Anna (Bosch (CR)) <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Pedro Alejandro González <[email protected]>
Co-authored-by: Anton Kesy <[email protected]>
Co-authored-by: jediofgever <[email protected]>

* Update CMakeLists.txt (ros-navigation#3843) (ros-navigation#3844)

(cherry picked from commit 2d6e9a9)

Co-authored-by: Steve Macenski <[email protected]>

* bump to 1.2.4 for AVX512 binary fix

* add option for sse4 and avs512 (ros-navigation#3853) (ros-navigation#3854)

(cherry picked from commit 7274811)

Co-authored-by: Steve Macenski <[email protected]>

* Bumping to 1.2.5 for binary release of AVX512 patches

* Start planner in the end of previous path

* [MPPI Optimization] adding regenerate noise param + adding docs (ros-navigation#3868) (ros-navigation#3869)

* adding regenerate noise param + adding docs

* fix tests

* remove unnecessary normalization

* Update optimizer.cpp

(cherry picked from commit 924f167)

Co-authored-by: Steve Macenski <[email protected]>

* [MPPI] Reworked Path Align Critic; 70% faster + Tracks Paths Better! Edit: strike that, now 80% (ros-navigation#3872) (ros-navigation#3881)

* adding regenerate noise param + adding docs

* fix tests

* remove unnecessary normalization

* Update optimizer.cpp

* adding refactored path alignment critic

* fix visualization bug

* speed up another 30%

* remove a little jitter

* a few more small optimizaitons

* fixing unit tests

* retain legacy critic

* adding tests for legacy

(cherry picked from commit 7009ffb)

Co-authored-by: Steve Macenski <[email protected]>

* revert back to no gps waypoint follower

* Use mutex to protect costmap reads. (ros-navigation#3877) (ros-navigation#3896)

* Use mutex to protect costmap reads.
Otherwise costmap can be read during a map update and return 0.

* Revert "Use mutex to protect costmap reads."

This reverts commit e16a44c.

* Lock costmap before running MPPI controller.

* Fix typo.

* Protect against costmap updates in MPP and RotationShim controllers.

---------

Co-authored-by: Leif Terry <[email protected]>
(cherry picked from commit a1c9fd5)

Co-authored-by: LeifHookedWireless <[email protected]>

* Adjust the Variable types in Nav2_costmap_2d pkg in [nav2_humble]  ros-navigation#3891 (ros-navigation#3900) (ros-navigation#3901)

* image.hpp ros-navigation#3891

* Update image.hpp

(cherry picked from commit 7a7c6da)

Co-authored-by: GoesM <[email protected]>

* Log if BT rate is exceeded (ros-navigation#3909) (ros-navigation#3912)

(cherry picked from commit a11cdd8)

Co-authored-by: Steve Macenski <[email protected]>

* Fixing subtree issues with blackboard shared resources (3640) (ros-navigation#3911) (ros-navigation#3915)

* fixing subtree issues

* Update bt_action_server_impl.hpp

(cherry picked from commit 4b4465d)

Co-authored-by: Steve Macenski <[email protected]>

* Update theta_star_planner.cpp (ros-navigation#3918) (ros-navigation#3921)

(cherry picked from commit 0629ff3)

Co-authored-by: Steve Macenski <[email protected]>

* Change custom semantic segmentation message for image

* Handle NaNs in AMCL beam sensor model (ros-navigation#3929) (ros-navigation#3936)

* Handle NaNs in AMCL beam sensor model

Signed-off-by: Michel Hidalgo <[email protected]>

* Use proper isnan check

Signed-off-by: Michel Hidalgo <[email protected]>

---------

Signed-off-by: Michel Hidalgo <[email protected]>
(cherry picked from commit 06c3550)

Co-authored-by: Michel Hidalgo <[email protected]>

* Fix NaN in Updated PathAlign (ros-navigation#3943) (ros-navigation#3944)

(cherry picked from commit 3d14d98)

Co-authored-by: Steve Macenski <[email protected]>

* Fix for  robot footprint collision in obstacles critic (ros-navigation#3878) (ros-navigation#3946)

* Inscribed/Circumscribed costs must be updated to take into account the
current shape of the robot.
Was previous only being called once in initialize().

* Add early return to avoid calculations if footprint has not changed.

* Only update radius if using footprint.
Add perf timers.

* Remove perf timers.

* Update comments.

---------

Co-authored-by: Leif Terry <[email protected]>
(cherry picked from commit 98af3b9)

Co-authored-by: LeifHookedWireless <[email protected]>

* Enabling soft realtime prioritization to the Controller Server (ros-navigation#3914) (ros-navigation#3975)

* Enabling soft realtime prioritization to the controller server

* abstracting to another function

* changing default priorities

* linting

(cherry picked from commit fbe8f56)

Co-authored-by: Steve Macenski <[email protected]>

* Integration of mapping api with dynamic velocities changes

* simplify logic

* eliminate un-necessary lines of code

* style

* style2

* remove duplicate line from merge

* remove blank line

* restore nav2_utils copy_all_paramteres function.

* Add segmentation confidence plugin

* Remove deprecated segmentation file

* Docstrings and remove repeated struct

* Add docstrings & minor changes

---------

Signed-off-by: Ryan Friedman <[email protected]>
Signed-off-by: Nick Lamprianidis <[email protected]>
Signed-off-by: ymd-stella <[email protected]>
Signed-off-by: Christian Henkel <[email protected]>
Signed-off-by: Mannucci, Anna (Bosch (CR)) <[email protected]>
Signed-off-by: Anton Kesy <[email protected]>
Co-authored-by: stevemacenski <[email protected]>
Co-authored-by: Ruffin <[email protected]>
Co-authored-by: Alexandr Buyval <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: BriceRenaudeau <[email protected]>
Co-authored-by: Hyung-Taik Choi <[email protected]>
Co-authored-by: Alexey Merzlyakov <[email protected]>
Co-authored-by: Filipe Cerveira <[email protected]>
Co-authored-by: Joshua Wallace <[email protected]>
Co-authored-by: mergify[bot] <37929162+mergify[bot]@users.noreply.github.com>
Co-authored-by: Aaditya Ravindran <[email protected]>
Co-authored-by: Ryan <[email protected]>
Co-authored-by: RBT22 <[email protected]>
Co-authored-by: Nick Lamprianidis <[email protected]>
Co-authored-by: ymd-stella <[email protected]>
Co-authored-by: DylanDeCoeyer-Quimesis <[email protected]>
Co-authored-by: Aaditya Ravindran <[email protected]>
Co-authored-by: gyaanantia <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: xianglunkai <[email protected]>
Co-authored-by: Chuanhong Guo <[email protected]>
Co-authored-by: Christian Henkel <[email protected]>
Co-authored-by: Hyunseok <[email protected]>
Co-authored-by: Anna Mannucci <[email protected]>
Co-authored-by: Mannucci, Anna (Bosch (CR)) <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Anton Kesy <[email protected]>
Co-authored-by: jediofgever <[email protected]>
Co-authored-by: LeifHookedWireless <[email protected]>
Co-authored-by: GoesM <[email protected]>
Co-authored-by: Michel Hidalgo <[email protected]>
Co-authored-by: Sebastian Solarte <[email protected]>
enricosutera pushed a commit to enricosutera/navigation2 that referenced this pull request May 19, 2024
…#3878)

* Inscribed/Circumscribed costs must be updated to take into account the
current shape of the robot.
Was previous only being called once in initialize().

* Add early return to avoid calculations if footprint has not changed.

* Only update radius if using footprint.
Add perf timers.

* Remove perf timers.

* Update comments.

---------

Co-authored-by: Leif Terry <[email protected]>
Signed-off-by: enricosutera <[email protected]>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants