# Gazebo 仿真
注意
Gazebo 先前被称为“Gazebo Ignition”( Gazebo Classic 先前被称为Gazebo)。 查看 官方博客文章 (opens new window) 获取更多信息。
Gazebo (opens new window) 是一个开源机器人模拟器。 它取代了旧的 Gazebo Classic 模拟器,是Ubuntu 22.04 及以后唯一支持的 Gazebo 版本。
支持的载具: Quadrotor、Plane、VTOL
注解
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_
.
注解
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.
The supported vehicles and make
commands are listed below.
Vehicle | Command | PX4_SYS_AUTOSTART |
---|---|---|
Quadrotor(x500) | make px4_sitl gz_x500 | 4001 |
Quadrotor(x500) with Depth Camera | make px4_sitl gz_x500_depth | 4002 |
Quadrotor(x500) with Vision Odometry | make px4_sitl gz_x500_vision | 4005 |
VTOL | make px4_sitl gz_standard_vtol | 4003 |
Plane | 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
.
- The setting is mutually exclusive with
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
.
- The setting is mutually exclusive with
注解
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 whenPX4_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
(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 (opens new window) 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.
PX4_SIMULATOR=GZ
: Sets the simulator, which for Gz must begz
.- This value should be set for the selected airframe, in which case it does not need to be set as an argument.
The PX4 Gazebo worlds and and models databases can be found on Github here (opens new window). They are added to the Gazebo search PATH
by gz_env.sh.in (opens new window) during the simulation startup phase.
注解
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.
Start simulator + default world + spawn vehicle at default pose
PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL=x500 ./build/px4_sitl_default/bin/px4
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
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 (opens new window).
To add a new model:
Add an sdf file in the PX4 Gazebo model directory (opens new window).
Define an airframe configuration file.
Define the default parameters for Gazebo in the airframe configuration file (this example is from x500 quadcopter (opens new window)):
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 (opens new window) for that specific airframe.Setting the default value of
PX4_SIM_MODEL
lets you start the simulation with justPX4_SYS_AUTOSTART=<your new airframe id> ./build/px4_sitl_default/bin/px4
注解
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