This repository contains the ROS 2 Gazebo simulation packages for the Unitree Go2 quadruped robot. It provides a complete simulation environment with Gazebo, including mapping and navigation capabilities with support for tight-space navigation testing.
- Gazebo Simulation: Realistic physics simulation of the Unitree Go2.
- Navigation Stack (Nav2): Fully configured navigation stack for autonomous movement.
- SLAM: Mapping capabilities using
slam_toolbox. - LiDAR Support: Simulation of Velodyne VLP-16 and Unitree 4D LiDAR.
- Mini Maze World: Test environment with narrow corridors (0.85-0.9m), ramps, and obstacles for tight-space navigation testing.
-
Navigate to your
unitree-sdkdirectory (assuming it is in your workspacesrc):cd ~/unitree-sdk
-
Clone this repository as a submodule:
git clone https://github.com/OpenMind/go2_gazebo_sim.git
-
Install dependencies:
rosdep install --from-paths . --ignore-src -r -y -
Build the workspace:
colcon build --symlink-install
-
Source the workspace:
source install/setup.bash -
Setup CycloneDDS The network interface is your WiFi adapter. Replace
wlxbc071d7223b6with your own network interface name found viaifconfigorip a.<CycloneDDS> <Domain> <General> <Interfaces> <NetworkInterface name="wlxbc071d7223b6" priority="default" multicast="default" /> </Interfaces> </General> </Domain> </CycloneDDS>
To launch the simulation and start mapping the environment:
ros2 launch go2_gazebo_sim go2_slam_launch.pyDefault world: maze_world.sdf (mini maze with narrow corridors and slopes)
To use a different world:
ros2 launch go2_gazebo_sim go2_slam_launch.py world:=default.sdfIn a new terminal, run the teleop keyboard node to drive the robot around:
ros2 run teleop_twist_keyboard teleop_twist_keyboardUse the keyboard controls displayed in the terminal to move the robot:
i- Move forward,- Move backwardj- Turn leftl- Turn rightk- Stopu/o/m/.- Move diagonally
Drive the robot around to cover the entire area and build a complete map.
Once you are satisfied with the map, save it using the map saver CLI:
cd ~
ros2 run nav2_map_server map_saver_cli -f my_mapThis will create my_map.yaml and my_map.pgm in your home directory.
To launch the simulation with the navigation stack using your saved map:
ros2 launch go2_gazebo_sim go2_nav_launch.py map:=${HOME}/my_map.yamlTo use a different world:
ros2 launch go2_gazebo_sim go2_nav_launch.py world:=default.sdf map:=${HOME}/my_map.yamlYou can now set 2D Pose Estimates and Navigation Goals in RViz.
go2_gazebo_sim: Main Gazebo simulation launch files and configurations.go2_description: URDF, mesh files, and world definitions for the robot.champ: Quadruped controller framework.
- maze_world.sdf (default): Mini maze with narrow passages (0.85-0.9m wide), upward/downward ramps (15° slopes), and step platform for comprehensive navigation testing.
- default.sdf: Simple environment with ground plane for basic testing.
Special thanks to khaledgabr77/unitree_go2_ros2 and its contributors. This repository is built upon their excellent work.