Skip to content

Gazebo Vehicles

This topic lists/displays the vehicles supported by the PX4 Gazebo simulation, and the make commands required to run them (the commands are run from a terminal in the PX4-Autopilot directory).

The models are included in PX4 as a submodule that is fetched from the Gazebo Models Repository.

Supported vehicle types include: mutirotor, VTOL, Plane, Rover.

WARNING

See Gazebo Classic Vehicles for vehicles that work with the older Gazebo "Classic" simulation. Note that vehicle models are not interchangable between the two versions of the simulator: the vehicles on this page only work with (new) Gazebo.

Multicopter

X500 Quadrotor

sh
make px4_sitl gz_x500

X500 Quadrotor with Visual Odometry

sh
make px4_sitl gz_x500_vision

x500 in Gazebo

X500 Quadrotor with Depth Camera

These models have a depth camera attached, modelled on the OAK-D.

Forward-facing depth camera:

sh
make px4_sitl gz_x500_depth

x500 with depth camera in Gazebo

X500 Quadrotor with Monocular Camera

This model has a simple monocular camera sensor attached (there is no physical camera visualization on the model itself).

sh
make px4_sitl gz_x500_mono_cam

INFO

The camera cannot yet be used to stream video or for image capture in QGroundControl. PX4-Autopilot#22563 can be used to track the additional work needed to fully enable these use cases.

X500 Quadrotor with Downward-facing Monocular Camera

This model has a simple monocular camera sensor attached facing down (there is no physical camera visualization on the model itself).

This can be used with the Aruco world to test precision landing.

sh
make px4_sitl x500_mono_cam_down

X500 Quadrotor with 2D LIDAR

This model have a 2D LIDAR attached, modelled on the Hokuyo UTM-30LX. It has a range between 0.1 and 30m, and scans in a 270° arc. The model can be used for testing Collision Prevention.

sh
make px4_sitl gz_x500_lidar

x500 with 2D LIDAR in Gazebo

INFO

The model cannot be used for testing normal rangefinder use cases, such as terrain following, as the information is not written to the DistanceSensor topic (it is written to the ObstacleDistance UORB message used by collision prevention).

Plane/Fixed-wing

Standard Plane

sh
make px4_sitl gz_rc_cessna

Plane in Gazebo

Advanced Plane

PX4 v1.15
sh
make px4_sitl gz_advanced_plane

Advanced Plane in Gazebo

INFO

The difference between the Advanced Plane and the "regular plane" lies in the Lift Physics that the two models use:

VTOL

Standard VTOL

sh
make px4_sitl gz_standard_vtol

Standard VTOL in Gazebo Classic

Rover

Differential Rover

Differential-steering Rover uses the rover world by default.

sh
make px4_sitl gz_r1_rover

Differential Rover in Gazebo

Ackermann Rover

Ackermann Rover uses the rover world by default.

sh
make px4_sitl gz_rover_ackermann

Ackermann Rover in Gazebo