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

Create Planner Benchmark, set planner to RRT* #204

Merged
merged 7 commits into from
Feb 5, 2025

Conversation

amalnanavati
Copy link
Contributor

@amalnanavati amalnanavati commented Nov 14, 2024

Description

I've been noticing many more planning failures lately (summer onwards) than we had in our Jan study. It turns out, that when I switched our default planner to RRTConnect #181 (side-note: I should not have done it as part of an unrelated PR), I did not add path shortening. This was resulting in the outputted plans having large swivels, which out system rejected.

This PR addresses that.

Testing procedure

Empirically, I tried this with 8 bites of string cheese at various locations on the plate, and none of them had a planning failure.

Before opening a pull request

  • Format your code using black formatter python3 -m black .
  • Run your code through pylint and address all warnings/errors. The only warnings that are acceptable to not address is TODOs that should be addressed in a future PR. From the top-level ada_feeding directory, run: pylint --recursive=y --rcfile=.pylintrc ..

Before Merging

  • Squash & Merge

Copy link
Contributor

@jjaime2 jjaime2 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Changes seem trivial enough, only wonder if we should validate on cubed melon since we saw several failures on that food type during the showcase.

@siddhss5
Copy link

siddhss5 commented Nov 14, 2024 via email

@amalnanavati
Copy link
Contributor Author

Ah, the path shortening algorithm is what I missed. Thanks for the correction!

I added AnytimePathShortening to our MoveIt config (ada_ros2#50) and empirically tested it on 8 pieces of string cheese. The planning failures are all resolved and the plans don't have swivels (big win), but empirically planning takes ~1.5x longer.

I'm currently working on a script to benchmark the "move above food" plans in sim, to get quantitative guidance for tuning AnytimePathShortening parameters, and to protect against future regressions.

@amalnanavati amalnanavati changed the title Switch default to RRT* Add AnytimePathShortening on top of Default RRTConnect Nov 14, 2024
@siddhss5
Copy link

siddhss5 commented Nov 14, 2024 via email

@amalnanavati
Copy link
Contributor Author

Quantitatively benchmarking on 192 "above food" plans (varying x, y, fork roll, and fork pitch), I'm not yet seeing the gains of Path Shortening + RRTConnect above RRT*. I'll play around with the path shortening parameters more (here), but let me know if you have suggestions.

Planner Success Rate Median Path Length (rad) Success Rate w/ Path Length Cutoffs Median Elapsed Time
AnytimePathShortening[RRTConnect] 0.89 3.29 0.67 2.73
RRT* 0.96 0.78 0.93 2.70
RRTConnect 0.97 3.68 0.58 1.00

@amalnanavati
Copy link
Contributor Author

amalnanavati commented Dec 3, 2024

Some updates:

MoveIt2 by default runs hybridization and shortcutting (via OMPL’s implementations). It runs num_planning_attempts planners (up to 4 at a time in parallel), hybridizes their results, and then uses any remaining time in allowed_planning_time to shortcut the resultant path. I have verified this both by going through the source code and by tracking debug logs. As a result of this, wrapping RRTConnect in AnytimePathShortening is not necessary – even what we were doing before this PR was hybridizing and shortcutting the results of RRTConnect. (And, for what it’s worth, even what we were running in the January study did hybridization and shortcutting on top of RRT*).

The next question, then, is why we are seeing increased path length when switching from hybridized-and-shortcutted (HAS) RRT* (Jan study) to hybridized-and-shortcutted (HAS) RRTConnect (Sep study). I think some of that had to do with insufficiently-tuned parameters. I had spent some cycles in 2023 tuning range for RRT*, but didn’t do that anew for RRTConnect. After some parameter tuning on RRTConnect, I found that a range of 0.01 works best, coupled with 24 planning attempts (it makes sense that RRTConnect should have a smaller range than RRT*'s 3.0, since RRTConnect doesn’t rewire).

However, even with the parameter tuning, I'm seeing much more variability in HAS-RRTConnect than HAS-RRT*. Keeping all parameters fixed and running both planners on the same 192 pose goals, HAS-RRTConnect's median path length varies from 1.4 to 3.1 rads, whereas HAS-RRT*'s is consistently 1.2. Further, in general MoveIt2 isn't great about guarenteeing the planner will return within allowed_planning_time, but even so HAS-RRTConnect has more variability---it is 1.4-2.6s whereas HAS-RRT* is consistently 1.0s.

TODOs:

  • Run it on lovelace, to see performance on production hardware (the above results were from weebo).
  • Percolate any parameter changes (num_planning_attempts from 5-->24 and allowed_plkanning_time from 2.0-->0.5) to the main system.
  • Decide whether our production system will use HAS-RRT* or HAS-RRTConnect.
  • Create an issue for follow-up TODOs re. speeding up the planning pipeline as a whole.

@siddhss5
Copy link

siddhss5 commented Dec 3, 2024 via email

@amalnanavati amalnanavati force-pushed the amaln/rrt-star branch 2 times, most recently from 2428cf3 to 1082c51 Compare December 16, 2024 23:07
@amalnanavati
Copy link
Contributor Author

amalnanavati commented Feb 5, 2025

Moving offline discussion here.

We ran a thorough benchmark of 192 different feasible "above food" forktip poses, to thoroughly understand the differences between: (1) RRTConnect con-con w/ MoveIt/OMPL's default hybridization and path shortening; (2) RRTConnect con-con w/ AnytimePathShortening wrapped around it; and (3) RRT*. The detailed results (available to anyone w/ a UW CSE email account) can be found here.

The TL;DR is that RRTConnect con-con does perform faster than RRT* (50th percentile of 0.15s vs. 0.5s), but its paths are considerably longer (50th percentile joint-space path length of 4.2rad vs. 0.8rad).

Based on observations and conversations with users, the frustration of having a bite acquisition attempt fail before the robot even moves (due to the system rejecting plans that are too long / have large swivels) is greater than the frustration of waiting an additional 0.4s for a bite. Thus, for the time being, I will merge this in with RRT*, and will create an issue (#214 ) to continue investigating it further.

Note that although we reverted back to RRT*, several positive outcomes still came out of this exercise:

  1. Realizing we can reduce RRT*'s allowed planning time from 2.0s to 0.5s and still get good paths.
  2. Creating a comprehensive planner benchmark for acquisition.
  3. Doing a deep dive into MoveIt/OMPL code (see the linked Google Doc above), which will accelerate further work on planner improvements.

@amalnanavati amalnanavati changed the title Add AnytimePathShortening on top of Default RRTConnect Create Planner Benchmark, set planner to RRT* Feb 5, 2025
@amalnanavati amalnanavati merged commit 2672231 into ros2-devel Feb 5, 2025
1 check passed
@amalnanavati amalnanavati deleted the amaln/rrt-star branch February 5, 2025 20:06
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.

4 participants