Skip to content
Rhys Mainwaring edited this page Aug 24, 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.

There are two branches with Ignition support: one uses the ArduPilot SITL-Gazebo backend with a binary protocol; the second uses the ArduPilot SITL-JSON backend. The set up for both is similar and described in more detail below.

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.

Using the ArduPilot SITL-Gazebo backend

The branch feature/ignition-edifice uses the ArduPilot SITL-Gazebo backend and is compatible with Ignition Edifice.

Setup

Clone the repo and build with:

git clone https://github.com/srmainwaring/ardupilot_gazebo.git -b feature/ignition-edifice
cd ardupilot_gazebo
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.

Quadcopter Takeoff

Using the ArduPilot SITL-JSON backend

The branch feature/ignition-edifice_json uses the ArduPilot SITL-JSON backend. The procedure to set up and and run the simulation is the same as for the SITL-Gazebo backend except for the differences below.

Setup

Clone the repo and build with:

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

Running

Run ArduPilot SITL

$ sim_vehicle.py -v ArduCopter -f JSON --add-param-file=$ARDUPILOT_HOME/Tools/autotest/default_params/gazebo-iris.parm --aircraft=iris --map --console

Ubuntu Virtual Machines

Hardware accelerated 3D graphics

To run ignition gazebo with accelerated 3D graphics on an Ubuntu virtual machine you need to set additional environment variables to disable some of the OpenGL extensions in the VMware SVGA driver. Ubuntu 20.04.2.0 or later is required, earlier versions do not have the Mesa drivers to support the OpenGL features required by the ogre2 render engine used by gazebo.

The following environment variables apply to a macOS Big Sur 11.4 host (AMD Radeon Pro W5700X 16GB) with an Ubuntu 20.04.2.0 guest on VMware. You may need to experiment with the choice of extensions depending upon the OpenGL support of your GPU.

# set_mesa_env

# Configure the Mesa Environment
# https://docs.mesa3d.org/envvars.html

# Core Mesa environment variables
export MESA_DEBUG=1
export MESA_GL_VERSION_OVERRIDE=4.1
export MESA_GLSL_VERSION_OVERRIDE=410
export MESA_EXTENSION_OVERRIDE="\
  -GL_ARB_buffer_storage \
  -GL_ARB_multi_draw_indirect \
  -GL_ARB_texture_buffer_range \
  -GL_ARB_compute_shader \
  -GL_ARB_ES3_compatibility \
  "

Time synchronisation

When time synchronisation is enabled using VMware Tools, the guest VM may step back in time. This causes the ignition server and gui to get out of sync and also causes issues between the ArduPilot Gazebo plugin and SITL. When this happens the gui will not update visuals (the drone appears frozen) and MAVProxy will display warnings such as:

GUIDED> arm throttle
GUIDED> Warning, time moved backwards. Restarting timer.
Warning, time moved backwards. Restarting timer.
Warning, time moved backwards. Restarting timer.
Warning, time moved backwards. Restarting timer.
Warning, time moved backwards. Restarting timer.
Warning, time moved backwards. Restarting timer.
Warning, time moved backwards. Restarting timer.
Warning, time moved backwards. Restarting timer.

A workaround is to disable VMware tools timesync:

$ vmware-toolbox-cmd timesync disable

Other platforms

There is experimental support for ignition gazebo and the ArduPilot plugin running natively on macOS. This is ongoing development work and for those interested in assisting see the ogre-next, ignition-rendering and ignition-gazebo GitHub repo issue and PR lists for work in progress.

As far as I'm aware, there is no native support for Windows at present.

Clone this wiki locally