🏔️ Terrain Simulation and Generation#
Genesis provides first-class support for height-field terrains via the gs.morphs.Terrain morph. A terrain is a static rigid object represented internally by a height map (for fast collision queries) and a watertight triangle mesh (for visualisation & SDF generation).
This page introduces the three most common ways to create terrains:
Pass in your own NumPy height map.
Procedurally generate a sub-terrain grid (Isaac Gym style).
Convert an arbitrary triangle mesh to a height map automatically.
1 Use a custom height map#
If you already have terrain data (for example from DEM files) you can feed it directly to Genesis. The only two numbers you need are the horizontal and vertical scales.
import numpy as np
import genesis as gs
# 1. initialise Genesis
gs.init(seed=0, backend=gs.gpu) # use gs.cpu for CPU backend
# 2. create a scene
scene = gs.Scene(show_viewer=True)
# 3. prepare a height map (here a simple bump for demo)
hf = np.zeros((40, 40), dtype=np.int16)
hf[10:30, 10:30] = 200 * np.hanning(20)[:, None] * np.hanning(20)[None, :]
horizontal_scale = 0.25 # metres between grid points
vertical_scale = 0.005 # metres per height-field unit
# 4. add the terrain entity
scene.add_entity(
morph=gs.morphs.Terrain(
height_field=hf,
horizontal_scale=horizontal_scale,
vertical_scale=vertical_scale,
),
)
scene.build()
# run the sim so you can inspect the surface
for _ in range(1_000):
scene.step()
Visual debugging tip#
After building the scene the height map is stored in terrain.geoms[0].metadata["height_field"]. You can draw small spheres on each sample to see the actual geometry:
import torch
hf = terrain.geoms[0].metadata["height_field"]
rows = horizontal_scale * torch.arange(hf.shape[0]).unsqueeze(1).repeat(1, hf.shape[1])
cols = horizontal_scale * torch.arange(hf.shape[1]).unsqueeze(0).repeat(hf.shape[0], 1)
heights = vertical_scale * torch.tensor(hf)
poss = torch.stack((rows, cols, heights), dim=-1).reshape(-1, 3)
scene.draw_debug_spheres(poss, radius=0.05, color=(0, 0, 1, 0.7))
2 Procedural sub-terrains#
gs.morphs.Terrain can also synthesise complex grounds by tiling a grid of sub-terrains – the same technique used by Isaac Gym. You only specify:
n_subterrains=(nx, ny)– how many tiles in each direction.subterrain_size=(sx, sy)– size of each tile in metres.subterrain_types– a 2-D list selecting a generator for each tile.
The full list of built-in generators is:
flat_terrain, random_uniform_terrain, pyramid_sloped_terrain, discrete_obstacles_terrain, wave_terrain, pyramid_stairs_terrain, stairs_terrain, stepping_stones_terrain, fractal_terrain.
scene = gs.Scene(show_viewer=True)
terrain = scene.add_entity(
morph=gs.morphs.Terrain(
n_subterrains=(2, 2),
subterrain_size=(6.0, 6.0),
horizontal_scale=0.25,
vertical_scale=0.005,
subterrain_types=[
["flat_terrain", "random_uniform_terrain"],
["pyramid_sloped_terrain", "discrete_obstacles_terrain"],
],
),
)
scene.build(n_envs=100) # you can still run many parallel envs
The code above is essentially the same as examples/rigid/terrain_subterrain.py shipped with Genesis. Feel free to open the example for a complete runnable script.
3 Generate a height map from a triangle mesh#
Sometimes you already have a detailed CAD or photogrammetry mesh and just want collisions to run quickly. The helper genesis.utils.terrain.mesh_to_heightfield samples the mesh with vertical rays and returns a NumPy height array together with the grid coordinates.
from genesis.utils.terrain import mesh_to_heightfield
import os
# path to your .obj / .glb / .stl terrain
mesh_path = os.path.join(gs.__path__[0], "assets", "meshes", "terrain_45.obj")
horizontal_scale = 2.0 # desired grid spacing (metres)
height, xs, ys = mesh_to_heightfield(mesh_path, spacing=horizontal_scale, oversample=3)
# shift the terrain so the centre of the mesh becomes (0,0)
translation = np.array([xs.min(), ys.min(), 0.0])
scene = gs.Scene(show_viewer=True)
scene.add_entity(
morph=gs.morphs.Terrain(
height_field=height,
horizontal_scale=horizontal_scale,
vertical_scale=1.0,
pos=translation, # optional world transform
),
)
scene.add_entity(gs.morphs.Sphere(pos=(10, 15, 10), radius=1))
scene.build()
This procedure is wrapped in examples/rigid/terrain_from_mesh.py.
API reference#
For a complete list of keyword arguments please refer to the autogenerated API page:
- class genesis.options.morphs.Terrain(*, pos: tuple = (0.0, 0.0, 0.0), euler: tuple | None = None, quat: tuple | None = None, visualization: bool = True, collision: bool = True, requires_jac_and_IK: bool = False, is_free: bool | None = None, randomize: bool = False, n_subterrains: Tuple[int, int] = (3, 3), subterrain_size: Tuple[float, float] = (12.0, 12.0), horizontal_scale: float = 0.25, vertical_scale: float = 0.005, uv_scale: float = 1.0, subterrain_types: Any = [['flat_terrain', 'random_uniform_terrain', 'stepping_stones_terrain'], ['pyramid_sloped_terrain', 'discrete_obstacles_terrain', 'wave_terrain'], ['random_uniform_terrain', 'pyramid_stairs_terrain', 'sloped_terrain']], height_field: Any = None, name: str | None = None, from_stored: Any = None, subterrain_parameters: dict[str, dict] | None = None)[source]#
Bases:
MorphMorph for creating a rigid terrain. This can be instantiated from two choices: 1) a grid of subterrains generated using the given configurations 2) a terrain generated using the given height field.
If randomize is True, subterrain type that involves randomness will have random parameters. Otherwise, they will use fixed random seed 0.
Users can easily configure the subterrain types by specifying the subterrain_types parameter. If using a single string, it will be repeated for all subterrains. If it’s a 2D list, it should have the same shape as n_subterrains. The supported subterrain types are:
‘flat_terrain’: flat terrain
‘random_uniform_terrain’: random uniform terrain
‘sloped_terrain’: sloped terrain
‘pyramid_sloped_terrain’: pyramid sloped terrain
‘discrete_obstacles_terrain’: discrete obstacles terrain
‘wave_terrain’: wave terrain
‘stairs_terrain’: stairs terrain
‘pyramid_stairs_terrain’: pyramid stairs terrain
‘stepping_stones_terrain’: stepping stones terrain
Note
Rigid terrain will also be represented as SDF for collision checking, but its resolution is auto-computed and ignores the value specified in gs.materials.Rigid().
- Parameters:
file (str) – The path to the file.
scale (float or tuple, optional) – The scaling factor for the size of the entity. If a float, it scales uniformly. If a 3-tuple, it scales along each axis. Defaults to 1.0. Note that 3-tuple scaling is only supported for gs.morphs.Mesh.
pos (tuple, shape (3,), optional) – The position of the entity in meters. Defaults to (0.0, 0.0, 0.0).
visualization (bool, optional) – Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision purposes. Defaults to True. visualization and collision cannot both be False.
collision (bool, optional) – Whether the entity needs to be considered for collision checking. Defaults to True. visualization and collision cannot both be False.
randomize (bool, optional) – Whether to randomize the subterrains that involve randomness. Defaults to False.
n_subterrains (tuple of int, optional) – The number of subterrains in x and y directions. Defaults to (3, 3).
subterrain_size (tuple of float, optional) – The size of each subterrain in meters. Defaults to (12.0, 12.0).
horizontal_scale (float, optional) – The size of each cell in the subterrain in meters. Defaults to 0.25.
vertical_scale (float, optional) – The height of each step in the subterrain in meters. Defaults to 0.005.
uv_scale (float, optional) – The scale of the UV mapping for the terrain. Defaults to 1.0.
subterrain_types (str or 2D list of str, optional) – The types of subterrains to generate. If a string, it will be repeated for all subterrains. If a 2D list, it should have the same shape as n_subterrains.
height_field (array-like, optional) – The height field to generate the terrain. If specified, all other configurations will be ignored. Defaults to None.
name (str, optional) – The name of the terrain. If specified, the terrain will only be generated once for a given set of options and later loaded from cache, instead of being re-generated systematically when building the scene. This holds true no matter if randomize is True.
from_stored (str, optional) – This parameter is deprecated.
subterrain_parameters (dictionary, optional) – Lets users pick their own subterrain parameters.
- model_config: ClassVar[ConfigDict] = {}#
Configuration for the model, should be a dictionary conforming to [ConfigDict][pydantic.config.ConfigDict].
Saving & re-using terrains#
When a terrain is created, Genesis generates the height map, the watertight mesh for collision detection and the simplified mesh for visuals. One can enable caching of the height map when a terrain is first created for a given set of options by passing name="my_terrain", which would later be loaded from cache without regeneration. This is useful for reconstructing randomized terrains exactly.
Happy climbing! 🧗♂️🏔️