CUDA-Accelerated Autonomous Navigation for Unitree Go2 Quadruped Robot
Features • Architecture • Quick Start • CUDA Acceleration • FAQ
This repository contains a complete autonomous navigation stack for the Unitree Go2 quadruped robot, featuring:
- DLIO - Direct LiDAR-Inertial Odometry with CUDA-accelerated GICP
- Open3D SLAM - Dense mapping and localization
- Far Planner - GPU-accelerated visibility graph planning
- Terrain Analysis - Real-time traversability assessment
- Local Planner - Reactive obstacle avoidance
LiDAR + IMU --> DLIO --> Open3D SLAM --> Terrain Analyzer --> Far Planner --> Local Planner --> Go2 Robot
| |
Odometry Terrain Map Ext
| Component | Description | Acceleration |
|---|---|---|
| DLIO | LiDAR-Inertial Odometry | CUDA (GICP) |
| Far Planner | Global path planning | CUDA (Visibility Graph) |
| Boundary Handler | Obstacle boundary processing | CUDA |
| Terrain Analysis | Traversability mapping | CPU + OpenMP |
| Local Planner | Reactive navigation | CPU |
The cyan lines show the visibility graph - navigation nodes that can "see" each other without obstacles. This computation is GPU-accelerated for real-time performance.
- ROS2 Humble
- CUDA 11.0+ (for GPU acceleration)
- Unitree Go2 SDK (for real robot)
# Clone the repository
git clone https://github.com/Quadruped-dyn-insp/Go2_planner_suite.git
cd Go2_planner_suite
# Build all workspaces
./scripts/build.sh./scripts/sim.sh./scripts/launch.sh| Operation | CPU Time | GPU Time | Speedup |
|---|---|---|---|
| Point Transform | O(N) seq | O(N/1024) parallel | ~100x |
| KNN Search | O(NxM) seq | O(NxM/1024) parallel | ~50x |
| Hessian Computation | O(N) seq | O(N/1024) parallel | ~100x |
| Scenario | Nodes | Edges | CPU Time | GPU Time |
|---|---|---|---|---|
| Small | 100 | 500 | 2.5 sec | 10 ms |
| Medium | 500 | 2000 | 4 min | 100 ms |
| Large | 1000 | 5000 | 42 min | 500 ms |
// DLIO - Point cloud registration
__global__ void transformPointsKernel(...);
__global__ void knnSearchKernel(...);
__global__ void computeHessianKernel(...);
// Far Planner - Visibility checking
__global__ void ComputeVisibilityConnections(...);
__device__ bool IsEdgeCollidePolygons_GPU(...);
__device__ bool doIntersect_GPU(...);Go2_planner_suite/
├── scripts/
│ ├── build.sh # Build all workspaces
│ ├── launch.sh # Launch real robot
│ └── sim.sh # Launch simulation
├── config/ # Global configuration
├── docs/
│ ├── images/ # Documentation images
│ └── setup/ # Setup guides
└── workspaces/
├── autonomous_exploration/ # Mid-layer framework
│ ├── local_planner/ # Reactive navigation
│ ├── terrain_analysis/ # Traversability
│ ├── loam_interface/ # Odometry bridge
│ └── vehicle_simulator/ # Gazebo simulation
├── dlio/ # CUDA-accelerated odometry
│ └── src/nano_gicp/cuda/ # GICP CUDA kernels
├── far_planner/ # CUDA-accelerated planner
│ ├── far_planner/ # Core planner + CUDA
│ └── boundary_handler/ # Boundary CUDA kernels
├── open3d_slam_ws/ # Dense mapping
└── pipeline_launcher/ # System orchestration
Q: What robot is this designed for?
A: Unitree Go2 quadruped robot with a Livox Mid-360 LiDAR and built-in IMU. It can be adapted for other robots by modifying the URDF and sensor configurations.
Q: Can I run this without a GPU?
A: Yes, but with reduced performance. The CUDA kernels have CPU fallbacks, but expect 10-100x slower planning and odometry in complex environments.
Q: What's the minimum GPU requirement?
A: Any CUDA-capable GPU with compute capability 6.0+ (Pascal or newer). Recommended: GTX 1060 or better for real-time performance.
Q: Why is my RViz display blank?
A: Check these in order:
- Verify
/state_estimationis publishing:ros2 topic hz /state_estimation - Check TF tree is connected:
ros2 run tf2_tools view_frames - Set RViz Fixed Frame to
map - Ensure
/registered_scanhas data:ros2 topic echo /registered_scan --once
Q: DLIO is not receiving IMU data?
A: Check:
- IMU topic name matches config:
ros2 topic list | grep imu - IMU data rate is sufficient (>100Hz recommended)
- Timestamps are synchronized with LiDAR
Q: Open3D SLAM shows "Failed to add odometry pose to buffer"?
A: This means DLIO odometry isn't reaching Open3D SLAM. Verify:
- DLIO is running and publishing
/odom_dlio - Topic remapping is correct in launch file
- Timestamps are valid (not zero)
Q: The visibility graph has too many/few connections?
A: Adjust these parameters in Far Planner config:
nav_clear_dist: Minimum clearance from obstacles (increase = fewer connections)project_dist: Maximum connection distance (decrease = fewer long connections)
Q: Path planning is slow even with GPU?
A: Check:
- CUDA is actually being used: look for "CUDA available" in logs
- Reduce number of navigation nodes if environment is too complex
- Verify GPU isn't thermal throttling:
nvidia-smi
Q: Robot doesn't follow the planned path?
A: The local planner may be overriding due to obstacles. Check:
/terrain_mapshows correct obstacles- Local planner parameters aren't too aggressive
- TF between
mapandbase_linkis accurate
Q: Gazebo crashes on startup?
A: Common fixes:
- Install missing dependencies:
pip install lxml - Kill zombie processes:
pkill -9 gzserver; pkill -9 gzclient - Check GPU drivers:
nvidia-smi - Reduce world complexity
Q: Robot falls through the ground in simulation?
A: Check:
- Spawn height in launch file (should be ~0.275m for Go2)
- Gazebo physics step size isn't too large
- Contact sensor plugin is loaded
Q: Controller manager service not available?
A: The robot model didn't spawn correctly. Check:
spawn_entity.pycompleted without errors- URDF/Xacro files are valid
- Gazebo plugins are installed
Q: CUDA compilation fails?
A: Ensure:
- CUDA toolkit is installed:
nvcc --version - Environment is set:
source /usr/local/cuda/bin/setup.sh - CMake can find CUDA: check
CMAKE_CUDA_COMPILER - GPU architecture matches: set
CMAKE_CUDA_ARCHITECTURES
Q: Missing ROS2 packages?
A: Install common dependencies:
sudo apt install ros-humble-pcl-ros ros-humble-tf2-ros \
ros-humble-nav-msgs ros-humble-geometry-msgs \
ros-humble-gazebo-ros-pkgsQ: Python module not found errors?
A: ROS2 Humble uses Python 3.10. If using conda:
conda deactivate # Use system Python for ROS
# OR
pip install <package> --target=/opt/ros/humble/lib/python3.10/site-packages| Parameter | File | Description |
|---|---|---|
sensor_frame |
DLIO config | LiDAR frame name |
nav_clear_dist |
Far Planner | Obstacle clearance |
terrain_resolution |
Terrain Analysis | Grid cell size |
local_planner_freq |
Local Planner | Control loop rate |
# Common remappings for real robot
/velodyne_points: /livox/lidar
/imu/data: /livox/imu
/odom: /odom_dlio| Module | Input Size | CPU Time | GPU Time |
|---|---|---|---|
| DLIO GICP | 10K points | 45 ms | 3 ms |
| Far Planner | 500 nodes | 240 sec | 0.1 sec |
| Terrain Analysis | 100K points | 15 ms | 15 ms* |
*Terrain analysis uses CPU+OpenMP (CUDA version planned)
- Fork the repository
- Create a feature branch:
git checkout -b feature/amazing-feature - Commit changes:
git commit -m 'Add amazing feature' - Push to branch:
git push origin feature/amazing-feature - Open a Pull Request
This project is licensed under the MIT License - see the LICENSE file for details.
- DLIO - Base odometry implementation
- FAR Planner - Planning algorithms
- Unitree Robotics - Go2 robot platform
Built for autonomous quadruped navigation



