ROS 2 with Gazebo

The purpose of this guide is to show how to integrate ArduPilot with Gazebo using ROS 2.

Prerequisites

Ensure you have the prerequisites complete and working before beginning this Gazebo tutorial.

  1. Install ROS 2

  2. Install and Run ROS 2 with ArduPilot SITL

Install Gazebo

First, install Gazebo Garden or Gazebo Harmonic

Next, set up all the necessary ROS 2 packages in the workspace.

We will clone the required repositories using vcstool and a ros2.repos files:

cd ~/ros2_ws
vcs import --input https://raw.githubusercontent.com/ArduPilot/ardupilot_gz/main/ros2_gz.repos --recursive src

Set the gazebo version to either garden or harmonic

export GZ_VERSION=garden

Update ROS dependencies:

cd ~/ros2_ws
source /opt/ros/humble/setup.bash
sudo apt update
rosdep update
rosdep install --from-paths src --ignore-src -r

Build and Run Tests

Build:

cd ~/ros2_ws
colcon build --packages-up-to ardupilot_gz_bringup

If you’d like to test your installation, run:

cd ~/ros2_ws
source install/setup.bash
colcon test --packages-select ardupilot_sitl ardupilot_dds_tests ardupilot_gazebo ardupilot_gz_applications ardupilot_gz_description ardupilot_gz_gazebo ardupilot_gz_bringup
colcon test-result --all --verbose

Run the Simulation

Finally, you can source the workspace and launch one of the example Gazebo simulations:

source install/setup.bash
ros2 launch ardupilot_gz_bringup iris_runway.launch.py

By default, this launch file starts ArduPilot SITL, Gazebo, and RViz with a single command.

../_images/IrisRunway.png

For more information regarding the ardupilot_gz package refer to ardupilot_gz/README.md.

Examples available

  • Iris Runway (Copter)

ros2 launch ardupilot_gz_bringup iris_runway.launch.py
  • Iris Maze (Copter)

ros2 launch ardupilot_gz_bringup iris_maze.launch.py
  • WildThumper (Rover)

ros2 launch ardupilot_gz_bringup wildthumper.launch.py

Here is a demo video of ArduPilot working with ROS 2 and Gazebo:

Next up

Run Cartographer SLAM in Cartographer SLAM with ROS 2 in SITL