Gazebo Simulation
Gazebo is a powerful 3D simulation environment for autonomous robots that is particularly suitable for testing object-avoidance and computer vision. This page describes its use with SITL and a single vehicle. Gazebo can also be used with HITL and for multi-vehicle simulation.
Supported Vehicles: Quad (Iris and Solo, Hex (Typhoon H480), Generic quad delta VTOL, Tailsitter, Plane, Rover, Submarine/UUV.
Gazebo is often used with ROS, a toolkit/offboard API for automating vehicle control. If you plan to use PX4 with ROS you should follow the ROS Instructions to install both ROS and Gazebo (and thereby avoid installation conflicts).
See Simulation for general information about simulators, the simulation environment, and simulation configuration (e.g. supported vehicles).
Installation
Gazebo 9 setup is included in our standard build instructions:
Windows: Not supported.
Additional installation instructions can be found on gazebosim.org.
Running the Simulation
Run a simulation by starting PX4 SITL and gazebo with the airframe configuration to load (multicopters, planes, VTOL, optical flow and multi-vehicle simulations are supported).
The easiest way to do this is to open a terminal in the root directory of the PX4 PX4-Autopilot repository and call make
for the desired target. For example, to start a quadrotor simulation (the default):
The supported vehicles and make
commands are listed below (click links to see vehicle images).
For the full list of build targets run make px4_sitl list_vmd_make_targets
(and filter on those that start with gazebo_
).
The Installing Files and Code guide is a useful reference if there are build errors.
The commands above launch a single vehicle with the full UI. Other options include:
Starting PX4 and Gazebo separately so that you can keep Gazebo running and only re-launch PX4 when needed (quicker than restarting both).
Run the simulation in Headless Mode, which does not start the Gazebo UI (this uses fewer resources and is much faster).
Taking it to the Sky
The make
commands above first build PX4, and then run it along with the Gazebo simulator.
Once PX4 has started it will launch the PX4 shell as shown below.
The console will print out status as PX4 loads the airframe-specific initialisation and parameter files, waits for (and connects to) the simulator. Once there is an INFO print that [ecl/EKF] is commencing GPS fusion
the vehicle is ready to arm.
Right-clicking the quadrotor model allows to enable follow mode from the context menu, which is handy to keep it in view.
You can bring it into the air by typing:
Usage/Configuration Options
Options that apply to all simulators are covered in the top level Simulation topic (some of these may be duplicated below).
Simulating Sensor/Hardware Failure
Simulate Failsafes explains how to trigger safety failsafes like GPS failure and battery drain.
Headless Mode
Gazebo can be run in a headless mode in which the Gazebo UI is not launched. This starts up more quickly and uses less system resources (i.e. it is a more "lightweight" way to run the simulation).
Simply prefix the normal make
command with HEADLESS=1
as shown:
Set Custom Takeoff Location
The takeoff location in SITL Gazebo can be set using environment variables. This will override both the default takeoff location, and any value set for the world.
The variables to set are: PX4_HOME_LAT
, PX4_HOME_LON
, and PX4_HOME_ALT
.
For example:
Change Simulation Speed
The simulation speed can be increased or decreased with respect to realtime using the environment variable PX4_SIM_SPEED_FACTOR
.
For more information see: Simulation > Run Simulation Faster than Realtime.
Change Wind Speed
To simulate wind speed, add this plugin to your world file and replace SET_YOUR_WIND_SPEED
with the desired speed:
You can see this how this is done in PX4/PX4-SITL_gazebo/worlds/windy.world.
Using a Joystick
Joystick and thumb-joystick support are supported through QGroundControl (setup instructions here).
Improving Distance Sensor Performance
The current default world is PX4/sitl_gazebo/worlds/iris.world), which uses a heightmap as ground.
This can cause difficulty when using a distance sensor. If there are unexpected results we recommend you change the model in iris.model from uneven_ground
to asphalt_plane
.
Simulating GPS Noise
Gazebo can simulate GPS noise that is similar to that typically found in real systems (otherwise reported GPS values will be noise-free/perfect). This is useful when working on applications that might be impacted by GPS noise - e.g. precision positioning.
GPS noise is enabled if the target vehicle's SDF file contains a value for the gpsNoise
element (i.e. it has the line: <gpsNoise>true</gpsNoise>
). It is enabled by default in many vehicle SDF files: solo.sdf, iris.sdf, standard_vtol.sdf, delta_wing.sdf, plane.sdf, typhoon_h480, tailsitter.sdf.
To enable/disable GPS noise:
Build any gazebo target in order to generate SDF files (for all vehicles). For example:
The SDF files are not overwritten on subsequent builds.
Open the SDF file for your target vehicle (e.g. ./Tools/sitl_gazebo/models/iris/iris.sdf).
Search for the
gpsNoise
element:If it is present, GPS is enabled. You can disable it by deleting the line:
<gpsNoise>true</gpsNoise>
If it is not preset GPS is disabled. You can enable it by adding the
gpsNoise
element to thegps_plugin
section (as shown above).
The next time you build/restart Gazebo it will use the new GPS noise setting.
Loading a Specific World
PX4 supports a number of Gazebo Worlds, which are stored in PX4/sitl_gazebo/worlds) By default Gazebo displays a flat featureless plane, as defined in empty.world.
You can load any of the worlds by specifying them as the final option in the PX4 configuration target.
For example, to load the warehouse world, you can append it as shown:
There are two underscores after the model (plane_cam
) indicating that the default debugger is used (none). See Building the Code > PX4 Make Build Targets.
You can also specify the full path to a world to load using the PX4_SITL_WORLD
environment variable. This is useful if testing a new world that is not yet included with PX4.
If the loaded world does not align with the map, you may need to set the world location.
Set World Location
The vehicle gets spawned very close to the origin of the world model at some simulated GPS location.
The vehicle is not spawned exactly at the Gazebo origin (0,0,0), but using a slight offset, which can highlight a number of common coding issues.
If using a world that recreates a real location (e.g. a particular airport) this can result in a very obvious mismatch between what is displayed in the simulated world, and what is shown on the ground station map. To overcome this problem you can set the location of the world origin to the GPS co-ordinates where it would be in "real life".
You can also set a Custom Takeoff Location that does the same thing. However adding the location to the map is easier (and can still be over-ridden by setting a custom location if needed).
The location of the world is defined in the .world file by specifying the location of the origin using the spherical_coordinates
tag. The latitude, longitude, elevation must all be specified (for this to be a valid).
An example can be found in the sonoma_raceway.world:
You can test this by spawning a rover in the Sonoma Raceway World using the following make
command (note that spawning takes longer the first time as the model needs to be downloaded from the model database):
The video below shows that the location of the environment is aligned with the gazebo world:
Starting Gazebo and PX4 Separately
For extended development sessions it might be more convenient to start Gazebo and PX4 separately or even from within an IDE.
In addition to the existing cmake targets that run sitl_run.sh
with parameters for px4 to load the correct model it creates a launcher targets named px4_<mode>
that is a thin wrapper around original sitl px4 app. This thin wrapper simply embeds app arguments like current working directories and the path to the model file.
To start Gazebo and PX4 separately:
Run gazebo (or any other sim) server and client viewers via the terminal specifing an
_ide
variant:or
In your IDE select
px4_<mode>
target you want to debug (e.g.px4_iris
)Start the debug session directly from IDE
This approach significantly reduces the debug cycle time because simulator (e.g. Gazebo) is always running in background and you only re-run the px4 process which is very light.
Simulated Survey Camera
The Gazebo survey camera simulates a MAVLink camera that captures geotagged JPEG images and sends camera capture information to a connected ground station. The camera also supports video streaming. It can be used to test camera capture, in particular within survey missions.
The camera emits the CAMERA_IMAGE_CAPTURED message every time an image is captured. The captured images are saved to: PX4-Autopilot/build/px4_sitle_default/tmp/frames/DSC_n_.jpg (where n starts as 00000 and is iterated by one on each capture).
To simulate a plane with this camera:
The camera also supports/responds to the following MAVLink commands: MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS, MAV_CMD_REQUEST_STORAGE_INFORMATION, MAV_CMD_REQUEST_CAMERA_SETTINGS, MAV_CMD_REQUEST_CAMERA_INFORMATION, MAV_CMD_RESET_CAMERA_SETTINGS, MAV_CMD_STORAGE_FORMAT, MAV_CMD_SET_CAMERA_ZOOM, MAV_CMD_IMAGE_START_CAPTURE, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, MAV_CMD_REQUEST_VIDEO_STREAM_STATUS, MAV_CMD_SET_CAMERA_MODE.
The simulated camera is implemented in PX4/PX4-SITL_gazebo/master/src/gazebo_camera_manager_plugin.cpp.
Simulated Parachute/Flight Termination
Gazebo can be used to simulate deploying a parachute during Flight Termination (flight termination is triggered by the PWM command that is simulated in Gazebo).
The if750a
target has a parachute attached to the vehicle. To simulate the vehicle, run the following command:
To put the vehicle into flight termination state, you can force it to fail a safety check that has flight termination set as the failsafe action. For example, you could do this by forcing a Geofence violation.
For more information see:
Video Streaming
PX4 SITL for Gazebo supports UDP video streaming from a Gazebo camera sensor attached to a vehicle model. When streaming is enabled, you can connect to this stream from QGroundControl (on UDP port 5600) and view video of the Gazebo environment from the simulated vehicle - just as you would from a real camera. The video is streamed using a gstreamer pipeline and can be enabled/disabled using a button in the Gazebo UI.
The Gazebo camera sensor is supported/enabled on the following frames:
Prerequisites
Gstreamer 1.0 is required for video streaming. The required dependencies should already have been installed when you set up Gazebo (they are included in the standard PX4 installation scripts/instructions for macOS and Ubuntu Linux).
FYI only, the dependencies include: gstreamer1.0-plugins-base
, gstreamer1.0-plugins-good
, gstreamer1.0-plugins-bad
, gstreamer1.0-plugins-ugly
, libgstreamer-plugins-base1.0-dev
.
Start/Stop Video Streaming
Video streaming is automatically started when supported by the target vehicle. For example, to start streaming video on the Typhoon H480:
Streaming can be paused/restarted using the Gazebo UI Video ON/OFF button..
How to View Gazebo Video
The easiest way to view the SITL/Gazebo camera video stream is in QGroundControl. Simply open Application Settings > General and set Video Source to UDP h.264 Video Stream and UDP Port to 5600:
The video from Gazebo should then display in QGroundControl just as it would from a real camera.
The Typhoon world is not very interesting.
It is also possible to view the video using the Gstreamer Pipeline. Simply enter the following terminal command:
Verbose Logging
SITL fails silently when there is something wrong with the gazebo model. You can enable more verbose logging using VERBOSE_SIM
, as shown:
or
Extending and Customizing
To extend or customize the simulation interface, edit the files in the Tools/sitl_gazebo
folder. The code is available on the sitl_gazebo repository on Github.
The build system enforces the correct GIT submodules, including the simulator. It will not overwrite changes in files in the directory.
Further Information
Last updated