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.sim.cfg import (
 31    RigidObjectCfg,
 32    RigidBodyAttributesCfg,
 33    ClothObjectCfg,
 34    ClothPhysicalAttributesCfg,
 35)
 36from embodichain.lab.sim.shapes import MeshCfg, CubeCfg
 37from embodichain.lab.sim.objects import ClothObject
 38
 39
 40def create_2d_grid_mesh(width: float, height: float, nx: int = 1, ny: int = 1):
 41    """Create a flat rectangle in the XY plane centered at `origin`.
 42
 43    The rectangle is subdivided into an `nx` by `ny` grid (cells) and
 44    triangulated. `nx=1, ny=1` yields the simple two-triangle rectangle.
 45
 46    Returns an vertices and triangles.
 47    """
 48    w = float(width)
 49    h = float(height)
 50    if nx < 1 or ny < 1:
 51        raise ValueError("nx and ny must be >= 1")
 52
 53    # Vectorized vertex positions using PyTorch
 54    x_lin = torch.linspace(-w / 2.0, w / 2.0, steps=nx + 1, dtype=torch.float64)
 55    y_lin = torch.linspace(-h / 2.0, h / 2.0, steps=ny + 1, dtype=torch.float64)
 56    yy, xx = torch.meshgrid(y_lin, x_lin)  # shapes: (ny+1, nx+1)
 57    xx_flat = xx.reshape(-1)
 58    yy_flat = yy.reshape(-1)
 59    zz_flat = torch.full_like(xx_flat, 0, dtype=torch.float64)
 60    verts = torch.stack([xx_flat, yy_flat, zz_flat], dim=1)  # (Nverts, 3)
 61
 62    # Vectorized triangle indices
 63    idx = torch.arange((nx + 1) * (ny + 1), dtype=torch.int64).reshape(ny + 1, nx + 1)
 64    v0 = idx[:-1, :-1].reshape(-1)
 65    v1 = idx[:-1, 1:].reshape(-1)
 66    v2 = idx[1:, :-1].reshape(-1)
 67    v3 = idx[1:, 1:].reshape(-1)
 68    tri1 = torch.stack([v0, v1, v3], dim=1)
 69    tri2 = torch.stack([v0, v3, v2], dim=1)
 70    faces = torch.cat([tri1, tri2], dim=0).to(torch.int32)
 71    return verts, faces
 72
 73
 74def main():
 75    """Main function to create and run the simulation scene."""
 76
 77    # Parse command line arguments
 78    parser = argparse.ArgumentParser(
 79        description="Create a simulation scene with SimulationManager"
 80    )
 81    parser.add_argument(
 82        "--headless",
 83        action="store_true",
 84        default=False,
 85        help="Run simulation in headless mode",
 86    )
 87    parser.add_argument(
 88        "--num_envs", type=int, default=1, help="Number of parallel environments"
 89    )
 90    parser.add_argument(
 91        "--enable_rt",
 92        action="store_true",
 93        default=False,
 94        help="Enable ray tracing for better visuals",
 95    )
 96    args = parser.parse_args()
 97
 98    # Configure the simulation
 99    sim_cfg = SimulationManagerCfg(
100        width=1920,
101        height=1080,
102        headless=True,
103        physics_dt=1.0 / 100.0,  # Physics timestep (100 Hz)
104        sim_device="cuda",  # soft simulation only supports cuda device
105        enable_rt=args.enable_rt,  # Enable ray tracing for better visuals
106        num_envs=args.num_envs,  # Number of parallel environments
107        arena_space=2.0,
108    )
109
110    # Create the simulation instance
111    sim = SimulationManager(sim_cfg)
112
113    print("[INFO]: Scene setup complete!")
114
115    cloth_verts, cloth_faces = create_2d_grid_mesh(width=0.3, height=0.3, nx=12, ny=12)
116    cloth_mesh = o3d.geometry.TriangleMesh(
117        vertices=o3d.utility.Vector3dVector(cloth_verts.to("cpu").numpy()),
118        triangles=o3d.utility.Vector3iVector(cloth_faces.to("cpu").numpy()),
119    )
120    cloth_save_path = os.path.join(tempfile.gettempdir(), "cloth_mesh.ply")
121    o3d.io.write_triangle_mesh(cloth_save_path, cloth_mesh)
122    # add cloth to the scene
123    cloth = sim.add_cloth_object(
124        cfg=ClothObjectCfg(
125            uid="cloth",
126            shape=MeshCfg(fpath=cloth_save_path),
127            init_pos=[0.5, 0.0, 0.3],
128            init_rot=[0, 0, 0],
129            physical_attr=ClothPhysicalAttributesCfg(
130                mass=0.01,
131                youngs=1e10,
132                poissons=0.4,
133                thickness=0.04,
134                bending_stiffness=0.01,
135                bending_damping=0.1,
136                dynamic_friction=0.95,
137                min_position_iters=30,
138            ),
139        )
140    )
141    padding_box_cfg = RigidObjectCfg(
142        uid="padding_box",
143        shape=CubeCfg(
144            size=[0.1, 0.1, 0.06],
145        ),
146        attrs=RigidBodyAttributesCfg(
147            mass=1.0,
148            static_friction=0.95,
149            dynamic_friction=0.9,
150            restitution=0.01,
151            min_position_iters=32,
152            min_velocity_iters=8,
153        ),
154        body_type="dynamic",
155        init_pos=[0.5, 0.0, 0.04],
156        init_rot=[0.0, 0.0, 0.0],
157    )
158    padding_box = sim.add_rigid_object(cfg=padding_box_cfg)
159    print("[INFO]: Add soft object complete!")
160
161    # Open window when the scene has been set up
162    if not args.headless:
163        sim.open_window()
164
165    print(f"[INFO]: Running simulation with {args.num_envs} environment(s)")
166    print("[INFO]: Press Ctrl+C to stop the simulation")
167
168    # Run the simulation
169    run_simulation(sim, cloth)
170
171
172def run_simulation(sim: SimulationManager, cloth: ClothObject) -> None:
173    """Run the simulation loop.
174
175    Args:
176        sim: The SimulationManager instance to run
177        soft_obj: soft object
178    """
179
180    # Initialize GPU physics
181    sim.init_gpu_physics()
182
183    step_count = 0
184
185    try:
186        last_time = time.time()
187        last_step = 0
188        while True:
189            # Update physics simulation
190            sim.update(step=1)
191            step_count += 1
192
193            # Print FPS every second
194            if step_count % 100 == 0:
195                current_time = time.time()
196                elapsed = current_time - last_time
197                fps = (
198                    sim.num_envs * (step_count - last_step) / elapsed
199                    if elapsed > 0
200                    else 0
201                )
202                print(f"[INFO]: Simulation step: {step_count}, FPS: {fps:.2f}")
203                last_time = current_time
204                last_step = step_count
205                if step_count % 500 == 0:
206                    cloth.reset()
207
208    except KeyboardInterrupt:
209        print("\n[INFO]: Stopping simulation...")
210    finally:
211        # Clean up resources
212        sim.destroy()
213        print("[INFO]: Simulation terminated successfully")
214
215
216if __name__ == "__main__":
217    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,
        physics_dt=1.0 / 100.0,  # Physics timestep (100 Hz)
        sim_device="cuda",  # soft simulation only supports cuda device
        enable_rt=args.enable_rt,  # Enable ray tracing for better visuals
        num_envs=args.num_envs,  # Number of parallel environments
        arena_space=2.0,
    )

    # 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=1e10,
                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.