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.
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_x500X500 Quadrotor with Visual Odometry 
sh
make px4_sitl gz_x500_vision
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 Quadrotor with Monocular Camera 
This models has a simple monocular camera sensor attached (there is no physical camera visualization on the model itself).
sh
make px4_sitl gz_x500_mono_camINFO
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.
Plane/Fixed-wing 
Standard Plane 
sh
make px4_sitl gz_rc_cessna
Advanced Plane 
PX4 v1.15sh
make px4_sitl gz_advanced_plane
INFO
The difference between the Advanced Plane and the "regular plane" lies in the Lift Physics that the two models use:
- You can configure the Advanced Lift Drag plugin used by the model to more closely match a particular vehicle using the Advanced Lift Drag Tool.
- For more detail on the lift calculations for the Advanced Plane, see PX4-SITL_gazebo-classic/src/liftdrag_plugin/index.md
VTOL 
Standard VTOL 
sh
make px4_sitl gz_standard_vtol