ROS 2 with Gazebo

Once ROS2 is correctly installed and running sitl, we can integrate Ardupilot with Gazebo.

First, install Gazebo Garden <https://gazebosim.org/docs/garden/install>.

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

We will clone the required repositories using vcstool <https://github.com/dirk-thomas/vcstool> and a ros2.repos files:

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

Set the gazebo version

export GZ_VERSION=garden

Update ROS dependencies:

cd ~/ros2_ws
source /opt/ros/humble/setup.bash
sudo apt update
rosdep update
rosdep install --rosdistro $ROS_DISTRO --from-paths src -i -r -y

Build:

cd ~/ros2_ws
colcon build --cmake-args -DBUILD_TESTING=ON

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

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

source ~/ros2_ws/install/setup.sh
ros2 launch ardupilot_gz_bringup iris_runway.launch.py

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

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