Gazebo Simulation

:::warning Gazebo was previously known as "Gazebo Ignition" (while Gazebo Classic was previously known as Gazebo). See the official blog post for more information. :::

Gazebo is an open source robotics simulator. It supersedes the older Gazebo Classic simulator, and is the only supported version of Gazebo for Ubuntu 22.04 and onwards.

Supported Vehicles: Quadrotor, Plane, VTOL

@youtube

:::note See Simulation for general information about simulators, the simulation environment, and simulation configuration (e.g. supported vehicles). :::

Installation (Ubuntu Linux)

Gazebo is installed by default on Ubuntu 22.04 as part of the development environment setup: Ubuntu Dev Environment Setup > Simulation and NuttX (Pixhawk) Targets

If you want to use Gazebo on Ubuntu 20.04 you can install it manually after following the normal setup process (installing gz-garden will uninstall Gazebo-Classic!):

sudo wget https://packages.osrfoundation.org/gazebo.gpg -O /usr/share/keyrings/pkgs-osrf-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/pkgs-osrf-archive-keyring.gpg] http://packages.osrfoundation.org/gazebo/ubuntu-stable $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/gazebo-stable.list > /dev/null
sudo apt-get update
sudo apt-get install gz-garden

Running the Simulation

Gazebo SITL simulation can be conveniently run through a make command as shown below:

cd /path/to/PX4-Autopilot
make px4_sitl gz_x500

This will run both the PX4 SITL instance and the Gazebo client. Note that all gazebo make targets have the prefix gz_.

The supported vehicles and make commands are listed below.

Vehicle

Command

PX4_SYS_AUTOSTART

make px4_sitl gz_x500

4001

make px4_sitl gz_x500_depth

4002

make px4_sitl gz_x500_vision

4005

make px4_sitl gz_standard_vtol

4003

make px4_sitl gz_rc_cessna

4004

The commands above launch a single vehicle with the full UI. QGroundControl should be able to automatically connect to the simulated vehicle.

In order to run the simulation without running the Gazebo gui, use the HEADLESS=1 flag:

HEADLESS=1 make px4_sitl gz_x500

Usage/Configuration Options

The startup pipeline allows for highly flexible configuration. In particular, it is possible to:

  • Start a new simulation with an arbitrary world or attach to an already running simulation.

  • Add a new vehicle to the simulation or link a new PX4 instance to an existing one.

These scenarios are managed by setting the appropriate environment variables.

Syntax

The startup syntax takes the form:

ARGS ./build/px4_sitl_default/bin/px4

where ARGS is a list of environment variables including:

  • PX4_SYS_AUTOSTART (Mandatory): Sets the airframe autostart id of the PX4 airframe to start.

  • PX4_GZ_MODEL_NAME: Sets the name of an existing model in the gazebo simulation. If provided, the startup script tries to bind a new PX4 instance to the Gazebo resource matching exactly that name.

    • The setting is mutually exclusive with PX4_GZ_MODEL.

  • PX4_GZ_MODEL: Sets the name of a new Gazebo model to be spawned in the simulator. If provided, the startup script looks for a model in the Gazebo resource path that matches the given variable, spawns it and binds a new PX4 instance to it.

    • The setting is mutually exclusive with PX4_GZ_MODEL_NAME.

    :::note If both PX4_GZ_MODEL_NAME and PX4_GZ_MODEL are not given, then PX4 looks for PX4_SIM_MODEL and uses it as an alias for PX4_GZ_MODEL. However, this prevents the use of PX4_GZ_MODEL_POSE. :::

  • PX4_GZ_MODEL_POSE: Sets the spawning position and orientation of the model when PX4_GZ_MODEL is adopted. If provided, the startup script spawns the model at a pose following the syntax "x,y,z,roll,pitch,yaw", where the positions are given in metres and the angles are in radians.

    • If omitted, the zero pose [0,0,0,0,0,0] is used.

    • If less then 6 values are provided, the missing ones are fixed to zero.

    • This can only be used with PX4_GZ_MODEL (not PX4_GZ_MODEL_NAME).

  • PX4_GZ_WORLD: Sets the Gazebo world file for a new simulation. If it is not given, then default is used.

  • PX4_SIMULATOR=GZ: Sets the simulator, which for Gz must be gz.

The PX4 Gazebo worlds and and models databases can be found on Github here. They are added to the Gazebo search PATH by gz_env.sh.in during the simulation startup phase.

:::note gz_env.sh.in is compiled and made available in $PX4_DIR/build/px4_sitl_default/rootfs/gz_env.sh :::

Examples

Here are some examples of the different scenarios covered above.

  1. Start simulator + default world + spawn vehicle at default pose

    PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL=x500 ./build/px4_sitl_default/bin/px4
  2. Start simulator + default world + spawn vehicle at custom pose (y=2m)

    PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_POSE="0,2" PX4_GZ_MODEL=x500 ./build/px4_sitl_default/bin/px4
  3. Start simulator + default world + link to existing vehicle

    PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_NAME=x500 ./build/px4_sitl_default/bin/px4

Adding New Worlds and Models

New worlds files can simply be copied into the PX4 Gazebo world directory.

To add a new model:

  1. Add an sdf file in the PX4 Gazebo model directory.

  2. Define the default parameters for Gazebo in the airframe configuration file (this example is from x500 quadcopter):

    PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
    PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
    PX4_SIM_MODEL=${PX4_SIM_MODEL:=<your model name>}
    • PX4_SIMULATOR=${PX4_SIMULATOR:=gz} sets the default simulator (Gz) for that specific airframe.

    • PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} sets the default world for that specific airframe.

    • Setting the default value of PX4_SIM_MODEL lets you start the simulation with just

      PX4_SYS_AUTOSTART=<your new airframe id> ./build/px4_sitl_default/bin/px4

:::note As long as the world file and the model file are in the Gazebo search path IGN_GAZEBO_RESOURCE_PATH it is not necessary to add them to the PX4 world and model directories. However, make px4_sitl gz_<model>_<world> won't work with them. :::

Multi-Vehicle Simulation

Multi-Vehicle simulation is supported on Linux hosts.

For more information see: Multi-Vehicle Simulation with Gazebo

Further Information

Last updated