8000 GitHub - CoMMALab/pRRTC: GPU-Parallel RRT-Connect
[go: up one dir, main page]
More Web Proxy on the site http://driver.im/
Skip to content

CoMMALab/pRRTC

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

pRRTC: GPU-Parallel RRT-Connect

arXiv VAMP

This repository holds the code for IROS 2025 submission "pRRTC: GPU-Parallel RRT-Connect for Fast, Consistent, and Low-Cost Motion Planning."

We introduce pRRTC, a GPU-based, parallel RRT-Connect-based algorithm. Our approach has three key improvements:

  • Concurrent sampling, expansion and connection of start and goal trees via GPU multithreading
  • SIMT-optimized collision checking to quickly validate edges, inspired by the SIMD-optimized validation of Vector-Accelerated Motion Planning
  • Efficient memory management between block- and thread-level parallelism, reducing expensive memory transfer overheads

Our empirical evaluations show that pRRTC achieves up to 6x average speedup on constrained reaching tasks at high collision checking resolution. pRRTC also demonstrates a 5x reduction in solution time variance and 1.5x improvement in initial path costs compared to state-of-the-art motion planners in complex environments.

Supported Robots

pRRTC currently supports 7-DoF Franka Emika Panda, 8-DoF Fetch, and 14-DoF Rethink Robotics Baxter.

Building Code

To build pRRTC, follow the instructions below

git clone git@github.com:CoMMALab/pRRTC.git
cmake -B build
cmake --build build

Running Code

The repository comes with two benchmarking scripts: evaluate_mbm.cpp and single_mbm.cpp.

evaluate_mbm.cpp allows users to benchmark pRRTC's performance using Panda, Fetch, or Baxter on the entire MotionBenchMaker dataset. To run evaluate_mbm.cpp:

build/evaluate_mbm <robot> <experiment name>

single_mbm.cpp allows users to benchmark pRRTC's performance using Panda, Fetch, or Baxter on a single problem of MotionBenchMaker. To run single_mbm.cpp:

build/single_mbm <robot> <MBM problem name> <MBM problem index>

The MotionBenchMaker JSON files are generated using the script detailed here.

Planner Configuration

pRRTC has the following parameters which can be modified in the benchmarking scripts:

  • max_samples: maximum number of samples in trees
  • max_iters: maximum number of planning iterations
  • num_new_configs: amount of new samples generated per iteration
  • range: maximum RRT-Connect extension range
  • granularity: number of discretized motions along an edge during collision checking
  • balance: whether to enable tree balancing -- 0 for no balancing; 1 for distributed balancing where each iteration may generate samples for one or two trees; 2 for single-sided balancing where each iteration generate samples for one tree only
  • tree_ratio: the threshold for distinguishing which tree is smaller in size -- if balance set to 1, then set tree_ratio to 0.5; if balance set to 2, then set tree_ratio to 1
  • dynamic_domain: whether to enable dynamic domain sampling -- 0 for false; 1 for true
  • dd_alpha: extent to which each radius is enlarged or shrunk per modification
  • dd_radius: starting radius for dynamic domain sampling
  • dd_min_radius: minimum radius for dynamic domain sampling
0