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, Rover
INFO
See Simulation for general information about simulators, the simulation environment, and simulation configuration (e.g. supported vehicles).
Installation (Ubuntu Linux) 
Gazebo Harmonic is installed by default on Ubuntu 22.04 as part of the normal development environment setup.
Gazebo versions Harmonic, Ionic, and Jetty are supported on Ubuntu 24.04. The latest installed Gazebo release is used by default.
INFO
The PX4 installation scripts are based on the instructions: Binary Installation on Ubuntu (gazebosim.org).
WARNING
Gazebo Harmonic cannot be installed on Ubuntu 20.04 and earlier.
On Ubuntu 20.04 we recommend use Gazebo Classic. If you really must use Gazebo then you should update to Ubuntu 22.04.
Until November 2024 it is possible to install Gazebo Garden on Ubuntu 20.04. After that date Garden will reach end-of-life and should not be used.
Running the Simulation 
Gazebo SITL simulation can be conveniently run using a make command as shown below:
sh
cd /path/to/PX4-Autopilot
make px4_sitl gz_x500This runs both the PX4 SITL instance and the Gazebo client.
The supported vehicles and make commands are listed below. Note that all gazebo make targets have the prefix gz_.
| Vehicle | 통신 | PX4_SYS_AUTOSTART | 
|---|---|---|
| Quadrotor (x500) | make px4_sitl gz_x500 | 4001 | 
| X500 Quadrotor with Depth Camera (Front-facing) | make px4_sitl gz_x500_depth | 4002 | 
| Quadrotor(x500) with Vision Odometry | make px4_sitl gz_x500_vision | 4005 | 
| Quadrotor(x500) with 1D LIDAR (Down-facing) | make px4_sitl gz_x500_lidar_down | 4016 | 
| Quadrotor(x500) with 2D LIDAR | make px4_sitl gz_x500_lidar_2d | 4013 | 
| Quadrotor(x500) with 1D LIDAR (Front-facing) | make px4_sitl gz_x500_lidar_front | 4017 | 
| Quadrotor(x500) with gimbal (Front-facing) in Gazebo | make px4_sitl gz_x500_gimbal | 4019 | 
| VTOL | make px4_sitl gz_standard_vtol | 4004 | 
| Plane | make px4_sitl gz_rc_cessna | 4003 | 
| Advanced Plane | make px4_sitl gz_advanced_plane | 4008 | 
| Quad Tailsitter VTOL | make px4_sitl gz_quadtailsitter | 4018 | 
| Tiltrotor VTOL | make px4_sitl gz_tiltrotor | 4020 | 
| Differential Rover | make px4_sitl gz_rover_differential | 50000 | 
| Ackermann Rover | make px4_sitl gz_rover_ackermann | 51000 | 
| Mecanum Rover | make px4_sitl gz_rover_mecanum | 52000 | 
All vehicle models (and worlds) are included as a submodule from the Gazebo Models Repository repository.
The commands above launch a single vehicle with the full UI. QGroundControl should be able to automatically connect to the simulated vehicle.
Standalone Mode 
Another way that Gazebo SITL can be connected is in standalone mode. In this mode PX4 SITL and Gazebo are started separately in their own terminals. By default these terminals are on the same host, but you can also connect SITL and Gazebo instances running on any two devices on the network (or even different networks if you use a VPN to connect them).
You start PX4 in standalone mode by prefixing the make command with PX4_GZ_STANDALONE=1:
sh
cd /path/to/PX4-Autopilot
PX4_GZ_STANDALONE=1 make px4_sitl gz_x500PX4 SITL will then wait until it detects an instance of gz-server, and then connect to it.
INFO
If you have not yet started gz-server when you run the make command, you will see the following warning until gazebo has been started and an instance of gz-server is detected by PX4:
sh
WARN [gz bridge] Service call timed out as Gazebo has not been detectedThe simplest way to start the simulation is to use the Python script simulation-gazebo, which can be found in the Gazebo Models Repository repository. This can be used to launch a gz-server instance with any supported world and vehicle.
The script can be used without installing any additional dependencies, and will fetch the supported PX4 models and worlds on first use (by default) and save them to ~/.simulation-gazebo. If called again the script will use this directory to get models and worlds. Therefore if you want to use your own model and run it in standalone mode, you will have to place its source code in ~/.simulation-gazebo.
You can fetch the script locally using any method you like, such as wget:
sh
wget https://raw.githubusercontent.com/PX4/PX4-gazebo-models/main/simulation-gazeboThe script can be started with:
sh
cd /path/to/script/
python3 simulation-gazeboFor more information and arguments, see Gazebo Models.
INFO
If make px4_sitl gz_x500 gives the error ninja: error: unknown target 'gz_x500' then run make distclean to start from a clean slate, and try running make px4_sitl gz_x500 again.
Headless Mode 
You might want to run Gazebo in "headless mode" (without the Gazebo GUI) as it uses fewer resources, and does not rely on your system having a graphics card that properly supports OpenGL rendering. This makes it faster to load and run, and for many simple use cases may be all you need.
The simulation can be run in headless mode by prefixing the command with the HEADLESS=1 environment variable:
sh
HEADLESS=1 make px4_sitl gz_x500Set Custom Takeoff Location 
The takeoff location in Gazebo Classic can be set using environment variables.
The variables to set are: PX4_HOME_LAT, PX4_HOME_LON, and PX4_HOME_ALT.
예:
export PX4_HOME_LAT=51.1788
export PX4_HOME_LON=-1.8263
export PX4_HOME_ALT=101
make px4_sitl gz_x500Specify World 
The simulation can be run inside a particular world by concatenating the desired world to the name of the desired vehicle. For example, to run the windy world with the x500 vehicle you can specify:
sh
make px4_sitl gz_x500_windyYou can also specify the world using the PX4_GZ_WORLD environment variable:
sh
PX4_GZ_WORLD=windy make px4_sitl gz_x500The supported worlds are listed below.
| 전역 | 통신 | 설명 | 
|---|---|---|
| default | make px4_sitl * | Empty world (a grey plane) | 
| aruco | make px4_sitl *_aruco | Empty world with aruco marker for testing precision landing | 
| baylands | make px4_sitl *_baylands | Baylands world surrounded by water | 
| lawn | make px4_sitl *_lawn | Lawn world for testing rovers | 
| rover | make px4_sitl *_rover | Rover world (optimised/preferred) | 
| walls | make px4_sitl *_walls | Wall world for testing collision prevention | 
| windy | make px4_sitl *_windy | Empty world with wind enabled | 
| moving_platform | make px4_sitl *_moving_platform | World with moving takeoff / landing platform | 
WARNING
Note that if no world is specified, PX4 will use the default world. However you must not explicitly specify _default on the model as this will prevent PX4 from launching. In other words, use make px4_sitl gz_x500 instead of make px4_sitl gz_x500_default for the default.
INFO
Baylands world throws a warning in Gazebo Harmonic because there are so many meshes. This can be ignored:
sh
[Wrn] [SDFFeatures.cc:843] The geometry element of collision [collision] couldn't be createdChange Simulation Speed 
PX4 SITL can be run faster or slower than real-time when using Gazebo.
The speed factor is set using the environment variable PX4_SIM_SPEED_FACTOR. For example, to run the Gazebo simulation of the X500 frame at 2 times the real time speed:
sh
PX4_SIM_SPEED_FACTOR=2 make px4_sitl gz_x500To run at half real-time:
sh
PX4_SIM_SPEED_FACTOR=0.5 make px4_sitl gz_x500You can apply the factor to all SITL runs in the current session using EXPORT:
sh
export PX4_SIM_SPEED_FACTOR=2
make px4_sitl gz_x500INFO
At some point IO or CPU will limit the speed that is possible on your machine and it will be slowed down "automatically". 강력한 데스크탑 컴퓨터는 일반적으로 약 6-10x에서 시뮬레이션할 수 있으며, 노트북의 경우의 최고 속도는 약 3-4x 입니다.
INFO
The simulators are run in lockstep, which means that Gazebo runs the simulator at the same speed as PX4 (the GZBridge sets the PX4 time on every sim step, in the clockCallback). In addition to being a precondition for running the simulation faster/slower than real-time, this also allows you to pause the simulation in order to step through code. Lockstep cannot be disabled on Gazebo.
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.
구문 
The startup syntax takes the form:
sh
ARGS ./build/px4_sitl_default/bin/px4where 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_SIM_MODEL.
 
- The setting is mutually exclusive with 
- PX4_SIM_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.
 - INFO - The environmental variable - PX4_GZ_MODELhas been deprecated and its functionality merged into- PX4_SIM_MODEL.
- The setting is mutually exclusive with 
:::
- PX4_GZ_MODEL_POSE: Sets the spawning position and orientation of the model when- PX4_SIM_MODELis 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_SIM_MODEL(notPX4_GZ_MODEL_NAME).
 
- If omitted, the zero pose 
- PX4_GZ_WORLD: Sets the Gazebo world file for a new simulation. If it is not given, then default is used.- This variable is ignored if an existing simulation is already running.
- This value should be specified for the selected airframe but may be overridden using this argument.
- If the moving platform world is selected using PX4_GZ_WORLD=moving_platform(or any world using the moving platform plugin), the platform can be configured using environment variables:- PX4_GZ_PLATFORM_VEL: Platform speed (m/s).
- PX4_GZ_PLATFORM_HEADING_DEG: Platform heading and direction of velocity (degrees). 0 = east, positive direction is counterclockwise.
 
 
- PX4_SIMULATOR=GZ: Sets the simulator, which for Gazebo must be- gz.- This value should be set for the selected airframe, in which case it does not need to be set as an argument.
 
- PX4_GZ_STANDALONE: Lets PX4 know that it should not launch an instance of Gazebo. Gazebo will need to be launched separately, as described in Standalone Mode.
- PX4_GZ_SIM_RENDER_ENGINE: Sets the render engine to be used by gazebo.- The default rendering engine (OGRE 2) is not well supported on some platforms/environments. Specify - PX4_GZ_SIM_RENDER_ENGINE=ogreto set the rendering engine to OGRE 1 if you have rendering issues when running PX4 on a virtual machine.
- PX4_SIM_SPEED_FACTOR: Sets the speed factor to run the simulation at faster/slower than realtime.
- PX4_GZ_FOLLOW_OFFSET_X,- PX4_GZ_FOLLOW_OFFSET_Y,- PX4_GZ_FOLLOW_OFFSET_Z: Set the relative offset of the follow camera to the vehicle.
The PX4 Gazebo worlds and and models databases can be found on GitHub here.
INFO
gz_env.sh.in is compiled and made available in $PX4_DIR/build/px4_sitl_default/rootfs/gz_env.sh
예 
Here are some examples of the different scenarios covered above.
- Start simulator + default world + spawn vehicle at default pose sh- PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4
- Start simulator + default world + spawn vehicle at custom pose (y=2m) sh- PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_POSE="0,2" PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4
- Start simulator + default world + link to existing vehicle sh- PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_NAME=x500 ./build/px4_sitl_default/bin/px4
- Start simulator in standalone mode + connect to Gazebo instance running default world sh- PX4_GZ_STANDALONE=1 PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4- In a separate terminal run: sh- python /path/to/simulation-gazebo
Adding New Worlds and Models 
SDF files, mesh files, textures and anything else to do with the functionality and appearance in Gazebo for worlds and models can be placed in the appropriate /worlds and /models directories in PX4-gazebo-models.
Within PX4 follow the below steps to add models and worlds.
Adding a Model 
To add a new model:
- Define an airframe configuration file. 
- Define the default parameters for Gazebo in the airframe configuration file (this example is from x500 quadcopter): ini- 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_MODELlets you start the simulation with just:sh- PX4_SYS_AUTOSTART=<your new airframe id> ./build/px4_sitl_default/bin/px4
 
- Add CMake Target for the airframe. - If you plan to use "regular" mode, add your model SDF to Tools/simulation/gz/models/.
- If you plan to use standalone mode, add your model SDF to ~/.simulation-gazebo/models/
 - You can of course also use both. 
- If you plan to use "regular" mode, add your model SDF to 
Adding a World 
To add a new world:
- Add your world to the list of worlds found in the - CMakeLists.txthere. This is required in order to allow- CMaketo generate correct targets.- If you plan to use "normal" mode, add your world sdf to Tools/simulation/gz/worlds/.
- If you plan to use standalone mode, add your world SDF to ~/.simulation-gazebo/worlds/
 
- If you plan to use "normal" mode, add your world sdf to 
INFO
As long as the world file and the model file are in the Gazebo search path (GZ_SIM_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.
Extending Gazebo with Plugins 
World, vehicle (model), and sensor behaviour can be customised using plugins. For more information see Gazebo Plugins.
다중 차량 시뮬레이션 
Multi-Vehicle simulation is supported on Linux hosts.
For more information see: Multi-Vehicle Simulation with Gazebo