Creating a cloth simulation#

This tutorial shows how to create a cloth simulation using SimulationManager. It covers procedurally generating a grid mesh, configuring a deformable cloth object, adding a rigid body for interaction, and running the simulation loop.

The Code#

The tutorial corresponds to the create_cloth.py script in the scripts/tutorials/sim directory.

Code for create_cloth.py
  1# ----------------------------------------------------------------------------
  2# Copyright (c) 2021-2026 DexForce Technology Co., Ltd.
  3#
  4# Licensed under the Apache License, Version 2.0 (the "License");
  5# you may not use this file except in compliance with the License.
  6# You may obtain a copy of the License at
  7#
  8#     http://www.apache.org/licenses/LICENSE-2.0
  9#
 10# Unless required by applicable law or agreed to in writing, software
 11# distributed under the License is distributed on an "AS IS" BASIS,
 12# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 13# See the License for the specific language governing permissions and
 14# limitations under the License.
 15# ----------------------------------------------------------------------------
 16
 17"""
 18This script demonstrates how to create a simulation scene using SimulationManager.
 19It shows the basic setup of simulation context, adding objects, lighting, and sensors.
 20"""
 21
 22import argparse
 23import os
 24import tempfile
 25import time
 26import torch
 27import open3d as o3d
 28from dexsim.utility.path import get_resources_data_path
 29from embodichain.lab.sim import SimulationManager, SimulationManagerCfg
 30from embodichain.lab.gym.utils.gym_utils import add_env_launcher_args_to_parser
 31from embodichain.lab.sim.cfg import (
 32    RenderCfg,
 33    RigidObjectCfg,
 34    RigidBodyAttributesCfg,
 35    ClothObjectCfg,
 36    ClothPhysicalAttributesCfg,
 37)
 38from embodichain.lab.sim.shapes import MeshCfg, CubeCfg
 39from embodichain.lab.sim.objects import ClothObject
 40
 41
 42def create_2d_grid_mesh(width: float, height: float, nx: int = 1, ny: int = 1):
 43    """Create a flat rectangle in the XY plane centered at `origin`.
 44
 45    The rectangle is subdivided into an `nx` by `ny` grid (cells) and
 46    triangulated. `nx=1, ny=1` yields the simple two-triangle rectangle.
 47
 48    Returns an vertices and triangles.
 49    """
 50    w = float(width)
 51    h = float(height)
 52    if nx < 1 or ny < 1:
 53        raise ValueError("nx and ny must be >= 1")
 54
 55    # Vectorized vertex positions using PyTorch
 56    x_lin = torch.linspace(-w / 2.0, w / 2.0, steps=nx + 1, dtype=torch.float64)
 57    y_lin = torch.linspace(-h / 2.0, h / 2.0, steps=ny + 1, dtype=torch.float64)
 58    yy, xx = torch.meshgrid(y_lin, x_lin)  # shapes: (ny+1, nx+1)
 59    xx_flat = xx.reshape(-1)
 60    yy_flat = yy.reshape(-1)
 61    zz_flat = torch.full_like(xx_flat, 0, dtype=torch.float64)
 62    verts = torch.stack([xx_flat, yy_flat, zz_flat], dim=1)  # (Nverts, 3)
 63
 64    # Vectorized triangle indices
 65    idx = torch.arange((nx + 1) * (ny + 1), dtype=torch.int64).reshape(ny + 1, nx + 1)
 66    v0 = idx[:-1, :-1].reshape(-1)
 67    v1 = idx[:-1, 1:].reshape(-1)
 68    v2 = idx[1:, :-1].reshape(-1)
 69    v3 = idx[1:, 1:].reshape(-1)
 70    tri1 = torch.stack([v0, v1, v3], dim=1)
 71    tri2 = torch.stack([v0, v3, v2], dim=1)
 72    faces = torch.cat([tri1, tri2], dim=0).to(torch.int32)
 73    return verts, faces
 74
 75
 76def main():
 77    """Main function to create and run the simulation scene."""
 78
 79    # Parse command line arguments
 80    parser = argparse.ArgumentParser(
 81        description="Create a simulation scene with SimulationManager"
 82    )
 83    add_env_launcher_args_to_parser(parser)
 84    args = parser.parse_args()
 85
 86    # Configure the simulation
 87    sim_cfg = SimulationManagerCfg(
 88        width=1920,
 89        height=1080,
 90        headless=True,
 91        num_envs=args.num_envs,
 92        physics_dt=1.0 / 100.0,  # Physics timestep (100 Hz)
 93        sim_device="cuda",  # soft simulation only supports cuda device
 94        render_cfg=RenderCfg(renderer=args.renderer),
 95    )
 96
 97    # Create the simulation instance
 98    sim = SimulationManager(sim_cfg)
 99
100    print("[INFO]: Scene setup complete!")
101
102    cloth_verts, cloth_faces = create_2d_grid_mesh(width=0.3, height=0.3, nx=12, ny=12)
103    cloth_mesh = o3d.geometry.TriangleMesh(
104        vertices=o3d.utility.Vector3dVector(cloth_verts.to("cpu").numpy()),
105        triangles=o3d.utility.Vector3iVector(cloth_faces.to("cpu").numpy()),
106    )
107    cloth_save_path = os.path.join(tempfile.gettempdir(), "cloth_mesh.ply")
108    o3d.io.write_triangle_mesh(cloth_save_path, cloth_mesh)
109    # add cloth to the scene
110    cloth = sim.add_cloth_object(
111        cfg=ClothObjectCfg(
112            uid="cloth",
113            shape=MeshCfg(fpath=cloth_save_path),
114            init_pos=[0.5, 0.0, 0.3],
115            init_rot=[0, 0, 0],
116            physical_attr=ClothPhysicalAttributesCfg(
117                mass=0.01,
118                youngs=1e9,
119                poissons=0.4,
120                thickness=0.04,
121                bending_stiffness=0.01,
122                bending_damping=0.1,
123                dynamic_friction=0.95,
124                min_position_iters=30,
125            ),
126        )
127    )
128    padding_box_cfg = RigidObjectCfg(
129        uid="padding_box",
130        shape=CubeCfg(
131            size=[0.1, 0.1, 0.06],
132        ),
133        attrs=RigidBodyAttributesCfg(
134            mass=1.0,
135            static_friction=0.95,
136            dynamic_friction=0.9,
137            restitution=0.01,
138            min_position_iters=32,
139            min_velocity_iters=8,
140        ),
141        body_type="dynamic",
142        init_pos=[0.5, 0.0, 0.04],
143        init_rot=[0.0, 0.0, 0.0],
144    )
145    padding_box = sim.add_rigid_object(cfg=padding_box_cfg)
146    print("[INFO]: Add soft object complete!")
147
148    # Open window when the scene has been set up
149    if not args.headless:
150        sim.open_window()
151
152    print(f"[INFO]: Running simulation with {args.num_envs} environment(s)")
153    print("[INFO]: Press Ctrl+C to stop the simulation")
154
155    # Run the simulation
156    run_simulation(sim, cloth)
157
158
159def run_simulation(sim: SimulationManager, cloth: ClothObject) -> None:
160    """Run the simulation loop.
161
162    Args:
163        sim: The SimulationManager instance to run
164        soft_obj: soft object
165    """
166
167    # Initialize GPU physics
168    sim.init_gpu_physics()
169
170    step_count = 0
171
172    try:
173        last_time = time.time()
174        last_step = 0
175        while True:
176            # Update physics simulation
177            sim.update(step=1)
178            step_count += 1
179
180            # Print FPS every second
181            if step_count % 100 == 0:
182                current_time = time.time()
183                elapsed = current_time - last_time
184                fps = (
185                    sim.num_envs * (step_count - last_step) / elapsed
186                    if elapsed > 0
187                    else 0
188                )
189                print(f"[INFO]: Simulation step: {step_count}, FPS: {fps:.2f}")
190                last_time = current_time
191                last_step = step_count
192                if step_count % 500 == 0:
193                    cloth.reset()
194
195    except KeyboardInterrupt:
196        print("\n[INFO]: Stopping simulation...")
197    finally:
198        # Clean up resources
199        sim.destroy()
200        print("[INFO]: Simulation terminated successfully")
201
202
203if __name__ == "__main__":
204    main()

The Code Explained#

Generating the cloth mesh#

Unlike the soft-body tutorial where a pre-existing mesh file is loaded, cloth objects are typically defined by a flat 2-D surface. The helper function create_2d_grid_mesh generates a rectangular grid mesh procedurally using PyTorch, then saves it to a temporary .ply file via Open3D so that the simulation can load it.

Loading a mesh from file also works for cloth objects, but generating a grid in code allows for easy customization of the cloth dimensions and resolution.

The function accepts the physical dimensions (width, height) and the number of subdivisions (nx, ny). A finer grid gives more cloth-like wrinkle detail at the cost of simulation performance.

def create_2d_grid_mesh(width: float, height: float, nx: int = 1, ny: int = 1):
    """Create a flat rectangle in the XY plane centered at `origin`.

    The rectangle is subdivided into an `nx` by `ny` grid (cells) and
    triangulated. `nx=1, ny=1` yields the simple two-triangle rectangle.

    Returns an vertices and triangles.
    """
    w = float(width)
    h = float(height)
    if nx < 1 or ny < 1:
        raise ValueError("nx and ny must be >= 1")

    # Vectorized vertex positions using PyTorch
    x_lin = torch.linspace(-w / 2.0, w / 2.0, steps=nx + 1, dtype=torch.float64)
    y_lin = torch.linspace(-h / 2.0, h / 2.0, steps=ny + 1, dtype=torch.float64)
    yy, xx = torch.meshgrid(y_lin, x_lin)  # shapes: (ny+1, nx+1)
    xx_flat = xx.reshape(-1)
    yy_flat = yy.reshape(-1)
    zz_flat = torch.full_like(xx_flat, 0, dtype=torch.float64)
    verts = torch.stack([xx_flat, yy_flat, zz_flat], dim=1)  # (Nverts, 3)

    # Vectorized triangle indices
    idx = torch.arange((nx + 1) * (ny + 1), dtype=torch.int64).reshape(ny + 1, nx + 1)
    v0 = idx[:-1, :-1].reshape(-1)
    v1 = idx[:-1, 1:].reshape(-1)
    v2 = idx[1:, :-1].reshape(-1)
    v3 = idx[1:, 1:].reshape(-1)
    tri1 = torch.stack([v0, v1, v3], dim=1)
    tri2 = torch.stack([v0, v3, v2], dim=1)
    faces = torch.cat([tri1, tri2], dim=0).to(torch.int32)
    return verts, faces

Configuring the simulation#

The simulation environment is configured with SimulationManagerCfg. For cloth simulation the device must be set to cuda. The arena_space parameter controls the spacing between parallel environments so that objects in neighboring environments do not overlap.

    # Configure the simulation
    sim_cfg = SimulationManagerCfg(
        width=1920,
        height=1080,
        headless=True,
        num_envs=args.num_envs,
        physics_dt=1.0 / 100.0,  # Physics timestep (100 Hz)
        sim_device="cuda",  # soft simulation only supports cuda device
        render_cfg=RenderCfg(renderer=args.renderer),
    )

    # Create the simulation instance
    sim = SimulationManager(sim_cfg)

    print("[INFO]: Scene setup complete!")

Adding a cloth object to the scene#

The grid mesh generated earlier is saved to disk and then passed to SimulationManager.add_cloth_object(). The physical properties of the cloth are controlled through cfg.ClothObjectCfg together with cfg.ClothPhysicalAttributesCfg:

  • cfg.MeshCfg — references the .ply file written to the system temp directory

  • cfg.ClothPhysicalAttributesCfg — material parameters:

    • mass — total mass of the cloth panel (kg)

    • youngs / poissons — elastic stiffness and compressibility

    • thickness — collision thickness of the cloth surface

    • bending_stiffness / bending_damping — resistance to and dissipation of bending motion

    • dynamic_friction — friction between the cloth and other objects

    • min_position_iters — solver iteration count for position constraints

    cloth_verts, cloth_faces = create_2d_grid_mesh(width=0.3, height=0.3, nx=12, ny=12)
    cloth_mesh = o3d.geometry.TriangleMesh(
        vertices=o3d.utility.Vector3dVector(cloth_verts.to("cpu").numpy()),
        triangles=o3d.utility.Vector3iVector(cloth_faces.to("cpu").numpy()),
    )
    cloth_save_path = os.path.join(tempfile.gettempdir(), "cloth_mesh.ply")
    o3d.io.write_triangle_mesh(cloth_save_path, cloth_mesh)
    # add cloth to the scene
    cloth = sim.add_cloth_object(
        cfg=ClothObjectCfg(
            uid="cloth",
            shape=MeshCfg(fpath=cloth_save_path),
            init_pos=[0.5, 0.0, 0.3],
            init_rot=[0, 0, 0],
            physical_attr=ClothPhysicalAttributesCfg(
                mass=0.01,
                youngs=1e9,
                poissons=0.4,
                thickness=0.04,
                bending_stiffness=0.01,
                bending_damping=0.1,
                dynamic_friction=0.95,
                min_position_iters=30,
            ),
        )
    )
    padding_box_cfg = RigidObjectCfg(

Adding a rigid body for interaction#

A small cubic rigid body (padding_box) is placed beneath the cloth so the cloth drapes over it. It is added with SimulationManager.add_rigid_object() using cfg.RigidObjectCfg and cfg.RigidBodyAttributesCfg:

  • cfg.CubeCfg — defines the box dimensions

  • body_type="dynamic" — the box responds to physics; change to "static" for a fixed obstacle

  • static_friction / dynamic_friction — surface friction keeps the cloth from sliding off too easily

    padding_box_cfg = RigidObjectCfg(
        uid="padding_box",
        shape=CubeCfg(
            size=[0.1, 0.1, 0.06],
        ),
        attrs=RigidBodyAttributesCfg(
            mass=1.0,
            static_friction=0.95,
            dynamic_friction=0.9,
            restitution=0.01,
            min_position_iters=32,
            min_velocity_iters=8,
        ),
        body_type="dynamic",
        init_pos=[0.5, 0.0, 0.04],
        init_rot=[0.0, 0.0, 0.0],
    )
    padding_box = sim.add_rigid_object(cfg=padding_box_cfg)
    print("[INFO]: Add soft object complete!")

The Code Execution#

To run the script and see the result, execute the following command:

python scripts/tutorials/sim/create_cloth.py

A window should appear showing a cloth panel falling and draping over a small rigid box. To stop the simulation, close the window or press Ctrl+C in the terminal.

You can also pass arguments to customise the simulation. For example, to run in headless mode with n parallel environments:

python scripts/tutorials/sim/create_cloth.py --headless --num_envs <n>

Now that we have a basic understanding of how to create a cloth scene, let’s move on to more advanced topics.