Multi-Vehicle Sim
This topic explains how to simulate multiple UAV vehicles using Gazebo (Gz) and SITL.
:::note Multi-Vehicle Simulation with Gazebo is only supported on Linux. :::
Gazebo makes it very easy to setup multi-vehicle scenarios (compared to other simulators).
First build PX4 SITL code using:
make px4_sitlEach instance of PX4 can then be launched in its own terminal, specifying a unique instance number and its desired combination of environment variables:
ARGS ./build/px4_sitl_default/bin/px4 [-i <instance>]<instance>: The instance number of the vehicle.Each vehicle must have a unique instance number. If not given, the instance number defaults to zero.
When used with
PX4_GZ_MODEL, Gazebo will automatically pick a unique model name in the form${PX4_GZ_MODEL}_instance.
ARGS: A list of environmental variables, as described in Gazebo Simulation > Usage/Configuration Options.
This allows for greater flexibility and customization.
Multiple Vehicles with ROS 2 and Gazebo
Multiple vehicles with ROS 2 are possible.
First follow the installation instructions for Gazebo.
Then configure your system for ROS 2 / PX4 operations.
In different terminals manually start a multi vehicle simulation. This example spawns 2 X500 Quadrotors and a fixed wing:
PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL=x500 ./build/px4_sitl_default/bin/px4 -i 1PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_POSE="0,1" PX4_GZ_MODEL=x500 ./build/px4_sitl_default/bin/px4 -i 2PX4_SYS_AUTOSTART=4004 PX4_GZ_MODEL_POSE="0,2" PX4_GZ_MODEL=rc_cessna ./build/px4_sitl_default/bin/px4 -i 3Start the agent:
MicroXRCEAgent udp4 -p 8888The agent will automatically connect to all clients.
Run
ros2 topic listto see the topic list, which should look like this:
Last updated