- Gazebo Simulation
- Installation
- Running the Simulation
- Simulation
- Running Simulation on a Remote Server
- Taking it to the Sky
- Usage/Configuration Options
- Loading a Specific World
- Set World Location
- Starting Gazebo and PX4 Separately
- Simulated Survey Camera
- Simulated Parachute/Flight Termination
- Video Streaming
- Extending and Customizing
- Further Information
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.
:::warning 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). :::
:::note 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:
- macOS: Development Environment on Mac
- Linux: Development Environment on Ubuntu LTS / Debian Linux > Gazebo, JMAVSim and NuttX (Pixhawk) Targets
- 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):
cd /path/to/PX4-Autopilot
make px4_sitl gazebo
The supported vehicles and make
commands are listed below (click links to see vehicle images).
:::note
For the full list of build targets run make px4_sitl list_vmd_make_targets
(and filter on those that start with gazebo_
).
:::
Vehicle | Command |
---|---|
Quadrotor | make px4_sitl gazebo |
Quadrotor with Optical Flow | make px4_sitl gazebo_iris_opt_flow |
3DR Solo (Quadrotor) | make px4_sitl gazebo_solo |
Typhoon H480 (Hexrotor) (supports video streaming) | make px4_sitl gazebo_typhoon_h480 |
Standard Plane | make px4_sitl gazebo_plane |
Standard Plane (with catapult launch) | make px4_sitl gazebo_plane_catapult |
Standard VTOL | make px4_sitl gazebo_standard_vtol |
Tailsitter VTOL | make px4_sitl gazebo_tailsitter |
Ackerman vehicle (UGV/Rover) | make px4_sitl gazebo_rover |
HippoCampus TUHH (UUV: Unmanned Underwater Vehicle) | make px4_sitl gazebo_uuv_hippocampus |
Boat (USV: Unmanned Surface Vehicle) | make px4_sitl gazebo_boat |
Cloudship (Airship) | make px4_sitl gazebo_cloudship |
:::note 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).
https://youtu.be/-a2WWLni5do
Simulation
Simulators allow PX4 flight code to control a computer modeled vehicle in a simulated “world”. You can interact with this vehicle just as you might with a real vehicle, using QGroundControl, an offboard API, or a radio controller/gamepad.
Tip Simulation is a quick, easy, and most importantly, safe way to test changes to PX4 code before attempting to fly in the real world. It is also a good way to start flying with PX4 when you haven’t yet got a vehicle to experiment with.
PX4 supports both Software In the Loop (SITL) simulation, where the flight stack runs on computer (either the same computer or another computer on the same network) and Hardware In the Loop (HITL) simulation using a simulation firmware on a real flight controller board.
Information about available simulators and how to set them up are provided in the next section. The other sections provide general information about how the simulator works, and are not required to use the simulators.
Supported Simulators
The following simulators work with PX4 for HITL and/or SITL simulation.
Simulator | Description |
---|---|
Gazebo | <p>This simulator is highly recommended.</p><p>A powerful 3D simulation environment that is particularly suitable for testing object-avoidance and computer vision. It can also be used for multi-vehicle simulation and is commonly used with ROS, a collection of tools for automating vehicle control. </p><p>Supported Vehicles: Quad (Iris and Solo), Hex (Typhoon H480), Generic quad delta VTOL, Tailsitter, Plane, Rover, Submarine </p> |
FlightGear | <p>A simulator that provides physically and visually realistic simulations. In particular it can simulate many weather conditions, including thunderstorms, snow, rain and hail, and can also simulate thermals and different types of atmospheric flows. Multi-vehicle simulation is also supported.</p> <p>Supported Vehicles: Plane, Autogyro, Rover</p> |
JSBSim | <p>A simulator that provides advanced flight dynamics models. This can be used to model realistic flight dynamics based on wind tunnel data.</p> <p>Supported Vehicles: Plane, Quad, Hex</p> |
jMAVSim | A simple multirotor simulator that allows you to fly copter type vehicles around a simulated world. <p>It is easy to set up and can be used to test that your vehicle can take off, fly, land, and responds appropriately to various fail conditions (e.g. GPS failure). It can also be used for multi-vehicle simulation.</p><p>Supported Vehicles: Quad</p> |
AirSim | <p>A cross platform simulator that provides physically and visually realistic simulations. This simulator is resource intensive, and requires a very significantly more powerful computer than the other simulators described here.</p><p>Supported Vehicles: Iris (MultiRotor model and a configuration for PX4 QuadRotor in the X configuration).</p> |
Simulation-In-Hardware (SIH) | <p>An alternative to HITL that offers a hard real-time simulation directly on the hardware autopilot.</p><p>Supported Vehicles: Quad</p> |
Instructions for how to setup and use the simulators are in the topics linked above.
The remainder of this topic is a “somewhat generic” description of how the simulation infrastructure works. It is not required to use the simulators.
Simulator MAVLink API
All simulators communicate with PX4 using the Simulator MAVLink API. This API defines a set of MAVLink messages that supply sensor data from the simulated world to PX4 and return motor and actuator values from the flight code that will be applied to the simulated vehicle. The image below shows the message flow.
Note A SITL build of PX4 uses simulator_mavlink.cpp to handle these messages while a hardware build in HIL mode uses mavlink_receiver.cpp. Sensor data from the simulator is written to PX4 uORB topics. All motors / actuators are blocked, but internal software is fully operational.
The messages are described below (see links for specific detail).
Message | Direction | Description |
---|---|---|
MAV_MODE:MAV_MODE_FLAG_HIL_ENABLED | NA | Mode flag when using simulation. All motors/actuators are blocked, but internal software is fully operational. |
HIL_ACTUATOR_CONTROLS | PX4 to Sim | PX4 control outputs (to motors, actuators). |
HIL_SENSOR | Sim to PX4 | Simulated IMU readings in SI units in NED body frame. |
HIL_GPS | Sim to PX4 | The simulated GPS RAW sensor value. |
HIL_OPTICAL_FLOW | Sim to PX4 | Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor) |
HIL_STATE_QUATERNION | Sim to PX4 | Contains the actual “simulated” vehicle position, attitude, speed etc. This can be logged and compared to PX4’s estimates for analysis and debugging (for example, checking how well an estimator works for noisy (simulated) sensor inputs). |
HIL_RC_INPUTS_RAW | Sim to PX4 | The RAW values of the RC channels received. |
Default PX4 MAVLink UDP Ports
By default, PX4 uses commonly established UDP ports for MAVLink communication with ground control stations (e.g. QGroundControl), Offboard APIs (e.g. MAVSDK, MAVROS) and simulator APIs (e.g. Gazebo). These ports are:
- UDP Port 14540 is used for communication with offboard APIs. Offboard APIs are expected to listen for connections on this port.
- UDP Port 14550 is used for communication with ground control stations. GCS are expected to listen for connections on this port. QGroundControl listens to this port by default.
- The simulator’s local TCP Port 4560 is used for communication with PX4. PX4 listens to this port, and simulators are expected to initiate the communication by broadcasting data to this port.
Note The ports for the GCS and offboard APIs are set in configuration files, while the simulator broadcast port is hard-coded in the simulation MAVLink module.
SITL Simulation Environment
The diagram below shows a typical SITL simulation environment for any of the supported simulators. The different parts of the system connect via UDP, and can be run on either the same computer or another computer on the same network.
- PX4 uses a simulation-specific module to connect to the simulator’s local TCP port 4560. Simulators then exchange information with PX4 using the Simulator MAVLink API described above. PX4 on SITL and the simulator can run on either the same computer or different computers on the same network.
- PX4 uses the normal MAVLink module to connect to ground stations (which listen on port 14550) and external developer APIs like MAVSDK or ROS (which listen on port 14540).
- A serial connection is used to connect Joystick/Gamepad hardware via QGroundControl.
If you use the normal build system SITL make
configuration targets (see next section) then both SITL and the Simulator will be launched on the same computer and the ports above will automatically be configured.
You can configure additional MAVLink UDP connections and otherwise modify the simulation environment in the build configuration and initialisation files.
Starting/Building SITL Simulation
The build system makes it very easy to build and start PX4 on SITL, launch a simulator, and connect them. The syntax (simplified) looks like this:
make px4_sitl simulator[_vehicle-model]
where simulator
is gazebo
, jmavsim
or some other simulator, and vehicle-model is a particular vehicle type supported by that simulator (jMAVSim only supports multicopters, while Gazebo supports many different types).
A number of examples are shown below, and there are many more in the individual pages for each of the simulators:
# Start Gazebo with plane
make px4_sitl gazebo_plane
# Start Gazebo with iris and optical flow
make px4_sitl gazebo_iris_opt_flow
# Start JMavSim with iris (default vehicle model)
make px4_sitl jmavsim
The simulation can be further configured via environment variables:
PX4_ESTIMATOR
: This variable configures which estimator to use. Possible options are:ekf2
(default),lpe
(deprecated). It can be set viaexport PX4_ESTIMATOR=lpe
before running the simulation.
The syntax described here is simplified, and there are many other options that you can configure via make - for example, to set that you wish to connect to an IDE or debugger. For more information see: Building the Code > PX4 Make Build Targets.
Run Simulation Faster than Realtime
SITL can be run faster or slower than realtime when using jMAVSim or Gazebo.
The speed factor is set using the environment variable PX4_SIM_SPEED_FACTOR
.
For example, to run the jMAVSim simulation at 2 times the real time speed:
PX4_SIM_SPEED_FACTOR=2 make px4_sitl jmavsim
To run at half real-time:
PX4_SIM_SPEED_FACTOR=0.5 make px4_sitl jmavsim
You can apply the factor to all SITL runs in the current session using EXPORT
:
export PX4_SIM_SPEED_FACTOR=2
make px4_sitl jmavsim
Note At some point IO or CPU will limit the speed that is possible on your machine and it will be slowed down “automatically”. Powerful desktop machines can usually run the simulation at around 6-10x, for notebooks the achieved rates can be around 3-4x.
Note To avoid PX4 detecting data link timeouts, increase the value of param COM_DL_LOSS_T proportional to the simulation rate. For example, if
COM_DL_LOSS_T
is 10 in realtime, at 10x simulation rate increase to 100.
Lockstep Simulation
PX4 SITL and the simulators (jMAVSim or Gazebo) have been set up to run in lockstep. What this means is that PX4 and the simulator wait on each other for sensor and actuator messages, rather than running at their own speeds.
Note Lockstep makes it possible to run the simulation faster or slower than realtime, and also to pause it in order to step through code.
The sequence of steps for lockstep are:
- The simulation sends a sensor message HIL_SENSOR including a timestamp
time_usec
to update the sensor state and time of PX4. - PX4 receives this and does one iteration of state estimation, controls, etc. and eventually sends an actuator message HIL_ACTUATOR_CONTROLS.
- The simulation waits until it receives the actuator/motor message, then simulates the physics and calculates the next sensor message to send to PX4 again.
The system starts with a “freewheeling” period where the simulation sends sensor messages including time and therefore runs PX4 until it has initialized and responds with an actuator message.
Disable Lockstep Simulation
The lockstep simulation can be disabled if, for example, SITL is to be used with a simulator that does not support this feature. In this case the simulator and PX4 use the host system time and do not wait on each other.
To disable lockstep in PX4, use set(ENABLE_LOCKSTEP_SCHEDULER no)
in the SITL board config.
To disable lockstep in Gazebo, edit the model SDF file and set <enable_lockstep>false</enable_lockstep>
(or for Iris edit the xacro file.
To disable lockstep in jMAVSim, remove -l
in jmavsim_run.sh, or make sure otherwise that the java binary is started without the -lockstep
flag.
Startup Scripts
Scripts are used to control which parameter settings to use or which modules to start.
They are located in the ROMFS/px4fmu_common/init.d-posix directory, the rcS
file is the main entry point.
See System Startup for more information.
Simulating Failsafes and Sensor/Hardware Failure
The SITL parameters can also be used to simulate common sensor failure cases, including low battery, loss of GPS or barometer, gyro failure, increased GPS noise etc. (e.g. SIM_GPS_BLOCK can be set to simulate GPS failure).
Additionally (and with some overlap), Simulate Failsafes explains how to trigger safety failsafes.
HITL Simulation Environment
With Hardware-in-the-Loop (HITL) simulation the normal PX4 firmware is run on real hardware. The HITL Simulation Environment in documented in: HITL Simulation.
Joystick/Gamepad Integration
QGroundControl desktop versions can connect to a USB Joystick/Gamepad and send its movement commands and button presses to PX4 over MAVLink. This works on both SITL and HITL simulations, and allows you to directly control the simulated vehicle. If you don’t have a joystick you can alternatively control the vehicle using QGroundControl’s onscreen virtual thumbsticks.
For setup information see the QGroundControl User Guide:
#3# Camera Simulation
PX4 supports capture of both still images and video from within the Gazebo simulated environment. This can be enabled/set up as described in Gazebo > Video Streaming.
The simulated camera is a gazebo plugin that implements the MAVLink Camera Protocol. PX4 connects/integrates with this camera in exactly the same way as it would with any other MAVLink camera:
- TRIG_INTERFACE must be set to
3
to configure the camera trigger driver for use with a MAVLink cameraTip In this mode the driver just sends a CAMERA_TRIGGER message whenever an image capture is requested. For more information see Camera.
- PX4 must forward all camera commands between the GCS and the (simulator) MAVLink Camera.
You can do this by starting MAVLink with the
-f
flag as shown, specifying the UDP ports for the new connection.mavlink start -u 14558 -o 14530 -r 4000 -f -m camera
Note More than just the camera MAVLink messages will be forwarded, but the camera will ignore those that it doesn’t consider relevant.
The same approach can be used by other simulators to implement camera support.
Running Simulation on a Remote Server
It is possible to run the simulator on one computer, and access it from another computer on the same network (or on another network with appropriate routing). This might be useful, for example, if you want to test a drone application running on real companion computer hardware running against a simulated vehicle.
This does not work “out of the box” because PX4 does not route packets to external interfaces by default (in order to avoid spamming the network and different simulations interfering with each other). Instead it routes traffic internally - to “localhost”.
There are a number of ways to make the UDP packets available on external interfaces, as outlined below.
Enable MAV_BROADCAST
Enable MAV_BROADCAST to broadcast heartbeats on the local network.
A remote computer can then connect to the simulator by listening to the appropriate port (i.e. 14550 for QGroundControl).
Use MAVLink Router
The mavlink-router can be used to route packets from localhost to an external interface.
To route packets between SITL running on one computer (sending MAVLink traffic to localhost on UDP port 14550), and QGC running on another computer (e.g. at address 10.73.41.30
) you could:
- Start mavlink-router with the following command:
mavlink-routerd -e 10.73.41.30:14550 127.0.0.1:14550
- Use a mavlink-router conf file.
[UdpEndpoint QGC] Mode = Normal Address = 10.73.41.30 Port = 14550 [UdpEndpoint SIM] Mode = Eavesdropping Address = 127.0.0.1 Port = 14550
Note More information about mavlink-router configuration can be found here.
Modify Configuration for External Broadcasting
The mavlink module routes to localhost by default, but you can specify an external IP address to broadcast to using its -t
option.
This should be done in various configuration files where mavlink start
is called.
For example: /ROMFS/px4fmu_common/init.d-posix/rcS.
SSH Tunneling
SSH tunneling is a flexible option because the simulation computer and the system using it need not be on the same network.
Note You might similarly use VPN to provide a tunnel to an external interface (on the same network or another network).
One way to create the tunnel is to use SSH tunneling options.
The tunnel itself can be created by running the following command on localhost, where remote.local
is the name of a remote computer:
ssh -C -fR 14551:localhost:14551 remote.local
The UDP packets need to be translated to TCP packets so they can be routed over SSH. The netcat utility can be used on both sides of the tunnel - first to convert packets from UDP to TCP, and then back to UDP at the other end.
Tip QGC must be running before executing netcat.
On the QGroundControl computer, UDP packet translation may be implemented by running following commands:
mkfifo /tmp/tcp2udp
netcat -lvp 14551 < /tmp/tcp2udp | netcat -u localhost 14550 > /tmp/tcp2udp
On the simulator side of the SSH tunnel, the command is:
mkfifo /tmp/udp2tcp
netcat -lvup 14550 < /tmp/udp2tcp | netcat localhost 14551 > /tmp/udp2tcp
The port number 14550
is valid for connecting to QGroundControl or another GCS, but should be adjusted for other endpoints (e.g. developer APIs etc.).
The tunnel may in theory run indefinitely, but netcat connections may need to be restarted if there is a problem.
The QGC_remote_connect.bash script can be run on the QGC computer to automatically setup/run the above instructions. The simulation must already be running on the remote server, and you must be able to SSH into that server.
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.
______ __ __ ___
| ___ \ \ \ / / / |
| |_/ / \ V / / /| |
| __/ / \ / /_| |
| | / /^\ \ \___ |
\_| \/ \/ |_/
px4 starting.
INFO [px4] Calling startup script: /bin/sh etc/init.d-posix/rcS 0
INFO [param] selected parameter default file eeprom/parameters_10016
[param] Loaded: eeprom/parameters_10016
INFO [dataman] Unknown restart, data manager file './dataman' size is 11798680 bytes
INFO [simulator] Waiting for simulator to connect on TCP port 4560
Gazebo multi-robot simulator, version 9.0.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org
...
INFO [ecl/EKF] 5188000: commencing GPS fusion
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.
:::note 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:
pxh> commander takeoff
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:
HEADLESS=1 make px4_sitl gazebo_plane
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:
export PX4_HOME_LAT=28.452386
export PX4_HOME_LON=-13.867138
export PX4_HOME_ALT=28.5
make px4_sitl gazebo
Change Simulation Speed
The simulation speed can be increased or decreased with respect to realtime using the environment variable PX4_SIM_SPEED_FACTOR
.
export PX4_SIM_SPEED_FACTOR=2
make px4_sitl_default gazebo
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 set windVelocityMean
in m/s (replace SET_YOUR_WIND_SPEED
with your desired speed).
If needed, adapt the windVelocityMax
parameter so that it is greater than windVelocityMean
:
<plugin name='wind_plugin' filename='libgazebo_wind_plugin.so'>
<frameId>base_link</frameId>
<robotNamespace/>
<windVelocityMean>SET_YOUR_WIND_SPEED</windVelocityMean>
<windVelocityMax>20.0</windVelocityMax>
<windVelocityVariance>0</windVelocityVariance>
<windDirectionMean>0 1 0</windDirectionMean>https://youtu.be/-a2WWLni5do
<windDirectionVariance>0</windDirectionVariance>
<windGustStart>0</windGustStart>
<windGustDuration>0</windGustDuration>
<windGustVelocityMean>0</windGustVelocityMean>
<windGustVelocityMax>20.0</windGustVelocityMax>
<windGustVelocityVariance>0</windGustVelocityVariance>
<windGustDirectionMean>1 0 0</windGustDirectionMean>
<windGustDirectionVariance>0</windGustDirectionVariance>
<windPubTopic>world_wind</windPubTopic>
</plugin>
Wind direction is passed as a direction vector (standard ENU convention), which will be normalized in the gazebo plugin.
Additionally you can state wind velocity variance in (m/s)² and direction variance based on a normal distribution to add some random factor into the simulation.
Gust is internally handled in the same way as wind, with the slight difference that you can state start time and duration with the following two parameters windGustStart
and windGustDuration
.
You can see 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:
make px4_sitl gazebo_iris
:::tip 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:<plugin name='gps_plugin' filename='libgazebo_gps_plugin.so'> <robotNamespace/> <gpsNoise>true</gpsNoise> </plugin>
- If it is present, GPS is enabled.
You can disable it by deleting the line:
<gpsNoise>true</gpsNoise>
- If it is not present, GPS is disabled.
You can enable it by adding the
gpsNoise
element to thegps_plugin
section (as shown above).
- If it is present, GPS is enabled.
You can disable it by deleting the line:
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:
make px4_sitl_default gazebo_plane_cam__warehouse
:::note
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.
:::tip 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.
:::note 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”.
:::note 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:
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<latitude_deg>38.161479</latitude_deg>
<longitude_deg>-122.454630</longitude_deg>
<elevation>488.0</elevation>
</spherical_coordinates>
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):
make px4_sitl gazebo_rover__sonoma_raceway
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:make px4_sitl gazebo___ide
or
make px4_sitl gazebo_iris_ide
- 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/px4sitle_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:
make px4_sitl_default gazebo_plane_cam
:::note 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. :::
:::note 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:
make px4_sitl gazebo_if750a
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).
:::note
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:
make px4_sitl gazebo_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.
:::note 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:
gst-launch-1.0 -v udpsrc port=5600 caps='application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264' \
! rtph264depay ! avdec_h264 ! videoconvert ! autovideosink fps-update-interval=1000 sync=false
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:
export VERBOSE_SIM=1
make px4_sitl gazebo
or
VERBOSE_SIM=1 make px4_sitl gazebo
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.
:::note The build system enfor../../assets/simulation/gazebo/sitl_video_stream.png)ces the correct GIT submodules, including the simulator. It will not overwrite changes in files in the directory. :::
Further Information
The following wiki, pages and posts are tagged with
Title | Type | Excerpt |
---|---|---|
gcs and cloud | post | Mon, Jan 31, 22, sample4 from sass2 product sample4 |
overview and initial powerup | post | Mon, Jan 31, 22, sample1.md of sass2 product2_sample files The most advanced hardware and software ecosystem for enterprise drones |
smartAP | post | Mon, Jan 31, 22, sample5 from sass2 product2 sample5 |
smartAPLink and faq | post | Mon, Jan 31, 22, sample3 from sass2 product2 sample3 |
telemetry and advanced software | post | Mon, Jan 31, 22, sample2.md of sass2 product2 sample2 file |
px4 docker image for jvsim simulation | post | 목, 2월 10, 22, docker image implmentation for docker px4 simuation |
qtcreator wiki from drone guide dev-setup | post | 화, 2월 15, 22, planning phase research for dashboard elements using |
offboard control using pixhawk raspi mavros | post | Wed, Feb 16, 22, hitl setup and configuraiton using pixhawk raspi mavros and px4 |
setup gazebo for simulation | post | Wed, Feb 16, 22, pixhawk ros gazebo gcs simulation |
setup mavros and px4 | post | Wed, Feb 16, 22, setup mavros and px4 |
testing sitl drone | post | Wed, Feb 16, 22, process to launch sitl drone |
ros and px4 architecture and data flow | post | Wed, Feb 16, 22, examine how data flows for user interface and drone control |
setup ros indigo with tutlesim | post | Wed, Feb 16, 22, pixhawk gcs simulation series 2 with ros indigo |
connecting raspi to matek f406 wing | post | Fri, Feb 18, 22, hardware setup with raspi 4 with matek f406 wing |
px4 simulation for gazebo | post | Fri, Feb 18, 22, simulation instruciton from px4 |
Let's roll and conquer! | post | Monday, Third week with jdlab and first week probably for actual work |
brainstorming session prior to setting out on gcs development | post | Mon, Feb 21, 22, pool resources and ideas into one single gcs you can develop |
overview of epp and eps for airframes | post | Tue, Feb 22, 22, research before business call to manufactueres |
connecting rpi to gcs with the use of uavmatrix on uavcast pro | post | Mon, Feb 28, 22, supported raspi board pinout maps and setup guide |
creating custom mission points for fixed wings | post | Fri, Mar 18, 22, p-turn or turnaround insertion to the mission raw data for exit and entry for p-turnaround and side/front-lap coverage creation that willmod... |
gStreamer vs qtAv | post | Wed, Mar 30, 22, qt movie qmovie phonon video player |
realtime georeferencing plus imu overlay | post | Tue, Apr 05, 22, how to add vehicle status sensor data to georeferencing |
rtk reach m2 receiver documentation | post | Wed, Apr 06, 22, rtk reach receiver wifi 5g lte |
avionics on airfoil and frames | post | Thu, Apr 07, 22, airfoil materials, designs and innovations in the avionics |
using openTX on radiomaster TX16s | post | Sun, Apr 10, 22, rc reciever transmitter opentx radiomaster configuration simulation |
adding GPS and IMU data to photos post flight | post | Mon, Apr 11, 22, perform post processing of gps/imu data or develop camera firmware lib to infuse IMU from fc to exif metadata |
BMU BMC BMS battery management | post | Thu, Apr 14, 22, to check the usage and health of batteries at all phases of flight cycle |
viewpro custom pwm | post | Thu, Apr 14, 22, customize viewpro camera and gimball with mavlink |
raspberrypi video streaming | post | Fri, Apr 22, 22, configure and setup raspi to enable streaming on mavlink and to advance to LTE transmission |
lx network, airlink, gcs and data transmission on smart radio, rf mesh and quantum encryption | post | Tue, Apr 26, 22, all about setup and how it operates and managed |