Skip to content

Gazebo heightmap terrain

A heightmap creates terrain from a grayscale image. Dark pixels are low points, bright pixels are high points, and Gazebo scales the result using the <size> element.

In Gazebo Harmonic, use the SDFormat <heightmap> geometry inside a normal static model. Put the same heightmap geometry in both <collision> and <visual> so physics and rendering use the same terrain.

cd /home/user/projects/new_blog/docs/Simulation/Gazebo/demo_worlds/heightmap/code
gz sim --force-version 8 heightmap_world.sdf

The official Gazebo Harmonic GUI docs recommend --force-version 8 when more than one Gazebo version is installed.

Embedded heightmap world

The important part is the heightmap_terrain model. It is not included from Fuel or a separate model folder; it is embedded directly in the world file.

Complete world
<?xml version="1.0" ?>
<sdf version="1.9">
  <world name="heightmap_demo">
    <physics name="1ms" type="ignored">
      <max_step_size>0.001</max_step_size>
      <real_time_factor>1.0</real_time_factor>
    </physics>

    <plugin
      filename="gz-sim-physics-system"
      name="gz::sim::systems::Physics">
    </plugin>
    <plugin
      filename="gz-sim-user-commands-system"
      name="gz::sim::systems::UserCommands">
    </plugin>
    <plugin
      filename="gz-sim-scene-broadcaster-system"
      name="gz::sim::systems::SceneBroadcaster">
    </plugin>

    <light type="directional" name="sun">
      <cast_shadows>true</cast_shadows>
      <pose>0 0 35 0 0 0</pose>
      <diffuse>0.9 0.86 0.78 1</diffuse>
      <specular>0.25 0.25 0.25 1</specular>
      <attenuation>
        <range>1000</range>
        <constant>0.9</constant>
        <linear>0.01</linear>
        <quadratic>0.001</quadratic>
      </attenuation>
      <direction>-0.45 0.35 -0.82</direction>
    </light>

    <model name="heightmap_terrain">
      <static>true</static>
      <link name="terrain_link">
        <collision name="terrain_collision">
          <geometry>
            <heightmap>
              <uri>media/ridge_heightmap.png</uri>
              <size>60 60 8</size>
              <pos>0 0 0</pos>
              <sampling>2</sampling>
            </heightmap>
          </geometry>
        </collision>
        <visual name="terrain_visual">
          <geometry>
            <heightmap>
              <uri>media/ridge_heightmap.png</uri>
              <size>60 60 8</size>
              <pos>0 0 0</pos>
              <sampling>2</sampling>
              <texture>
                <size>8</size>
                <diffuse>media/terrain_diffuse.png</diffuse>
                <normal>media/flat_normal.png</normal>
              </texture>
            </heightmap>
          </geometry>
        </visual>
      </link>
    </model>

    <model name="contact_test_box">
      <pose>6 -10 9 0 0 0.3</pose>
      <link name="link">
        <inertial>
          <mass>1.0</mass>
          <inertia>
            <ixx>0.166</ixx>
            <iyy>0.166</iyy>
            <izz>0.166</izz>
          </inertia>
        </inertial>
        <collision name="collision">
          <geometry>
            <box>
              <size>1 1 1</size>
            </box>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <box>
              <size>1 1 1</size>
            </box>
          </geometry>
          <material>
            <ambient>0.1 0.35 0.8 1</ambient>
            <diffuse>0.1 0.35 0.8 1</diffuse>
          </material>
        </visual>
      </link>
    </model>
  </world>
</sdf>
Reusable model file
<?xml version="1.0" ?>
<sdf version="1.9">
  <model name="heightmap_terrain">
    <static>true</static>
    <link name="terrain_link">
      <collision name="terrain_collision">
        <geometry>
          <heightmap>
            <uri>media/ridge_heightmap.png</uri>
            <size>60 60 8</size>
            <pos>0 0 0</pos>
            <sampling>2</sampling>
          </heightmap>
        </geometry>
      </collision>
      <visual name="terrain_visual">
        <geometry>
          <heightmap>
            <uri>media/ridge_heightmap.png</uri>
            <size>60 60 8</size>
            <pos>0 0 0</pos>
            <sampling>2</sampling>
            <texture>
              <size>8</size>
              <diffuse>media/terrain_diffuse.png</diffuse>
              <normal>media/flat_normal.png</normal>
            </texture>
          </heightmap>
        </geometry>
      </visual>
    </link>
  </model>
</sdf>

Heightmap elements

<heightmap>
  <uri>media/ridge_heightmap.png</uri>
  <size>60 60 8</size>
  <pos>0 0 0</pos>
  <sampling>2</sampling>
  <texture>
    <size>8</size>
    <diffuse>media/terrain_diffuse.png</diffuse>
    <normal>media/flat_normal.png</normal>
  </texture>
</heightmap>
Element Meaning
<uri> Path to the grayscale image. In this example it is relative to the SDF file.
<size>x y z</size> Terrain width, length, and height range in meters. Here the image becomes a 60 m by 60 m terrain with up to 8 m of relief.
<pos> Offset for the generated terrain.
<sampling> Samples per heightmap datum. Higher values look smoother but cost more.
<texture> Diffuse and normal textures used by the visual terrain.
<blend> Optional. Use it when you add multiple textures and want different materials by elevation.
<use_terrain_paging> Optional. Useful for very large terrains if the renderer supports terrain paging.

Note

The SDFormat spec describes <heightmap> as a geometry based on a 2D grayscale image. It also supports DEM files. Gazebo Rendering's heightmap example shows both image heightmaps and DEM heightmaps.

Creating the heightmap image

Use a square grayscale image. Power-of-two-plus-one sizes such as 129x129, 257x257, or 513x513 are common for terrain grids.

  • Black means the lowest terrain height.
  • White means the highest terrain height.
  • Smooth gradients create slopes.
  • Sharp brightness changes create cliffs or collision edges.
  • Increase the third value in <size> to exaggerate height.

For example, if <size>60 60 8</size>:

  • black pixels are near z = 0
  • white pixels are near z = 8
  • a 50% gray pixel is near z = 4

Alternatives for terrain

Heightmap image: Best for local test worlds, rough outdoor terrain, and hand-authored hills. This is the simplest option.

DEM heightmap: Best for real terrain data from GIS sources. Gazebo Harmonic lists DEM support, and the rendering example loads a .tif DEM. With DEM data, watch the vertical offset because real elevation files may include negative minimum elevation.

Mesh terrain: Use <mesh> with .dae, .obj, or .stl when you need overhangs, caves, walls, buildings, or artist-authored geometry. Heightmaps cannot represent vertical overhangs because each x-y point has only one height.

SDF image extrusion: SDFormat also has <image> geometry, which extrudes boxes from a grayscale image. It is useful for blocky obstacles, occupancy-map-like layouts, and quick maze or wall tests, not natural terrain.

Primitive terrain: Use planes, boxes, ramps, and cylinders for deterministic unit tests. This is better than a heightmap when you need exact contact geometry.

Fuel or GUI world editing: Gazebo can insert models from Fuel and save worlds from the GUI. This is useful for assembling a scene quickly, then you can edit the saved SDF by hand.

Common issues

  • If the robot falls through the terrain, make sure the <collision> also uses the heightmap geometry.
  • If the terrain appears flat, increase the z value in <size>.
  • If textures do not load, run Gazebo from the code folder or use paths resolvable from GZ_SIM_RESOURCE_PATH.
  • If startup uses the wrong Gazebo version, run gz sim --versions and use gz sim --force-version 8 ... for Harmonic.

References