From 5c3f1c5f3c5247e947307d05c0bc6bf0e57329de Mon Sep 17 00:00:00 2001 From: chenjian Date: Tue, 24 Mar 2026 18:42:45 +0800 Subject: [PATCH 1/9] add cloth object --- embodichain/lab/sim/cfg.py | 126 ++++++++ embodichain/lab/sim/common.py | 3 +- embodichain/lab/sim/objects/__init__.py | 1 + embodichain/lab/sim/objects/cloth_object.py | 306 +++++++++++++++++++ embodichain/lab/sim/objects/soft_object.py | 24 +- embodichain/lab/sim/sim_manager.py | 32 ++ embodichain/lab/sim/utility/sim_utils.py | 37 ++- examples/sim/demo/pick_up_cloth.py | 317 ++++++++++++++++++++ 8 files changed, 832 insertions(+), 14 deletions(-) create mode 100644 embodichain/lab/sim/objects/cloth_object.py create mode 100644 examples/sim/demo/pick_up_cloth.py diff --git a/embodichain/lab/sim/cfg.py b/embodichain/lab/sim/cfg.py index 1f4d9ee1..5063e5ce 100644 --- a/embodichain/lab/sim/cfg.py +++ b/embodichain/lab/sim/cfg.py @@ -30,6 +30,7 @@ VoxelConfig, SoftBodyAttr, SoftBodyMaterialModel, + ClothBodyAttr, ) from embodichain.utils import configclass, is_configclass from embodichain.data.constants import EMBODICHAIN_DEFAULT_DATA_ROOT @@ -384,6 +385,116 @@ def attr(self) -> SoftBodyAttr: return attr +@configclass +class ClothPhysicalAttributesCfg: + # material properties + youngs: float = 1e10 + """Young's modulus (higher = stiffer).""" + + poissons: float = 0.3 + """Poisson's ratio.""" + + dynamic_friction: float = 0.5 + """Dynamic friction coefficient.""" + + elasticity_damping: float = 0.0 + """Elasticity damping factor.""" + + thickness: float = 0.001 + """Cloth thickness (m).""" + + bending_stiffness: float = 0.00001 + """Bending stiffness.""" + + bending_damping: float = 0.0 + """Bending damping.""" + + # cloth body properties + enable_kinematic: bool = False + """If True, (partially) kinematic behavior is enabled.""" + + enable_ccd: bool = True + """Enable continuous collision detection (CCD).""" + + enable_self_collision: bool = False + """Enable self-collision handling.""" + + has_gravity: bool = True + """Whether the cloth is affected by gravity.""" + + self_collision_stress_tolerance: float = 0.9 + """Stress tolerance threshold for self-collision constraints.""" + + collision_mesh_simplification: bool = True + """Whether to simplify the collision mesh for self-collision.""" + + vertex_velocity_damping: float = 0.005 + """Per-vertex velocity damping.""" + + mass: float = -1.0 + """Total mass of the cloth. If negative, density is used to compute mass.""" + + density: float = 1.0 + """Material density in kg/m^3.""" + + max_depenetration_velocity: float = 1e6 + """Maximum velocity used to resolve penetrations.""" + + max_velocity: float = 100.0 + """Clamp for linear (or vertex) velocity.""" + + self_collision_filter_distance: float = 0.1 + """Distance threshold for filtering self-collision vertex pairs.""" + + linear_damping: float = 0.05 + """Global linear damping applied to the cloth.""" + + sleep_threshold: float = 0.05 + """Velocity/energy threshold below which the cloth can go to sleep.""" + + settling_threshold: float = 0.1 + """Threshold used to decide convergence/settling state.""" + + settling_damping: float = 10.0 + """Additional damping applied during settling phase.""" + + min_position_iters: int = 4 + """Minimum solver iterations for position correction.""" + + min_velocity_iters: int = 1 + """Minimum solver iterations for velocity updates.""" + + def attr(self) -> ClothBodyAttr: + """Convert to dexsim ClothBodyAttr.""" + attr = ClothBodyAttr() + attr.youngs = self.youngs + attr.poissons = self.poissons + attr.dynamic_friction = self.dynamic_friction + attr.elasticity_damping = self.elasticity_damping + attr.thickness = self.thickness + attr.bending_stiffness = self.bending_stiffness + attr.bending_damping = self.bending_damping + attr.enable_kinematic = self.enable_kinematic + attr.enable_ccd = self.enable_ccd + attr.enable_self_collision = self.enable_self_collision + attr.has_gravity = self.has_gravity + attr.self_collision_stress_tolerance = self.self_collision_stress_tolerance + attr.collision_mesh_simplification = self.collision_mesh_simplification + attr.vertex_velocity_damping = self.vertex_velocity_damping + attr.mass = self.mass + attr.density = self.density + attr.max_depenetration_velocity = self.max_depenetration_velocity + attr.max_velocity = self.max_velocity + attr.self_collision_filter_distance = self.self_collision_filter_distance + attr.linear_damping = self.linear_damping + attr.sleep_threshold = self.sleep_threshold + attr.settling_threshold = self.settling_threshold + attr.settling_damping = self.settling_damping + attr.min_position_iters = self.min_position_iters + attr.min_velocity_iters = self.min_velocity_iters + return attr + + @configclass class JointDrivePropertiesCfg: """Properties to define the drive mechanism of a joint.""" @@ -592,6 +703,21 @@ class SoftObjectCfg(ObjectBaseCfg): """Mesh configuration for the soft body.""" +@configclass +class ClothObjectCfg(ObjectBaseCfg): + """Configuration for a cloth body asset in the simulation. + + This class extends the base asset configuration to include specific properties for cloth bodies, + such as physical attributes and collision group. + """ + + physical_attr: ClothPhysicalAttributesCfg = ClothPhysicalAttributesCfg() + """Physical attributes for the cloth body.""" + + shape: MeshCfg = MeshCfg() + """Mesh configuration for the cloth body.""" + + @configclass class RigidObjectGroupCfg: """Configuration for a rigid object group asset in the simulation. diff --git a/embodichain/lab/sim/common.py b/embodichain/lab/sim/common.py index c6fd274b..0a64a6d9 100644 --- a/embodichain/lab/sim/common.py +++ b/embodichain/lab/sim/common.py @@ -24,6 +24,7 @@ from embodichain.lab.sim.cfg import ObjectBaseCfg from embodichain.utils import logger +import dexsim from copy import deepcopy T = TypeVar("T") @@ -62,7 +63,7 @@ def __init__( self.uid = self.cfg.uid if self.uid is None: logger.log_error("UID must be set in the configuration.") - self._entities = entities + self._entities: tuple[dexsim.models.MeshObject] = entities self.device = device self.reset() diff --git a/embodichain/lab/sim/objects/__init__.py b/embodichain/lab/sim/objects/__init__.py index f70fdf33..7cde4bbf 100644 --- a/embodichain/lab/sim/objects/__init__.py +++ b/embodichain/lab/sim/objects/__init__.py @@ -22,6 +22,7 @@ RigidObjectGroupCfg, ) from .soft_object import SoftObject, SoftBodyData, SoftObjectCfg +from .cloth_object import ClothObject, ClothBodyData, ClothObjectCfg from .articulation import Articulation, ArticulationData, ArticulationCfg from .robot import Robot, RobotCfg from .light import Light, LightCfg diff --git a/embodichain/lab/sim/objects/cloth_object.py b/embodichain/lab/sim/objects/cloth_object.py new file mode 100644 index 00000000..8a429105 --- /dev/null +++ b/embodichain/lab/sim/objects/cloth_object.py @@ -0,0 +1,306 @@ +# ---------------------------------------------------------------------------- +# Copyright (c) 2021-2026 DexForce Technology Co., Ltd. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ---------------------------------------------------------------------------- + +import torch +import dexsim +import numpy as np +from functools import cached_property + +from dataclasses import dataclass +from typing import List, Sequence, Union + +from dexsim.models import MeshObject +from dexsim.engine import PhysicsScene, ClothBody +from dexsim.types import ClothBodyGPUAPIReadWriteType +from embodichain.lab.sim.common import ( + BatchEntity, +) +from embodichain.utils.math import ( + matrix_from_euler, +) +from embodichain.utils import logger +from embodichain.lab.sim.cfg import ( + ClothObjectCfg, +) +from embodichain.utils.math import xyz_quat_to_4x4_matrix + + +@dataclass +class ClothBodyData: + """Data manager for cloth. + + Note: + 1. The pose data managed by dexsim is in the format of (qx, qy, qz, qw, x, y, z), but in EmbodiChain, we use (x, y, z, qw, qx, qy, qz) format. + """ + + def __init__( + self, entities: List[MeshObject], ps: PhysicsScene, device: torch.device + ) -> None: + """Initialize the ClothBodyData. + + Args: + entities (List[MeshObject]): List of MeshObjects representing the cloth bodies. + ps (PhysicsScene): The physics scene. + device (torch.device): The device to use for the cloth body data. + """ + self.entities = entities + # TODO: cloth body data can only be stored in cuda device for now. + self.device = device + # TODO: inorder to retrieve arena position, we need to access the node of each entity. + self._arena_positions = self._get_arena_position() + self.ps = ps + self.num_instances = len(entities) + + self.cloth_bodies: tuple[ClothBody] = [ + self.entities[i].get_physical_body() for i in range(self.num_instances) + ] + self.n_vertices = self.cloth_bodies[0].get_num_vertices() + + self._rest_position_buffer = torch.empty( + (self.num_instances, self.n_vertices, 4), + device=self.device, + dtype=torch.float32, + ) + for i, cloth_body in enumerate(self.cloth_bodies): + self._rest_position_buffer[i] = cloth_body.get_position_inv_mass_buffer() + + self._vertex_position = torch.zeros( + (self.num_instances, self.n_vertices, 3), + device=self.device, + dtype=torch.float32, + ) + + self._vertex_velocity = torch.zeros( + (self.num_instances, self.n_vertices, 3), + device=self.device, + dtype=torch.float32, + ) + + def _get_arena_position(self): + n_env = len(self.entities) + arena_positions = torch.empty( + (n_env, 3), device=self.device, dtype=torch.float32 + ) + for i, entity in enumerate(self.entities): + arena = entity.node.get_parent() + arena_position = arena.get_world_pose()[:3, 3] + arena_positions[i] = torch.as_tensor( + arena_position, device=self.device, dtype=torch.float32 + ) + return arena_positions + + @property + def rest_vertices(self): + """Get the rest position buffer of the cloth bodies.""" + return self._rest_position_buffer[:, :, :3].clone() + + @property + def vertex_position(self): + """Get the current vertex position buffer of the cloth bodies.""" + for i, clothbody in enumerate(self.cloth_bodies): + self._vertex_position[i] = clothbody.get_position_inv_mass_buffer()[:, :3] + return self._vertex_position.clone() + + @property + def vertex_velocity(self): + """Get the current vertex velocity buffer of the cloth bodies.""" + for i, clothbody in enumerate(self.cloth_bodies): + self._vertex_velocity[i] = clothbody.get_velocity_buffer()[:, 3:] + return self._vertex_velocity.clone() + + +class ClothObject(BatchEntity): + """ClothObject represents a batch of cloth body in the simulation.""" + + def __init__( + self, + cfg: ClothObjectCfg, + entities: List[MeshObject] = None, + device: torch.device = torch.device("cpu"), + ) -> None: + self._world: dexsim.World = dexsim.default_world() + self._ps = self._world.get_physics_scene() + self._all_indices = torch.arange(len(entities), dtype=torch.int32).tolist() + + self._data = ClothBodyData(entities=entities, ps=self._ps, device=device) + + self._world.update(0.001) + + super().__init__(cfg=cfg, entities=entities, device=device) + self._set_default_collision_filter() + + def _set_default_collision_filter(self) -> None: + collision_filter_data = torch.zeros( + size=(self.num_instances, 4), dtype=torch.int32 + ) + for i in range(self.num_instances): + collision_filter_data[i, 0] = i + collision_filter_data[i, 1] = 1 + self.set_collision_filter(collision_filter_data) + + def set_collision_filter( + self, filter_data: torch.Tensor, env_ids: Sequence[int] | None = None + ) -> None: + """Set collision filter data for the cloth object. + + Args: + filter_data (torch.Tensor): [N, 4] of int. + First element of each object is arena id. + If 2nd element is 0, the object will collision with all other objects in world. + 3rd and 4th elements are not used currently. + + env_ids (Sequence[int] | None): Environment indices. If None, then all indices are used. + """ + local_env_ids = self._all_indices if env_ids is None else env_ids + + if len(local_env_ids) != len(filter_data): + logger.log_error( + f"Length of env_ids {len(local_env_ids)} does not match pose length {len(filter_data)}." + ) + + filter_data_np = filter_data.cpu().numpy().astype(np.uint32) + for i, env_idx in enumerate(local_env_ids): + self._entities[env_idx].get_physical_body().set_collision_filter_data( + filter_data_np[i] + ) + + @property + def body_data(self) -> ClothBodyData | None: + """Get the cloth body data manager for this cloth object. + + Returns: + ClothBodyData | None: The cloth body data manager. + """ + return self._data + + def get_rest_vertex_position(self) -> torch.Tensor: + """Get the rest vertex position of the cloth bodies. + + Returns: + torch.Tensor: The rest vertex position of the cloth bodies, shape (num_instances, n_vertices, 3). + """ + return self._data.rest_vertices + + def get_current_vertex_position(self) -> torch.Tensor: + """Get the current vertex position of the cloth bodies. + + Returns: + torch.Tensor: The current vertex position of the cloth bodies, shape (num_instances, n_vertices, 3). + """ + return self._data.vertex_position + + def get_current_vertex_velocity(self) -> torch.Tensor: + """Get the current vertex velocity of the cloth bodies. + + Returns: + torch.Tensor: The current vertex velocity of the cloth bodies, shape (num_instances, n_vertices, 3). + """ + return self._data.vertex_velocity + + def set_local_pose( + self, pose: torch.Tensor, env_ids: Sequence[int] | None = None + ) -> None: + """Set local pose of the cloth object. + + Args: + pose (torch.Tensor): The local pose of the cloth object with shape (N, 7) or (N, 4, 4). + env_ids (Sequence[int] | None): Environment indices. If None, then all indices are used. + """ + local_env_ids = self._all_indices if env_ids is None else env_ids + + if len(local_env_ids) != len(pose): + logger.log_error( + f"Length of env_ids {len(local_env_ids)} does not match pose length {len(pose)}." + ) + + if pose.dim() == 2 and pose.shape[1] == 7: + pose4x4 = xyz_quat_to_4x4_matrix(pose) + elif pose.dim() == 3 and pose.shape[1:3] == (4, 4): + pose4x4 = pose + else: + logger.log_error( + f"Invalid pose shape {pose.shape}. Expected (N, 7) or (N, 4, 4)." + ) + + for i, env_idx in enumerate(local_env_ids): + # TODO: cloth body cannot directly set by `set_local_pose` currently. + rest_vertices = self.body_data.rest_vertices[i] + rotation = pose4x4[i][:3, :3] + translation = pose4x4[i][:3, 3] + + # apply transformation to local rest vertices and back + rest_vertices_local = rest_vertices - self._data._arena_positions[i] + transformed_vertices = rest_vertices_local @ rotation.T + translation + transformed_vertices = transformed_vertices + self._data._arena_positions[i] + + cloth_body: ClothBody = self._entities[env_idx].get_physical_body() + position_buffer = cloth_body.get_position_inv_mass_buffer() + velocity_buffer = cloth_body.get_velocity_buffer() + position_buffer[:, :3] = transformed_vertices + velocity_buffer[:, 3:] = 0.0 + + cloth_body.mark_dirty(ClothBodyGPUAPIReadWriteType.ALL) + # TODO: currently cloth body has no wake up interface, use set_wake_counter and pass in a positive value to wake it up + cloth_body.set_wake_counter(0.4) + + def get_local_pose(self, to_matrix=False): + """Get local pose of the cloth object. + + Args: + to_matrix (bool, optional): If True, return the pose as a 4x4 matrix. If False, return as (x, y, z, qw, qx, qy, qz). Defaults to False. + + Returns: + torch.Tensor: The local pose of the cloth object with shape (N, 7) or (N, 4, 4) depending on `to_matrix`. + """ + raise NotImplementedError( + "Getting local pose for ClothObject is not supported." + ) + + def reset(self, env_ids: Sequence[int] | None = None) -> None: + local_env_ids = self._all_indices if env_ids is None else env_ids + num_instances = len(local_env_ids) + + # TODO: set attr for cloth body after loading in physics scene. + + # rest cloth body to init_pos + pos = torch.as_tensor( + self.cfg.init_pos, dtype=torch.float32, device=self.device + ) + rot = ( + torch.as_tensor(self.cfg.init_rot, dtype=torch.float32, device=self.device) + * torch.pi + / 180.0 + ) + pos = pos.unsqueeze(0).repeat(num_instances, 1) + rot = rot.unsqueeze(0).repeat(num_instances, 1) + mat = matrix_from_euler(rot, "XYZ") + pose = ( + torch.eye(4, dtype=torch.float32, device=self.device) + .unsqueeze(0) + .repeat(num_instances, 1, 1) + ) + pose[:, :3, 3] = pos + pose[:, :3, :3] = mat + self.set_local_pose(pose, env_ids=local_env_ids) + + def destroy(self) -> None: + # TODO: not tested yet + env = self._world.get_env() + arenas = env.get_all_arenas() + if len(arenas) == 0: + arenas = [env] + for i, entity in enumerate(self._entities): + arenas[i].remove_actor(entity) diff --git a/embodichain/lab/sim/objects/soft_object.py b/embodichain/lab/sim/objects/soft_object.py index ac9aa192..8a0ea845 100644 --- a/embodichain/lab/sim/objects/soft_object.py +++ b/embodichain/lab/sim/objects/soft_object.py @@ -23,7 +23,7 @@ from typing import List, Sequence, Union from dexsim.models import MeshObject -from dexsim.engine import PhysicsScene +from dexsim.engine import PhysicsScene, SoftBody from dexsim.types import SoftBodyGPUAPIReadWriteType from embodichain.lab.sim.common import ( BatchEntity, @@ -64,7 +64,7 @@ def __init__( self.ps = ps self.num_instances = len(entities) - self.softbodies = [ + self.softbodies: tuple[SoftBody] = [ self.entities[i].get_physical_body() for i in range(self.num_instances) ] self.n_collision_vertices = self.softbodies[0].get_num_vertices() @@ -155,7 +155,7 @@ def sim_vertex_velocity(self): class SoftObject(BatchEntity): - """SoftObject represents a batch of rigid body in the simulation.""" + """SoftObject represents a batch of soft body in the simulation.""" def __init__( self, @@ -163,7 +163,7 @@ def __init__( entities: List[MeshObject] = None, device: torch.device = torch.device("cpu"), ) -> None: - self._world = dexsim.default_world() + self._world: dexsim.World = dexsim.default_world() self._ps = self._world.get_physics_scene() self._all_indices = torch.arange(len(entities), dtype=torch.int32).tolist() @@ -188,7 +188,7 @@ def _set_default_collision_filter(self) -> None: def set_collision_filter( self, filter_data: torch.Tensor, env_ids: Sequence[int] | None = None ) -> None: - """Set collision filter data for the rigid object. + """Set collision filter data for the soft object. Args: filter_data (torch.Tensor): [N, 4] of int. @@ -213,20 +213,20 @@ def set_collision_filter( @property def body_data(self) -> SoftBodyData | None: - """Get the soft body data manager for this rigid object. + """Get the soft body data manager for this soft object. Returns: - SoftBodyData | None: The rigid body data manager. + SoftBodyData | None: The soft body data manager. """ return self._data def set_local_pose( self, pose: torch.Tensor, env_ids: Sequence[int] | None = None ) -> None: - """Set local pose of the rigid object. + """Set local pose of the soft object. Args: - pose (torch.Tensor): The local pose of the rigid object with shape (N, 7) or (N, 4, 4). + pose (torch.Tensor): The local pose of the soft object with shape (N, 7) or (N, 4, 4). env_ids (Sequence[int] | None): Environment indices. If None, then all indices are used. """ local_env_ids = self._all_indices if env_ids is None else env_ids @@ -272,7 +272,7 @@ def set_local_pose( ) # apply vertices to soft body - soft_body = self._entities[env_idx].get_physical_body() + soft_body: SoftBody = self._entities[env_idx].get_physical_body() collision_position_buffer = soft_body.get_position_inv_mass_buffer() sim_position_buffer = soft_body.get_sim_position_inv_mass_buffer() sim_velocity_buffer = soft_body.get_sim_velocity_buffer() @@ -326,13 +326,13 @@ def get_current_sim_vertex_velocities(self) -> torch.Tensor: return self.body_data.sim_vertex_velocity_buffer def get_local_pose(self, to_matrix: bool = False) -> torch.Tensor: - """Get local pose of the rigid object. + """Get local pose of the soft object. Args: to_matrix (bool, optional): If True, return the pose as a 4x4 matrix. If False, return as (x, y, z, qw, qx, qy, qz). Defaults to False. Returns: - torch.Tensor: The local pose of the rigid object with shape (N, 7) or (N, 4, 4) depending on `to_matrix`. + torch.Tensor: The local pose of the soft object with shape (N, 7) or (N, 4, 4) depending on `to_matrix`. """ raise NotImplementedError("Getting local pose for SoftObject is not supported.") diff --git a/embodichain/lab/sim/sim_manager.py b/embodichain/lab/sim/sim_manager.py index ea7c656b..a3bc9140 100644 --- a/embodichain/lab/sim/sim_manager.py +++ b/embodichain/lab/sim/sim_manager.py @@ -54,6 +54,7 @@ RigidObject, RigidObjectGroup, SoftObject, + ClothObject, Articulation, Robot, Light, @@ -73,6 +74,7 @@ LightCfg, RigidObjectCfg, SoftObjectCfg, + ClothObjectCfg, RigidObjectGroupCfg, ArticulationCfg, RobotCfg, @@ -880,6 +882,36 @@ def add_soft_object(self, cfg: SoftObjectCfg) -> SoftObject: self._soft_objects[uid] = soft_obj return soft_obj + def add_cloth_object(self, cfg: ClothObjectCfg) -> ClothObject: + """Add a cloth object to the scene. + + Args: + cfg (ClothObjectCfg): Configuration for the cloth object. + + Returns: + ClothObject: The added cloth object instance handle. + """ + if not self.is_use_gpu_physics: + logger.log_error("Cloth object requires GPU physics to be enabled.") + + from embodichain.lab.sim.utility import ( + load_cloth_object_from_cfg, + ) + + uid = cfg.uid + if uid is None: + logger.log_error("Cloth object uid must be specified.") + + env_list = [self._env] if len(self._arenas) == 0 else self._arenas + obj_list = load_cloth_object_from_cfg( + cfg=cfg, + env_list=env_list, + ) + + cloth_obj = ClothObject(cfg=cfg, entities=obj_list, device=self.device) + self._soft_objects[uid] = cloth_obj + return cloth_obj + def get_rigid_object(self, uid: str) -> RigidObject | None: """Get a rigid object by its unique ID. diff --git a/embodichain/lab/sim/utility/sim_utils.py b/embodichain/lab/sim/utility/sim_utils.py index 494a6266..088709c3 100644 --- a/embodichain/lab/sim/utility/sim_utils.py +++ b/embodichain/lab/sim/utility/sim_utils.py @@ -32,7 +32,12 @@ from dexsim.environment import Env, Arena from dexsim.models import MeshObject -from embodichain.lab.sim.cfg import ArticulationCfg, RigidObjectCfg, SoftObjectCfg +from embodichain.lab.sim.cfg import ( + ArticulationCfg, + RigidObjectCfg, + SoftObjectCfg, + ClothObjectCfg, +) from embodichain.lab.sim.shapes import MeshCfg, CubeCfg, SphereCfg from embodichain.utils import logger from dexsim.kit.meshproc import get_mesh_auto_uv @@ -341,3 +346,33 @@ def load_soft_object_from_cfg( obj.set_name(f"{cfg.uid}_{i}") obj_list.append(obj) return obj_list + + +def load_cloth_object_from_cfg( + cfg: ClothObjectCfg, env_list: List[Arena] +) -> List[MeshObject]: + obj_list = [] + + option = LoadOption() + option.rebuild_normals = cfg.shape.load_option.rebuild_normals + option.rebuild_tangent = cfg.shape.load_option.rebuild_tangent + option.rebuild_3rdnormal = cfg.shape.load_option.rebuild_3rdnormal + option.rebuild_3rdtangent = cfg.shape.load_option.rebuild_3rdtangent + option.smooth = cfg.shape.load_option.smooth + option.share_mesh = False + + for i, env in enumerate(env_list): + obj = env.load_actor( + fpath=cfg.shape.fpath, duplicate=True, attach_scene=True, option=option + ) + obj.add_clothbody(cfg.physical_attr.attr()) + if cfg.shape.compute_uv: + vertices = obj.get_vertices() + triangles = obj.get_triangles() + + o3d_mesh = o3d.t.geometry.TriangleMesh(vertices, triangles) + _, uvs = get_mesh_auto_uv(o3d_mesh, cfg.shape.project_direction) + obj.set_uv_mapping(uvs) + obj.set_name(f"{cfg.uid}_{i}") + obj_list.append(obj) + return obj_list diff --git a/examples/sim/demo/pick_up_cloth.py b/examples/sim/demo/pick_up_cloth.py new file mode 100644 index 00000000..1c07aa16 --- /dev/null +++ b/examples/sim/demo/pick_up_cloth.py @@ -0,0 +1,317 @@ +# ---------------------------------------------------------------------------- +# Copyright (c) 2021-2026 DexForce Technology Co., Ltd. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ---------------------------------------------------------------------------- + +""" +This script demonstrates the creation and simulation of a robot with a soft object, +and performs a pressing task in a simulated environment. +""" + +import argparse +import numpy as np +import time +import open3d as o3d +import torch + +from dexsim.utility.path import get_resources_data_path + +from embodichain.lab.sim import SimulationManager, SimulationManagerCfg +from embodichain.lab.sim.objects import Robot, SoftObject +from embodichain.lab.sim.utility.action_utils import interpolate_with_distance +from embodichain.lab.sim.shapes import MeshCfg +from embodichain.lab.sim.solvers import PytorchSolverCfg +from embodichain.data import get_data_path +from embodichain.utils import logger +from embodichain.lab.sim.cfg import ( + JointDrivePropertiesCfg, + RobotCfg, + RigidObjectCfg, + RigidBodyAttributesCfg, + LightCfg, + ClothObjectCfg, + ClothPhysicalAttributesCfg, + URDFCfg, +) +import os +from embodichain.lab.sim.shapes import MeshCfg, CubeCfg +import tempfile + + +def parse_arguments(): + """ + Parse command-line arguments to configure the simulation. + + Returns: + argparse.Namespace: Parsed arguments including number of environments, device, and rendering options. + """ + parser = argparse.ArgumentParser( + description="Create and simulate a robot in SimulationManager" + ) + parser.add_argument( + "--enable_rt", action="store_true", help="Enable ray tracing rendering" + ) + return parser.parse_args() + + +def initialize_simulation(args): + """ + Initialize the simulation environment based on the provided arguments. + + Args: + args (argparse.Namespace): Parsed command-line arguments. + + Returns: + SimulationManager: Configured simulation manager instance. + """ + config = SimulationManagerCfg( + headless=True, + sim_device="cuda", + enable_rt=args.enable_rt, + physics_dt=1.0 / 100.0, + ) + sim = SimulationManager(config) + + light = sim.add_light( + cfg=LightCfg(uid="main_light", intensity=50.0, init_pos=(0, 0, 2.0)) + ) + + return sim + + +def create_robot(sim: SimulationManager, position=[0.0, 0.0, 0.0]): + """ + Create and configure a robot with an arm and a dexterous hand in the simulation. + + Args: + sim (SimulationManager): The simulation manager instance. + + Returns: + Robot: The configured robot instance added to the simulation. + """ + # Retrieve URDF paths for the robot arm and hand + ur10_urdf_path = get_data_path("UniversalRobots/UR10/UR10.urdf") + gripper_urdf_path = get_data_path("DH_PGC_140_50_M/DH_PGC_140_50_M.urdf") + # Configure the robot with its components and control properties + cfg = RobotCfg( + uid="UR10", + urdf_cfg=URDFCfg( + components=[ + {"component_type": "arm", "urdf_path": ur10_urdf_path}, + {"component_type": "hand", "urdf_path": gripper_urdf_path}, + ] + ), + drive_pros=JointDrivePropertiesCfg( + stiffness={"JOINT[0-9]": 1e4, "FINGER[1-2]": 1e3}, + damping={"JOINT[0-9]": 1e3, "FINGER[1-2]": 1e2}, + max_effort={"JOINT[0-9]": 1e5, "FINGER[1-2]": 1e4}, + drive_type="force", + ), + control_parts={ + "arm": ["JOINT[0-9]"], + "hand": ["FINGER[1-2]"], + }, + solver_cfg={ + "arm": PytorchSolverCfg( + end_link_name="ee_link", + root_link_name="base_link", + tcp=[ + [0.0, 1.0, 0.0, 0.0], + [-1.0, 0.0, 0.0, 0.0], + [0.0, 0.0, 1.0, 0.12], + [0.0, 0.0, 0.0, 1.0], + ], + ) + }, + init_qpos=[0.0, -np.pi / 2, -np.pi / 2, np.pi / 2, -np.pi / 2, 0.0, 0.0, 0.0], + init_pos=position, + ) + return sim.add_robot(cfg=cfg) + + +def create_padding_box(sim: SimulationManager): + padding_box_cfg = RigidObjectCfg( + uid="padding_box", + shape=CubeCfg( + size=[0.008, 0.03, 0.02], + ), + attrs=RigidBodyAttributesCfg( + mass=0.01, + static_friction=0.95, + dynamic_friction=0.9, + restitution=0.01, + min_position_iters=32, + min_velocity_iters=8, + ), + body_type="kinematic", + init_pos=[0.5, 0.0, 0.01], + init_rot=[0.0, 0.0, 0.0], + ) + padding_box = sim.add_rigid_object(cfg=padding_box_cfg) + return padding_box + + +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 + + +def create_cloth(sim: SimulationManager): + cloth_verts, cloth_faces = create_2d_grid_mesh(width=0.3, height=0.3, nx=20, ny=20) + 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) + + 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=1e6, + poissons=0.3, + thickness=0.02, + bending_stiffness=0.01, + bending_damping=0.1, + dynamic_friction=0.99, + min_position_iters=30, + ), + ) + ) + return cloth + + +def get_grasp_traj(sim: SimulationManager, robot: Robot, grasp_xpos: torch.Tensor): + n_envs = sim.num_envs + rest_arm_qpos = robot.get_qpos("arm") + + approach_xpos = grasp_xpos.clone() + approach_xpos[:, 2, 3] += 0.04 + + _, qpos_approach = robot.compute_ik( + pose=approach_xpos, joint_seed=rest_arm_qpos, name="arm" + ) + _, qpos_grasp = robot.compute_ik( + pose=grasp_xpos, joint_seed=qpos_approach, name="arm" + ) + hand_open_qpos = torch.tensor([0.00, 0.00], dtype=torch.float32, device=sim.device) + hand_close_qpos = torch.tensor( + [0.025, 0.025], dtype=torch.float32, device=sim.device + ) + + arm_trajectory = torch.cat( + [ + rest_arm_qpos[:, None, :], + qpos_approach[:, None, :], + qpos_grasp[:, None, :], + qpos_grasp[:, None, :], + qpos_approach[:, None, :], + rest_arm_qpos[:, None, :], + ], + dim=1, + ) + hand_trajectory = torch.cat( + [ + hand_open_qpos[None, None, :].repeat(n_envs, 1, 1), + hand_open_qpos[None, None, :].repeat(n_envs, 1, 1), + hand_open_qpos[None, None, :].repeat(n_envs, 1, 1), + hand_close_qpos[None, None, :].repeat(n_envs, 1, 1), + hand_close_qpos[None, None, :].repeat(n_envs, 1, 1), + hand_close_qpos[None, None, :].repeat(n_envs, 1, 1), + ], + dim=1, + ) + all_trajectory = torch.cat([arm_trajectory, hand_trajectory], dim=-1) + interp_trajectory = interpolate_with_distance( + trajectory=all_trajectory, interp_num=220, device=sim.device + ) + return interp_trajectory + + +def main(): + """ + Main function to demonstrate robot simulation. + + This function initializes the simulation, creates the robot and other objects, + and performs the press softbody task. + """ + args = parse_arguments() + sim = initialize_simulation(args) + + robot = create_robot(sim) + cloth = create_cloth(sim) + padding_box = create_padding_box(sim) + sim.init_gpu_physics() + sim.open_window() + sim.update(step=10) # Let the cloth settle before interaction + + grasp_xpos = torch.tensor( + [ + [ + [-1, 0, 0, 0.5], + [0, 1, 0, 0], + [0, 0, -1, 0.075], + [0, 0, 0, 1], + ], + ], + dtype=torch.float32, + device=sim.device, + ) + grab_traj = get_grasp_traj(sim, robot, grasp_xpos) + input("Press Enter to start grabing cloth...") + + n_waypoint = grab_traj.shape[1] + for i in range(n_waypoint): + robot.set_qpos(grab_traj[:, i, :]) + sim.update(step=4) + time.sleep(1e-2) + input("Press Enter to exit the simulation...") + + +if __name__ == "__main__": + main() From 24c26491392e7b9b28e153e9e0c55f26fe3dd0fc Mon Sep 17 00:00:00 2001 From: chenjian Date: Tue, 24 Mar 2026 18:57:07 +0800 Subject: [PATCH 2/9] update example --- examples/sim/demo/pick_up_cloth.py | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/examples/sim/demo/pick_up_cloth.py b/examples/sim/demo/pick_up_cloth.py index 1c07aa16..a39a1eb9 100644 --- a/examples/sim/demo/pick_up_cloth.py +++ b/examples/sim/demo/pick_up_cloth.py @@ -113,9 +113,9 @@ def create_robot(sim: SimulationManager, position=[0.0, 0.0, 0.0]): ] ), drive_pros=JointDrivePropertiesCfg( - stiffness={"JOINT[0-9]": 1e4, "FINGER[1-2]": 1e3}, - damping={"JOINT[0-9]": 1e3, "FINGER[1-2]": 1e2}, - max_effort={"JOINT[0-9]": 1e5, "FINGER[1-2]": 1e4}, + stiffness={"JOINT[0-9]": 1e4, "FINGER[1-2]": 1e2}, + damping={"JOINT[0-9]": 1e3, "FINGER[1-2]": 1e1}, + max_effort={"JOINT[0-9]": 1e5, "FINGER[1-2]": 1e3}, drive_type="force", ), control_parts={ @@ -144,10 +144,10 @@ def create_padding_box(sim: SimulationManager): padding_box_cfg = RigidObjectCfg( uid="padding_box", shape=CubeCfg( - size=[0.008, 0.03, 0.02], + size=[0.01, 0.04, 0.03], ), attrs=RigidBodyAttributesCfg( - mass=0.01, + mass=1.0, static_friction=0.95, dynamic_friction=0.9, restitution=0.01, @@ -197,7 +197,7 @@ def create_2d_grid_mesh(width: float, height: float, nx: int = 1, ny: int = 1): def create_cloth(sim: SimulationManager): - cloth_verts, cloth_faces = create_2d_grid_mesh(width=0.3, height=0.3, nx=20, ny=20) + 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()), @@ -213,12 +213,12 @@ def create_cloth(sim: SimulationManager): init_rot=[0, 0, 0], physical_attr=ClothPhysicalAttributesCfg( mass=0.01, - youngs=1e6, - poissons=0.3, - thickness=0.02, + youngs=1e10, + poissons=0.4, + thickness=0.04, bending_stiffness=0.01, bending_damping=0.1, - dynamic_friction=0.99, + dynamic_friction=0.95, min_position_iters=30, ), ) From 4ae3394c872411227b8569d0c1173d8535ef6a40 Mon Sep 17 00:00:00 2001 From: chenjian Date: Tue, 24 Mar 2026 19:04:02 +0800 Subject: [PATCH 3/9] add unittest --- tests/sim/objects/test_cloth_object.py | 147 +++++++++++++++++++++++++ 1 file changed, 147 insertions(+) create mode 100644 tests/sim/objects/test_cloth_object.py diff --git a/tests/sim/objects/test_cloth_object.py b/tests/sim/objects/test_cloth_object.py new file mode 100644 index 00000000..d7182b66 --- /dev/null +++ b/tests/sim/objects/test_cloth_object.py @@ -0,0 +1,147 @@ +# ---------------------------------------------------------------------------- +# Copyright (c) 2021-2026 DexForce Technology Co., Ltd. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ---------------------------------------------------------------------------- + +import os +from dexsim.utility.path import get_resources_data_path +from embodichain.lab.sim import SimulationManager, SimulationManagerCfg +from embodichain.lab.sim.cfg import ClothPhysicalAttributesCfg +from embodichain.lab.sim.shapes import MeshCfg +from embodichain.lab.sim.objects import ClothObjectCfg, ClothObject +import open3d as o3d +import pytest +import torch +import tempfile + + +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 + + +class BaseSoftObjectTest: + def setup_simulation(self): + sim_cfg = SimulationManagerCfg( + width=1920, + height=1080, + headless=True, + physics_dt=1.0 / 100.0, # Physics timestep (100 Hz) + sim_device="cuda", + enable_rt=False, # Enable ray tracing for better visuals + num_envs=4, + arena_space=3.0, + ) + + # Create the simulation instance + self.sim = SimulationManager(sim_cfg) + + # Enable manual physics update for precise control + self.n_envs = 4 + + 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 softbody to the scene + self.cloth: ClothObject = self.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, + ), + ) + ) + + def test_run_simulation(self): + self.sim.init_gpu_physics() + for _ in range(100): + self.sim.update(step=1) + self.cloth.reset() + for _ in range(100): + self.sim.update(step=1) + + def test_remove(self): + self.sim.remove_asset(self.cloth.uid) + assert ( + self.cloth.uid not in self.sim._soft_objects + ), "Cow UID still present after removal" + + def test_get_current_vertex_positions(self): + vertex_positions = self.cloth.get_current_vertex_position() + assert vertex_positions.shape == ( + self.sim.num_envs, + self.cloth._data.n_vertices, + 3, + ), "Vertex positions shape mismatch" + + def teardown_method(self): + """Clean up resources after each test method.""" + self.sim.destroy() + + +class TestSoftObjectCUDA(BaseSoftObjectTest): + def setup_method(self): + self.setup_simulation() + + +if __name__ == "__main__": + test = TestSoftObjectCUDA() + test.setup_method() + test.test_run_simulation() + test.test_get_current_vertex_positions() From c90e8250e80f077cbf6bb45b3112ff90ab4404ff Mon Sep 17 00:00:00 2001 From: chenjian Date: Tue, 24 Mar 2026 19:11:52 +0800 Subject: [PATCH 4/9] update --- embodichain/lab/sim/objects/cloth_object.py | 2 +- embodichain/lab/sim/objects/soft_object.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/embodichain/lab/sim/objects/cloth_object.py b/embodichain/lab/sim/objects/cloth_object.py index 8a429105..2dc6a7ad 100644 --- a/embodichain/lab/sim/objects/cloth_object.py +++ b/embodichain/lab/sim/objects/cloth_object.py @@ -64,7 +64,7 @@ def __init__( self.ps = ps self.num_instances = len(entities) - self.cloth_bodies: tuple[ClothBody] = [ + self.cloth_bodies: Sequence[ClothBody] = [ self.entities[i].get_physical_body() for i in range(self.num_instances) ] self.n_vertices = self.cloth_bodies[0].get_num_vertices() diff --git a/embodichain/lab/sim/objects/soft_object.py b/embodichain/lab/sim/objects/soft_object.py index 8a0ea845..28f47d49 100644 --- a/embodichain/lab/sim/objects/soft_object.py +++ b/embodichain/lab/sim/objects/soft_object.py @@ -64,7 +64,7 @@ def __init__( self.ps = ps self.num_instances = len(entities) - self.softbodies: tuple[SoftBody] = [ + self.softbodies: Sequence[SoftBody] = [ self.entities[i].get_physical_body() for i in range(self.num_instances) ] self.n_collision_vertices = self.softbodies[0].get_num_vertices() From c767af10fd1da8e76573cf06ef33ffde2f52fea0 Mon Sep 17 00:00:00 2001 From: chenjian Date: Thu, 26 Mar 2026 17:41:28 +0800 Subject: [PATCH 5/9] remove --- embodichain/lab/sim/common.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/embodichain/lab/sim/common.py b/embodichain/lab/sim/common.py index 0a64a6d9..f1380ed6 100644 --- a/embodichain/lab/sim/common.py +++ b/embodichain/lab/sim/common.py @@ -63,7 +63,7 @@ def __init__( self.uid = self.cfg.uid if self.uid is None: logger.log_error("UID must be set in the configuration.") - self._entities: tuple[dexsim.models.MeshObject] = entities + self._entities = entities self.device = device self.reset() From 59640dcc040822916b49a5ac579a83bb8235757e Mon Sep 17 00:00:00 2001 From: chenjian Date: Thu, 26 Mar 2026 18:18:04 +0800 Subject: [PATCH 6/9] fix arena position in soft | cloth --- embodichain/lab/sim/objects/cloth_object.py | 23 +++++---------- embodichain/lab/sim/objects/soft_object.py | 32 ++++++--------------- examples/sim/demo/pick_up_cloth.py | 6 +++- examples/sim/demo/press_softbody.py | 6 +++- 4 files changed, 25 insertions(+), 42 deletions(-) diff --git a/embodichain/lab/sim/objects/cloth_object.py b/embodichain/lab/sim/objects/cloth_object.py index 2dc6a7ad..c924becc 100644 --- a/embodichain/lab/sim/objects/cloth_object.py +++ b/embodichain/lab/sim/objects/cloth_object.py @@ -60,7 +60,6 @@ def __init__( # TODO: cloth body data can only be stored in cuda device for now. self.device = device # TODO: inorder to retrieve arena position, we need to access the node of each entity. - self._arena_positions = self._get_arena_position() self.ps = ps self.num_instances = len(entities) @@ -89,19 +88,6 @@ def __init__( dtype=torch.float32, ) - def _get_arena_position(self): - n_env = len(self.entities) - arena_positions = torch.empty( - (n_env, 3), device=self.device, dtype=torch.float32 - ) - for i, entity in enumerate(self.entities): - arena = entity.node.get_parent() - arena_position = arena.get_world_pose()[:3, 3] - arena_positions[i] = torch.as_tensor( - arena_position, device=self.device, dtype=torch.float32 - ) - return arena_positions - @property def rest_vertices(self): """Get the rest position buffer of the cloth bodies.""" @@ -219,6 +205,10 @@ def set_local_pose( pose (torch.Tensor): The local pose of the cloth object with shape (N, 7) or (N, 4, 4). env_ids (Sequence[int] | None): Environment indices. If None, then all indices are used. """ + from embodichain.lab.sim import SimulationManager + + sim = SimulationManager.get_instance() + local_env_ids = self._all_indices if env_ids is None else env_ids if len(local_env_ids) != len(pose): @@ -235,6 +225,7 @@ def set_local_pose( f"Invalid pose shape {pose.shape}. Expected (N, 7) or (N, 4, 4)." ) + arena_offsets = sim.arena_offsets for i, env_idx in enumerate(local_env_ids): # TODO: cloth body cannot directly set by `set_local_pose` currently. rest_vertices = self.body_data.rest_vertices[i] @@ -242,9 +233,9 @@ def set_local_pose( translation = pose4x4[i][:3, 3] # apply transformation to local rest vertices and back - rest_vertices_local = rest_vertices - self._data._arena_positions[i] + rest_vertices_local = rest_vertices - arena_offsets[i] transformed_vertices = rest_vertices_local @ rotation.T + translation - transformed_vertices = transformed_vertices + self._data._arena_positions[i] + transformed_vertices = transformed_vertices cloth_body: ClothBody = self._entities[env_idx].get_physical_body() position_buffer = cloth_body.get_position_inv_mass_buffer() diff --git a/embodichain/lab/sim/objects/soft_object.py b/embodichain/lab/sim/objects/soft_object.py index 28f47d49..48e6098e 100644 --- a/embodichain/lab/sim/objects/soft_object.py +++ b/embodichain/lab/sim/objects/soft_object.py @@ -60,7 +60,6 @@ def __init__( # TODO: soft body data can only be stored in cuda device for now. self.device = device # TODO: inorder to retrieve arena position, we need to access the node of each entity. - self._arena_positions = self._get_arena_position() self.ps = ps self.num_instances = len(entities) @@ -105,19 +104,6 @@ def __init__( dtype=torch.float32, ) - def _get_arena_position(self): - n_env = len(self.entities) - arena_positions = torch.empty( - (n_env, 3), device=self.device, dtype=torch.float32 - ) - for i, entity in enumerate(self.entities): - arena = entity.node.get_parent() - arena_position = arena.get_world_pose()[:3, 3] - arena_positions[i] = torch.as_tensor( - arena_position, device=self.device, dtype=torch.float32 - ) - return arena_positions - @property def rest_collision_vertices(self): """Get the rest position buffer of the soft bodies.""" @@ -229,6 +215,9 @@ def set_local_pose( pose (torch.Tensor): The local pose of the soft object with shape (N, 7) or (N, 4, 4). env_ids (Sequence[int] | None): Environment indices. If None, then all indices are used. """ + from embodichain.lab.sim import SimulationManager + + sim = SimulationManager.get_instance() local_env_ids = self._all_indices if env_ids is None else env_ids if len(local_env_ids) != len(pose): @@ -245,6 +234,7 @@ def set_local_pose( f"Invalid pose shape {pose.shape}. Expected (N, 7) or (N, 4, 4)." ) + arena_offsets = sim.arena_offsets for i, env_idx in enumerate(local_env_ids): # TODO: soft body cannot directly set by `set_local_pose` currently. rest_collision_vertices = self.body_data.rest_collision_vertices[i] @@ -253,23 +243,17 @@ def set_local_pose( translation = pose4x4[i][:3, 3] # apply transformation to local rest vertices and back - rest_collision_vertices_local = ( - rest_collision_vertices - self._data._arena_positions[i] - ) + rest_collision_vertices_local = rest_collision_vertices - arena_offsets[i] transformed_collision_vertices = ( rest_collision_vertices_local @ rotation.T + translation ) - transformed_collision_vertices = ( - transformed_collision_vertices + self._data._arena_positions[i] - ) + transformed_collision_vertices = transformed_collision_vertices - rest_sim_vertices_local = rest_sim_vertices - self._data._arena_positions[i] + rest_sim_vertices_local = rest_sim_vertices - arena_offsets[i] transformed_sim_vertices = ( rest_sim_vertices_local @ rotation.T + translation ) - transformed_sim_vertices = ( - transformed_sim_vertices + self._data._arena_positions[i] - ) + transformed_sim_vertices = transformed_sim_vertices # apply vertices to soft body soft_body: SoftBody = self._entities[env_idx].get_physical_body() diff --git a/examples/sim/demo/pick_up_cloth.py b/examples/sim/demo/pick_up_cloth.py index a39a1eb9..ecc57188 100644 --- a/examples/sim/demo/pick_up_cloth.py +++ b/examples/sim/demo/pick_up_cloth.py @@ -62,6 +62,9 @@ def parse_arguments(): parser.add_argument( "--enable_rt", action="store_true", help="Enable ray tracing rendering" ) + parser.add_argument( + "--num_envs", type=int, default=4, help="Number of parallel environments" + ) return parser.parse_args() @@ -80,6 +83,7 @@ def initialize_simulation(args): sim_device="cuda", enable_rt=args.enable_rt, physics_dt=1.0 / 100.0, + num_envs=args.num_envs, ) sim = SimulationManager(config) @@ -232,7 +236,6 @@ def get_grasp_traj(sim: SimulationManager, robot: Robot, grasp_xpos: torch.Tenso approach_xpos = grasp_xpos.clone() approach_xpos[:, 2, 3] += 0.04 - _, qpos_approach = robot.compute_ik( pose=approach_xpos, joint_seed=rest_arm_qpos, name="arm" ) @@ -302,6 +305,7 @@ def main(): dtype=torch.float32, device=sim.device, ) + grasp_xpos = grasp_xpos.repeat(sim.num_envs, 1, 1) grab_traj = get_grasp_traj(sim, robot, grasp_xpos) input("Press Enter to start grabing cloth...") diff --git a/examples/sim/demo/press_softbody.py b/examples/sim/demo/press_softbody.py index 12883116..25e1640d 100644 --- a/examples/sim/demo/press_softbody.py +++ b/examples/sim/demo/press_softbody.py @@ -57,6 +57,9 @@ def parse_arguments(): parser.add_argument( "--enable_rt", action="store_true", help="Enable ray tracing rendering" ) + parser.add_argument( + "--num_envs", type=int, default=9, help="Number of parallel environments" + ) return parser.parse_args() @@ -75,6 +78,7 @@ def initialize_simulation(args): sim_device="cuda", enable_rt=args.enable_rt, physics_dt=1.0 / 100.0, + num_envs=args.num_envs, ) sim = SimulationManager(config) @@ -186,7 +190,7 @@ def press_cow(sim: SimulationManager, robot: Robot): ) interp_trajectory = interp_trajectory[0] for qpos in interp_trajectory: - robot.set_qpos(qpos.unsqueeze(0), joint_ids=arm_ids) + robot.set_qpos(qpos.unsqueeze(0).repeat(sim.num_envs, 1), joint_ids=arm_ids) sim.update(step=5) From d79b6c409f4430f4d048c51ba97e1da3791f4853 Mon Sep 17 00:00:00 2001 From: chenjian Date: Thu, 26 Mar 2026 18:21:24 +0800 Subject: [PATCH 7/9] update --- embodichain/lab/sim/sim_manager.py | 33 +++++++++++++++++++++++++++++- 1 file changed, 32 insertions(+), 1 deletion(-) diff --git a/embodichain/lab/sim/sim_manager.py b/embodichain/lab/sim/sim_manager.py index a3bc9140..6a8bf537 100644 --- a/embodichain/lab/sim/sim_manager.py +++ b/embodichain/lab/sim/sim_manager.py @@ -258,6 +258,7 @@ def __init__( self._rigid_objects: Dict[str, RigidObject] = dict() self._rigid_object_groups: Dict[str, RigidObjectGroup] = dict() self._soft_objects: Dict[str, SoftObject] = dict() + self._cloth_objects: Dict[str, ClothObject] = dict() self._articulations: Dict[str, Articulation] = dict() self._robots: Dict[str, Robot] = dict() @@ -373,6 +374,7 @@ def asset_uids(self) -> List[str]: uid_list.extend(list(self._rigid_objects.keys())) uid_list.extend(list(self._rigid_object_groups.keys())) uid_list.extend(list(self._soft_objects.keys())) + uid_list.extend(list(self._cloth_objects.keys())) uid_list.extend(list(self._articulations.keys())) return uid_list @@ -746,6 +748,8 @@ def get_asset( return self._rigid_object_groups[uid] if uid in self._soft_objects: return self._soft_objects[uid] + if uid in self._cloth_objects: + return self._cloth_objects[uid] if uid in self._articulations: return self._articulations[uid] @@ -909,7 +913,7 @@ def add_cloth_object(self, cfg: ClothObjectCfg) -> ClothObject: ) cloth_obj = ClothObject(cfg=cfg, entities=obj_list, device=self.device) - self._soft_objects[uid] = cloth_obj + self._cloth_objects[uid] = cloth_obj return cloth_obj def get_rigid_object(self, uid: str) -> RigidObject | None: @@ -940,6 +944,20 @@ def get_soft_object(self, uid: str) -> SoftObject | None: return None return self._soft_objects[uid] + def get_cloth_object(self, uid: str) -> ClothObject | None: + """Get a cloth object by its unique ID. + + Args: + uid (str): The unique ID of the cloth object. + + Returns: + ClothObject | None: The cloth object instance if found, otherwise None. + """ + if uid not in self._cloth_objects: + logger.log_warning(f"Cloth object {uid} not found.") + return None + return self._cloth_objects[uid] + def get_rigid_object_uid_list(self) -> List[str]: """Get current rigid body uid list @@ -956,6 +974,14 @@ def get_soft_object_uid_list(self) -> List[str]: """ return list(self._soft_objects.keys()) + def get_cloth_object_uid_list(self) -> List[str]: + """Get current cloth body uid list + + Returns: + List[str]: list of cloth body uid. + """ + return list(self._cloth_objects.keys()) + def add_rigid_object_group(self, cfg: RigidObjectGroupCfg) -> RigidObjectGroup: """Add a rigid object group to the scene. @@ -1476,6 +1502,11 @@ def remove_asset(self, uid: str) -> bool: obj.destroy() return True + if uid in self._cloth_objects: + obj = self._cloth_objects.pop(uid) + obj.destroy() + return True + if uid in self._rigid_object_groups: group = self._rigid_object_groups.pop(uid) group.destroy() From a0fadee6441a5c8eb376fcb04a738daff4e44095 Mon Sep 17 00:00:00 2001 From: chenjian Date: Fri, 27 Mar 2026 10:25:58 +0800 Subject: [PATCH 8/9] update --- embodichain/lab/sim/objects/cloth_object.py | 2 +- embodichain/lab/sim/objects/soft_object.py | 6 +- scripts/tutorials/sim/create_cloth.py | 221 ++++++++++++++++++++ 3 files changed, 226 insertions(+), 3 deletions(-) create mode 100644 scripts/tutorials/sim/create_cloth.py diff --git a/embodichain/lab/sim/objects/cloth_object.py b/embodichain/lab/sim/objects/cloth_object.py index c924becc..28db03cb 100644 --- a/embodichain/lab/sim/objects/cloth_object.py +++ b/embodichain/lab/sim/objects/cloth_object.py @@ -235,7 +235,7 @@ def set_local_pose( # apply transformation to local rest vertices and back rest_vertices_local = rest_vertices - arena_offsets[i] transformed_vertices = rest_vertices_local @ rotation.T + translation - transformed_vertices = transformed_vertices + transformed_vertices = transformed_vertices + arena_offsets[i] cloth_body: ClothBody = self._entities[env_idx].get_physical_body() position_buffer = cloth_body.get_position_inv_mass_buffer() diff --git a/embodichain/lab/sim/objects/soft_object.py b/embodichain/lab/sim/objects/soft_object.py index 48e6098e..a06a30f9 100644 --- a/embodichain/lab/sim/objects/soft_object.py +++ b/embodichain/lab/sim/objects/soft_object.py @@ -247,13 +247,15 @@ def set_local_pose( transformed_collision_vertices = ( rest_collision_vertices_local @ rotation.T + translation ) - transformed_collision_vertices = transformed_collision_vertices + transformed_collision_vertices = ( + transformed_collision_vertices + arena_offsets[i] + ) rest_sim_vertices_local = rest_sim_vertices - arena_offsets[i] transformed_sim_vertices = ( rest_sim_vertices_local @ rotation.T + translation ) - transformed_sim_vertices = transformed_sim_vertices + transformed_sim_vertices = transformed_sim_vertices + arena_offsets[i] # apply vertices to soft body soft_body: SoftBody = self._entities[env_idx].get_physical_body() diff --git a/scripts/tutorials/sim/create_cloth.py b/scripts/tutorials/sim/create_cloth.py new file mode 100644 index 00000000..cddd59c6 --- /dev/null +++ b/scripts/tutorials/sim/create_cloth.py @@ -0,0 +1,221 @@ +# ---------------------------------------------------------------------------- +# Copyright (c) 2021-2026 DexForce Technology Co., Ltd. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ---------------------------------------------------------------------------- + +""" +This script demonstrates how to create a simulation scene using SimulationManager. +It shows the basic setup of simulation context, adding objects, lighting, and sensors. +""" + +import argparse +import os +import tempfile +import time +import torch +import open3d as o3d +from dexsim.utility.path import get_resources_data_path +from embodichain.lab.sim import SimulationManager, SimulationManagerCfg +from embodichain.lab.sim.cfg import ( + RobotCfg, + RigidObjectCfg, + RigidBodyAttributesCfg, + ClothObjectCfg, + ClothPhysicalAttributesCfg, + SoftObjectCfg, + SoftbodyVoxelAttributesCfg, + SoftbodyPhysicalAttributesCfg, +) +from embodichain.lab.sim.shapes import MeshCfg, CubeCfg +from embodichain.lab.sim.objects import RigidObject, ClothObject, SoftObject + + +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 + + +def main(): + """Main function to create and run the simulation scene.""" + + # Parse command line arguments + parser = argparse.ArgumentParser( + description="Create a simulation scene with SimulationManager" + ) + parser.add_argument( + "--headless", + action="store_true", + default=False, + help="Run simulation in headless mode", + ) + parser.add_argument( + "--num_envs", type=int, default=4, help="Number of parallel environments" + ) + parser.add_argument( + "--enable_rt", + action="store_true", + default=False, + help="Enable ray tracing for better visuals", + ) + args = parser.parse_args() + + # 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!") + + 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( + 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!") + + # Open window when the scene has been set up + if not args.headless: + sim.open_window() + + print(f"[INFO]: Running simulation with {args.num_envs} environment(s)") + print("[INFO]: Press Ctrl+C to stop the simulation") + + # Run the simulation + run_simulation(sim, cloth) + + +def run_simulation(sim: SimulationManager, cloth: ClothObject) -> None: + """Run the simulation loop. + + Args: + sim: The SimulationManager instance to run + soft_obj: soft object + """ + + # Initialize GPU physics + sim.init_gpu_physics() + + step_count = 0 + + try: + last_time = time.time() + last_step = 0 + while True: + # Update physics simulation + sim.update(step=1) + step_count += 1 + + # Print FPS every second + if step_count % 100 == 0: + current_time = time.time() + elapsed = current_time - last_time + fps = ( + sim.num_envs * (step_count - last_step) / elapsed + if elapsed > 0 + else 0 + ) + print(f"[INFO]: Simulation step: {step_count}, FPS: {fps:.2f}") + last_time = current_time + last_step = step_count + if step_count % 500 == 0: + cloth.reset() + + except KeyboardInterrupt: + print("\n[INFO]: Stopping simulation...") + finally: + # Clean up resources + sim.destroy() + print("[INFO]: Simulation terminated successfully") + + +if __name__ == "__main__": + main() From 593bb8443aa7d67676c56992879d3d27bb3af540 Mon Sep 17 00:00:00 2001 From: chenjian Date: Fri, 27 Mar 2026 10:40:54 +0800 Subject: [PATCH 9/9] update --- docs/source/tutorial/create_cloth.rst | 100 ++++++++++++++++++++++++++ docs/source/tutorial/index.rst | 1 + scripts/tutorials/sim/create_cloth.py | 8 +-- 3 files changed, 103 insertions(+), 6 deletions(-) create mode 100644 docs/source/tutorial/create_cloth.rst diff --git a/docs/source/tutorial/create_cloth.rst b/docs/source/tutorial/create_cloth.rst new file mode 100644 index 00000000..c43bc091 --- /dev/null +++ b/docs/source/tutorial/create_cloth.rst @@ -0,0 +1,100 @@ +Creating a cloth simulation +=========================== + +.. currentmodule:: embodichain.lab.sim + +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. + +.. dropdown:: Code for create_cloth.py + :icon: code + + .. literalinclude:: ../../../scripts/tutorials/sim/create_cloth.py + :language: python + :linenos: + + +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. + +.. literalinclude:: ../../../scripts/tutorials/sim/create_cloth.py + :language: python + :start-at: def create_2d_grid_mesh + :end-at: return verts, faces + +Configuring the simulation +-------------------------- + +The simulation environment is configured with :class:`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. + +.. literalinclude:: ../../../scripts/tutorials/sim/create_cloth.py + :language: python + :start-at: # Configure the simulation + :end-at: 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 :meth:`SimulationManager.add_cloth_object`. The physical properties of the cloth are controlled through :class:`cfg.ClothObjectCfg` together with :class:`cfg.ClothPhysicalAttributesCfg`: + +- :class:`cfg.MeshCfg` — references the ``.ply`` file written to the system temp directory +- :class:`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 + +.. literalinclude:: ../../../scripts/tutorials/sim/create_cloth.py + :language: python + :start-at: cloth_verts, cloth_faces = create_2d_grid_mesh + :end-at: ) + :end-before: padding_box_cfg + +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 :meth:`SimulationManager.add_rigid_object` using :class:`cfg.RigidObjectCfg` and :class:`cfg.RigidBodyAttributesCfg`: + +- :class:`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 + +.. literalinclude:: ../../../scripts/tutorials/sim/create_cloth.py + :language: python + :start-at: padding_box_cfg = RigidObjectCfg( + :end-at: print("[INFO]: Add soft object complete!") + +The Code Execution +~~~~~~~~~~~~~~~~~~ + +To run the script and see the result, execute the following command: + +.. code-block:: bash + + 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: + +.. code-block:: bash + + python scripts/tutorials/sim/create_cloth.py --headless --num_envs + +Now that we have a basic understanding of how to create a cloth scene, let's move on to more advanced topics. diff --git a/docs/source/tutorial/index.rst b/docs/source/tutorial/index.rst index 05154047..ef6efe79 100644 --- a/docs/source/tutorial/index.rst +++ b/docs/source/tutorial/index.rst @@ -7,6 +7,7 @@ Tutorials create_scene create_softbody + create_cloth rigid_object_group robot add_robot diff --git a/scripts/tutorials/sim/create_cloth.py b/scripts/tutorials/sim/create_cloth.py index cddd59c6..b81f2bf6 100644 --- a/scripts/tutorials/sim/create_cloth.py +++ b/scripts/tutorials/sim/create_cloth.py @@ -28,17 +28,13 @@ from dexsim.utility.path import get_resources_data_path from embodichain.lab.sim import SimulationManager, SimulationManagerCfg from embodichain.lab.sim.cfg import ( - RobotCfg, RigidObjectCfg, RigidBodyAttributesCfg, ClothObjectCfg, ClothPhysicalAttributesCfg, - SoftObjectCfg, - SoftbodyVoxelAttributesCfg, - SoftbodyPhysicalAttributesCfg, ) from embodichain.lab.sim.shapes import MeshCfg, CubeCfg -from embodichain.lab.sim.objects import RigidObject, ClothObject, SoftObject +from embodichain.lab.sim.objects import ClothObject def create_2d_grid_mesh(width: float, height: float, nx: int = 1, ny: int = 1): @@ -89,7 +85,7 @@ def main(): help="Run simulation in headless mode", ) parser.add_argument( - "--num_envs", type=int, default=4, help="Number of parallel environments" + "--num_envs", type=int, default=1, help="Number of parallel environments" ) parser.add_argument( "--enable_rt",