Skip to content
Rhys edited this page Aug 21, 2021 · 17 revisions

ArduPilot Ignition Gazebo

This fork of ardupilot_gazebo incorporates @gerkey's port to ignition and has been updated to support Ignition Edifice.

Prerequisites

Ignition Edifice is supported on Ubuntu Bionic and Ubuntu Focal. If you are running Ubuntu as a virtual machine you will need Ubuntu 20.04 (Focal) in order to have the OpenGL support required for the ogre2 render engine.

Follow the instructions for a binary install of ignition edifice and verify that ignition gazebo is running correctly.

Set up an ArduPilot development environment. In the following it is assumed that you are able to run ArduPilot SITL using the MAVProxy GCS.

Setup

This branch feature/ignition-edifice of this fork is compatible with Ignition Edifice. Clone the repo and build with:

git clone https://github.com/srmainwaring/ardupilot_gazebo.git -b feature/ignition-edifice
mkdir build && cd build
cmake .. -DCMAKE_BUILD_TYPE=RelWithDebInfo
make -j4

Running

Configure the environment

We assume your platform is Ubuntu and the plugin code has been cloned into $HOME/Code/ardupilot/sim/ardupilot_gazebo. Set the ignition environment variables in your .bashrc or the terminal used run gazebo:

export IGN_CONFIG_PATH=/usr/share/ignition
export IGN_RENDERING_RESOURCE_PATH=/usr/share/ignition/ignition-rendering5
export IGN_GAZEBO_RESOURCE_PATH=$HOME/Code/ardupilot/sim/ardupilot_gazebo/models:$HOME/Code/ardupilot/sim/ardupilot_gazebo/worlds
export IGN_GAZEBO_SYSTEM_PLUGIN_PATH=/usr/lib/x86_64-linux-gnu/ign-gazebo-5/plugins:$HOME/Code/ardupilot/sim/ardupilot_gazebo/build

Run Gazebo

$ ign gazebo -v 4 iris_arducopter_runway.world

Run ArduPilot SITL

$ sim_vehicle.py -v ArduCopter -f gazebo-iris --map --console

Arm and takeoff

STABILIZE> mode guided
GUIDED> arm throttle
GUIDED> takeoff 5

This image shows the simulation running on an Ubuntu virtual machine hosted on macOS. The text overlay is presenting additional OpenGL information used to analyse the hardware acceleration on the VM.

Clone this wiki locally