# Gazebo Classic 模拟
注意
Gazebo Classic 支持 PX4 到 Ubuntu Linux 20.04。 它已被 Gazebo( 曾被称为 (opens new window)“Gazebo Ignition”)所取代,适用于Ubuntu 22.04及更高版本。
Gazebo Classic 是一个功能强大的三维仿真环境,专门用于测试避障和计算机视觉等自主机器人技术。 本页描述了在SITL和单一载具上的使用方式。 Classic Gazebo还可以与HITL一起使用,并用于多载具模拟。
**支持机型:**四旋翼 ( Iris , Hex (Typhoon H480), 常规标准VTOL (QuadPlane)),尾座式,固定翼,无人车,潜艇/无人水下航行器。
注解
See Simulation for general information about simulators, the simulation environment, and simulation configuration (e.g. supported vehicles).
# 安装
Linux、macOS和Windows版的 Gazebo Classic 9 或 11 安装包含在我们的 [标准构建说明}(../dev_setup/dev_env.md) 中。 其他安装说明可在 gazebosim.org (opens new window) 上找到。
注解
If you plan to use PX4 with ROS you should follow the ROS Instructions to install both ROS and Gazebo Classic (and thereby avoid installation conflicts).
注解
The following commands can be used to remove Gazebo (Garden) and reinstall Gazebo-Classic 11:
sudo apt remove gz-garden
sudo apt install aptitude
sudo aptitude install gazebo libgazebo11 libgazebo-dev
Note that aptitude
is needed because it can resolve dependency conflicts (by removing certain packages) that apt
is unable to handle.
# Running the Simulation
Run a simulation by starting PX4 SITL and Gazebo Classic 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-classic
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-classic_
).
Vehicle | Command |
---|---|
Quadrotor | make px4_sitl gazebo-classic |
Quadrotor with Optical Flow | make px4_sitl gazebo-classic_iris_opt_flow |
Quadrotor with Depth Camera (forward-facing) | make px4_sitl gazebo-classic_iris_depth_camera |
Quadrotor with Depth Camera (downward-facing) | make px4_sitl gazebo-classic_iris_downward_depth_camera |
3DR Solo (Quadrotor) | make px4_sitl gazebo-classic_solo |
Typhoon H480 (Hexrotor) (supports video streaming) | make px4_sitl gazebo-classic_typhoon_h480 |
Standard Plane | make px4_sitl gazebo-classic_plane |
Standard Plane (with catapult launch) | make px4_sitl gazebo-classic_plane_catapult |
Standard VTOL | make px4_sitl gazebo-classic_standard_vtol |
Tailsitter VTOL | make px4_sitl gazebo-classic_tailsitter |
Ackerman UGV (Rover) | make px4_sitl gazebo-classic_rover |
Differential UGV (Rover) | make px4_sitl gazebo-classic_r1_rover |
HippoCampus TUHH (UUV: Unmanned Underwater Vehicle) | make px4_sitl gazebo-classic_uuv_hippocampus |
Boat (USV: Unmanned Surface Vehicle) | make px4_sitl gazebo-classic_boat |
Cloudship (Airship) | make px4_sitl gazebo-classic_cloudship |
注解
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 Classic running and only re-launch PX4 when needed (quicker than restarting both).
- Run the simulation in Headless Mode, which does not start the Gazebo Classic 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 Classic 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.
注解
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 Classic can be run in a headless mode in which the Gazebo Classic 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-classic_plane
# Set Custom Takeoff Location
The takeoff location in Gazebo Classic 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-classic
# 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-classic
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>
<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 (opens new window).
# 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-Autopilot/Tools/simulation/gazebo/sitl_gazebo/worlds/iris.world (opens new window)), 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 Classic 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-classic_iris
提示
The SDF files are not overwritten on subsequent builds.
Open the SDF file for your target vehicle (e.g. ./Tools/simulation/gazebo/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).
The next time you build/restart Gazebo Classic it will use the new GPS noise setting.
# Loading a Specific World
PX4 supports a number of Worlds, which are stored in PX4-Autopilot/Tools/simulation/gazebo/sitl_gazebo/worlds (opens new window). By default Gazebo Classic displays a flat featureless plane, as defined in empty.world (opens new window).
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-classic_plane_cam__warehouse
注解
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 coordinates 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 (opens new window):
<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-classic_rover__sonoma_raceway
The video below shows that the location of the environment is aligned with the world:
# Starting Gazebo and PX4 Separately
For extended development sessions it might be more convenient to start Gazebo Classic 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 Classic and PX4 separately:
Run gazebo classic (or any other sim) server and client viewers via the terminal specifying an
_ide
variant:make px4_sitl gazebo-classic___ide
or
make px4_sitl gazebo-classic_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 is always running in background and you only re-run the px4 process which is very light.
# Simulated Survey Camera
The Gazebo Classic survey camera simulates a MAVLink camera (opens new window) 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 (opens new window) 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:
make px4_sitl_default gazebo-classic_plane_cam
注解
The camera also supports/responds to the following MAVLink commands: MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS (opens new window), MAV_CMD_REQUEST_STORAGE_INFORMATION (opens new window), MAV_CMD_REQUEST_CAMERA_SETTINGS (opens new window), MAV_CMD_REQUEST_CAMERA_INFORMATION (opens new window), MAV_CMD_RESET_CAMERA_SETTINGS (opens new window), MAV_CMD_STORAGE_FORMAT (opens new window), MAV_CMD_SET_CAMERA_ZOOM (opens new window), MAV_CMD_IMAGE_START_CAPTURE (opens new window), MAV_CMD_IMAGE_STOP_CAPTURE (opens new window), MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION (opens new window), MAV_CMD_REQUEST_VIDEO_STREAM_STATUS (opens new window), MAV_CMD_SET_CAMERA_MODE (opens new window).
注解
The simulated camera is implemented in PX4/PX4-SITL_gazebo/main/src/gazebo_camera_manager_plugin.cpp (opens new window).
# Simulated Depth Camera
The Gazebo Classic depth camera model (opens new window) simulates an Intel® RealSense™ D455 stereo depth camera using the Openni Kinect plugin (opens new window).
This publishes depth images and camera information on the /camera/depth/image_raw
and /camera/depth/camera_info
ROS topics respectively.
To use these images, you will need to install ROS or ROS 2. Note the warning at the top of this page about how to "avoid installation conflicts" when installing ROS and Gazebo.
You can simulate a quadrotor with a forward-facing depth camera:
make px4_sitl gazebo-classic_iris_depth_camera
or a quadrotor with a downward-facing depth camera:
make px4_sitl gazebo-classic_iris_downward_depth_camera
# Simulated Parachute/Flight Termination
Gazebo Classic can be used to simulate deploying a parachute during Flight Termination (flight termination is triggered by the PWM command that is simulated in Gazebo Classic).
The if750a
target has a parachute attached to the vehicle. To simulate the vehicle, run the following command:
make px4_sitl gazebo-classic_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 Classic supports UDP video streaming from a camera sensor attached to a simulated vehicle model. When streaming is enabled, you can connect to this stream from QGroundControl (on UDP port 5600) and view video of the Gazebo Classic 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 Classic UI.
The simulated 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 Classic (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:
make px4_sitl gazebo-classic_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 Classic 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 Classic 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:
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 model. You can enable more verbose logging using VERBOSE_SIM
, as shown:
export VERBOSE_SIM=1
make px4_sitl gazebo-classic
or
VERBOSE_SIM=1 make px4_sitl gazebo-classic
# Extending and Customizing
To extend or customize the simulation interface, edit the files in the Tools/simulation/gazebo/sitl_gazebo
folder. The code is available on the sitl_gazebo repository (opens new window) on Github.
注解
The build system enforces the correct GIT submodules, including the simulator. It will not overwrite changes in files in the directory.