Skip to content

Gazebo Worlds

This topic provides imagery/information about the Gazebo worlds supported by PX4.

The default world is spawned by default, though this may be overridden by a model specific world. Developers can also manually specify the world to load: Gazebo > Specify World (or Gazebo Models Repository).

The source code for supported worlds can be found in the Gazebo Models Repository on GitHub here: PX4/PX4-gazebo-models/tree/main/worlds.

Empty (Default)

Empty world (a grey plane). This is used by default.

PX4-gazebo-models/main/worlds/default.sdf

screenshot of default world

Aruco

Aruco world is the default world with the addition of an ArUco marker.

This is used in conjunction with the x500_mono_cam_down airframe to test precision landing.

PX4-gazebo-models/main/worlds/aruco.sdf

screenshot of Aruco world

Baylands

Baylands world surrounded by water.

PX4-gazebo-models/main/worlds/bayland.sdf

Screenshot of Baylands world

Lawn

Lawn is a flat green world that is a less-optimized alternative to rover world. It is not recommended the low frame rate causes segmentation faults on some frames.

PX4-gazebo-models/main/worlds/lawn.sdf

screenshot of lawn world

Rover

Rover world is optimised for rovers (and will be further optimised for rovers) and is the default world for Ackermann Rover (4012) (make px4_sitl gz_rover_ackermann) and Differential-steering Rover ((r1-rover (4009)) (make px4_sitl gz_r1_rover).

PX4-gazebo-models/main/worlds/rover.sdf

screenshot of rover world

INFO

Rover world is very similar to lawn world, but with these tow main differences:

  • Grid on the ground which is useful as a reference while driving.
  • Higher update rate which solves segfault issues specifically with rovers with ackermann steering.

Walls

World with walls that is designed for testing collision prevention.

PX4-gazebo-models/main/worlds/walls.sdf

screenshot of walls world

Windy

Empty world with wind enabled.

PX4-gazebo-models/main/worlds/walls.sdf

Model Specific Worlds

Some vehicle models rely on the physics / plugins of a specific world. The PX4 toolchain will automatically spawn a world that has the same name as the vehicle model if one exists (instead of the default world):

The model specific worlds are: