Skip to main content
This page explains how Gazebo simulation worlds are structured, introduces the SDF and Xacro file formats, and walks through the AWS RoboMaker Small House world used in the TurtleBot3 demos.

Prerequisites


The SDF world file format

Simulation Description Format (SDF) is the XML schema used by Gazebo to describe simulation worlds. Every world file has the following top-level structure:
<?xml version="1.0"?>
<sdf version="1.6">
  <world name="my_world">
    {/* Plugins */}
    {/* Physics */}
    {/* Lighting */}
    {/* Models */}
  </world>
</sdf>

Plugins

Gazebo Sim (Harmonic) is plugin-based. Each capability — physics, sensors, scene rendering — is a loadable shared library declared in the world file:
<plugin filename="gz-sim-physics-system"
        name="gz::sim::systems::Physics"/>
<plugin filename="gz-sim-sensors-system"
        name="gz::sim::systems::Sensors">
  <render_engine>ogre2</render_engine>
</plugin>
<plugin filename="gz-sim-imu-system"
        name="gz::sim::systems::Imu"/>
gz-sim-scene-broadcaster-system is only loaded when the simulation is not running headless. The Small House world uses an Xacro argument to control this:
<xacro:unless value="$(arg headless)">
  <plugin filename="gz-sim-scene-broadcaster-system"
          name="gz::sim::systems::SceneBroadcaster"/>
</xacro:unless>

Physics

The <physics> element configures the ODE (Open Dynamics Engine) solver. The Small House world uses a 3 ms time step:
<physics name="3ms" type="ode">
  <max_step_size>0.003</max_step_size>
  <real_time_factor>1</real_time_factor>
</physics>
A smaller time step improves simulation accuracy at the cost of computational load. For navigation tasks with a TurtleBot, 3 ms is a good balance.

Lighting

Gazebo supports directional, point, and spot lights. The Small House world uses a single directional sun:
<light name="sun" type="directional">
  <cast_shadows>0</cast_shadows>
  <pose>0 0 10 0 0 0</pose>
  <diffuse>0.8 0.8 0.8 1</diffuse>
  <specular>0.2 0.2 0.2 1</specular>
  <attenuation>
    <range>1000</range>
    <constant>0.9</constant>
    <linear>0.01</linear>
    <quadratic>0.001</quadratic>
  </attenuation>
  <direction>-0.5 0.1 -0.9</direction>
</light>
The <direction> vector (-0.5, 0.1, -0.9) angles the light from upper-left, creating natural shadow contrast on furniture.

Xacro: parameterized world files

Xacro (XML Macros) extends plain SDF with:
  • Arguments — pass parameters when loading the world
  • Conditionals<xacro:if> / <xacro:unless> for optional blocks
  • Macros — reusable XML templates with local variables
World files that use Xacro carry the .sdf.xacro extension. To process them, ROS 2 runs the Xacro preprocessor at launch time, producing a pure SDF file that Gazebo can load. The Small House world declares one argument:
<sdf version="1.6" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <xacro:arg name="headless" default="false"/>
  ...
The launch file passes this argument when spawning the world:
# tb_demo_world.launch.py (excerpt)
world_name = LaunchConfiguration("world_name",
    default="house_world.sdf.xacro")

Model anatomy

Every Gazebo model lives in its own directory with two required files:
tb_worlds/models/aws_robomaker_residential_ChairA_01/
├── model.config      ← metadata (name, version, author)
├── model.sdf         ← geometry, physics, visuals
├── meshes/
│   ├── aws_ChairA_01_visual.DAE    ← visual mesh (detailed)
│   └── aws_ChairA_01_collision.DAE ← collision mesh (simplified)
└── materials/        ← textures and material scripts

model.config

<?xml version="1.0" ?>
<model>
  <name>aws_robomaker_residential_ChairA_01</name>
  <version>1.0</version>
  <sdf version="1.6">model.sdf</sdf>
  <author>
    <name></name>
    <email></email>
  </author>
  <description></description>
</model>

model.sdf

A static furniture model needs three things: inertial properties, a collision shape for physics, and a visual mesh for rendering. Here is the complete ChairA_01 model:
<?xml version="1.0"?>
<sdf version="1.6">
  <model name="aws_robomaker_residential_ChairA_01">
    <link name="link_ChairA_01">
      <inertial>
        <mass>7.5</mass>
        <inertia>
          <ixx>0.217</ixx>  {/* rotation resistance around X axis */}
          <iyy>0.217</iyy>
          <izz>0.067</izz>  {/* lowest: chair spins easily around vertical */}
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyz>0</iyz>
        </inertia>
      </inertial>

      {/* Collision: simplified mesh for fast physics */}
      <collision name="collision">
        <geometry>
          <mesh>
            <uri>model://aws_robomaker_residential_ChairA_01/meshes/aws_ChairA_01_collision.DAE</uri>
            <scale>1 1 1</scale>
          </mesh>
        </geometry>
      </collision>

      {/* Visual: full-detail mesh for rendering */}
      <visual name="visual">
        <geometry>
          <mesh>
            <uri>model://aws_robomaker_residential_ChairA_01/meshes/aws_ChairA_01_visual.DAE</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
  </model>
</sdf>
The collision mesh is deliberately simpler than the visual mesh — fewer polygons mean faster contact detection. For furniture that the robot will not physically interact with (static obstacles), a convex hull approximation is sufficient.

The AWS RoboMaker Small House world

The Small House world is a residential interior adapted from AWS RoboMaker’s open-source assets. It contains 68 aws_robomaker_residential_* models covering:
CategoryExamples
FurnitureBed_01, ChairA_01, ChairD_01, CoffeeTable_01, Sofa_01
AppliancesAirconditionerA_01, AirconditionerB_01, CookingBench_01
DécorCarpet_01, Curtain_01, Chandelier_01, Ball_01
PortraitsDeskPortraitA_01, DeskPortraitB_01, DeskPortraitC_01
StorageNightStand_01, Wardrobe_01, Board_01

Placing models in the world

Each model is placed with a <model> block in the world file. The <include> element references the model directory by name; <pose> gives its position (x, y, z) and orientation (roll, pitch, yaw in radians):
<model name='Bed_01_001'>
  <static>true</static>
  <include>
    <uri>model://aws_robomaker_residential_Bed_01</uri>
  </include>
  <pose frame=''>-6.165067 2.030560 -0.000010 0 -0 0</pose>
</model>

<model name='AirconditionerA_01_001'>
  <static>true</static>
  <include>
    <uri>model://aws_robomaker_residential_AirconditionerA_01</uri>
  </include>
  <pose frame=''>-9.199410 2.411230 2.084544 0 -0 0</pose>
</model>
Setting <static>true</static> tells Gazebo the model does not move — the physics engine skips dynamics for it, saving computation.

Launching the house world

# Clone the repo
git clone https://github.com/pantelis/turtlebot-maze
cd turtlebot-maze

# Build Docker images (first time only, ~5 GB)
docker compose build

# Start the house world
docker compose up demo-world-house
Gazebo will open showing the residential interior. The TurtleBot spawns near the entrance. The house world ships with a pre-built Nav2 occupancy grid map at 5 cm/px resolution (tb_worlds/maps/house_world_map.yaml). The map was generated by running GMapping SLAM in the world and recording the result. When a new model is added or furniture is rearranged, the map must be regenerated — Nav2 will plan routes through walls it does not know about.

Available worlds

The turtlebot-maze project includes four Gazebo environments:
ServiceSceneModelsMap resolution
demo-worldOriginal TurtleBot mazeBuilt-in5 cm/px
demo-world-enhancedMaze + textured walls + ArUco markersArUco, PBR textures5 cm/px
demo-world-houseAWS residential house68 residential5 cm/px
demo-world-bookstoreAWS bookstore34 retail5 cm/px
demo-world-warehouseAWS warehouse (no roof)14 industrial2 cm/px
All worlds use the same Docker images and behavior demo services — only the world service name changes.

Key SDF elements reference

ElementPurpose
<world>Top-level container for the entire scene
<model>A named, poseable assembly of links and joints
<link>A rigid body with mass, inertia, collision, and visual
<joint>A constraint between two links (fixed, revolute, prismatic…)
<collision>Shape used for physics contact detection
<visual>Shape used for rendering only
<inertial>Mass and moment-of-inertia tensor
<geometry>Primitive (box, sphere, cylinder) or mesh reference
<plugin>Gazebo system plugin (physics, sensors, GUI)
<pose>6-DOF placement: x y z roll pitch yaw
<static>If true, the model is fixed to the world frame
<include>Reference an external model by URI