# 🏔️ 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: 1. Pass in your own NumPy height map. 2. Procedurally generate a *sub-terrain* grid (Isaac Gym style). 3. 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. ```python 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: ```python 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`. ```python 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. ```python 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: ```{eval-rst} .. autoclass:: genesis.options.morphs.Terrain :members: :show-inheritance: ``` --- ### 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! 🧗‍♂️🏔️