A ROS 2 Humble simulation package for the Boston Dynamics Spot robot using Ignition/Gazebo Sim (the successor to Gazebo Classic). This package provides:
- Full URDF/SDF robot description for simulation
- Integration with CHAMP quadruped controller
- Launch files for easy simulation setup
- Gazebo world configurations
- ROS 2/Gazebo bridge configuration for sensor and control interfaces
- All mesh and material files are referenced using Fuel URLs from fuel.gazebosim.org for convenience.
- Currently all body camera and depth sensors are not used. Thus they are disabled to save computations.
champ- Core CHAMP quadruped controller integration package adapted for ROS 2 Humble and Spotchamp_base- Base implementation of quadruped controller with gait generators and kinematicschamp_config- Configuration package containing robot-specific parameters and settings for the CHAMP quadruped controllerchamp_msgs- Custom ROS 2 message definitions for quadruped control and state informationspot_bringup- Launch files and configuration to start Spot simulation with all required nodesspot_description- URDF and SDF robot description files defining Spot's model for ROS 2 and Gazebospot_gazebo- Ignition Gazebo simulation specific files including worlds and simulation plugins
- Ubuntu 22.04
- ROS 2 humble
- Gazebo Fortress
- Install dependencies
cd ~/ros2_ws source /opt/ros/humble/setup.bash sudo rosdep init rosdep update rosdep install --from-paths src --ignore-src -r -i -y --rosdistro humble
- Build the project
colcon build --cmake-args -DBUILD_TESTING=ON
- Source the workspace
source ~/ros2_ws/install/setup.sh
- Launch the simulation
ros2 launch spot_bringup spot.gazebo.launch.py
- Start the gazebo siimulation
ros2 launch spot_bringup spot.gazebo.launch.py rviz:=false
- Use
SLAMto build a map
ros2 launch spot_navigation online_async_launch.py
- Once the map is built and saved
ros2 launch spot_navigation localization_launch.py map:=simple_tunnel.yaml use_sim_time:=true rviz:=true
NOTE currently the quality of AMCL is really bad so better find something better to use
- Integrate a better controller like
- champ ros2 branch.
- spot_config with some modification.
- spot_description for URDF.












