Interacting with a deformable object#

While deformable objects sometimes refer to a broader class of objects, such as cloths, fluids and soft bodies, in PhysX, deformable objects syntactically correspond to soft bodies. Unlike rigid objects, soft bodies can deform under external forces and collisions.

Soft bodies are simulated using Finite Element Method (FEM) in PhysX. The soft body comprises of two tetrahedral meshes – a simulation mesh and a collision mesh. The simulation mesh is used to simulate the deformations of the soft body, while the collision mesh is used to detect collisions with other objects in the scene. For more details, please check the PhysX documentation.

This tutorial shows how to interact with a deformable object in the simulation. We will spawn a set of soft cubes and see how to set their nodal positions and velocities, along with apply kinematic commands to the mesh nodes to move the soft body.

The Code#

The tutorial corresponds to the run_deformable_object.py script in the source/standalone/tutorials/01_assets directory.

Code for run_deformable_object.py
  1# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
  2# All rights reserved.
  3#
  4# SPDX-License-Identifier: BSD-3-Clause
  5
  6"""
  7This script demonstrates how to work with the deformable object and interact with it.
  8
  9.. code-block:: bash
 10
 11    # Usage
 12    ./isaaclab.sh -p source/standalone/tutorials/01_assets/run_deformable_object.py
 13
 14"""
 15
 16"""Launch Isaac Sim Simulator first."""
 17
 18
 19import argparse
 20
 21from omni.isaac.lab.app import AppLauncher
 22
 23# add argparse arguments
 24parser = argparse.ArgumentParser(description="Tutorial on interacting with a deformable object.")
 25# append AppLauncher cli args
 26AppLauncher.add_app_launcher_args(parser)
 27# parse the arguments
 28args_cli = parser.parse_args()
 29
 30# launch omniverse app
 31app_launcher = AppLauncher(args_cli)
 32simulation_app = app_launcher.app
 33
 34"""Rest everything follows."""
 35
 36import torch
 37
 38import omni.isaac.core.utils.prims as prim_utils
 39
 40import omni.isaac.lab.sim as sim_utils
 41import omni.isaac.lab.utils.math as math_utils
 42from omni.isaac.lab.assets import DeformableObject, DeformableObjectCfg
 43from omni.isaac.lab.sim import SimulationContext
 44
 45
 46def design_scene():
 47    """Designs the scene."""
 48    # Ground-plane
 49    cfg = sim_utils.GroundPlaneCfg()
 50    cfg.func("/World/defaultGroundPlane", cfg)
 51    # Lights
 52    cfg = sim_utils.DomeLightCfg(intensity=2000.0, color=(0.8, 0.8, 0.8))
 53    cfg.func("/World/Light", cfg)
 54
 55    # Create separate groups called "Origin1", "Origin2", "Origin3"
 56    # Each group will have a robot in it
 57    origins = [[0.25, 0.25, 0.0], [-0.25, 0.25, 0.0], [0.25, -0.25, 0.0], [-0.25, -0.25, 0.0]]
 58    for i, origin in enumerate(origins):
 59        prim_utils.create_prim(f"/World/Origin{i}", "Xform", translation=origin)
 60
 61    # Deformable Object
 62    cfg = DeformableObjectCfg(
 63        prim_path="/World/Origin.*/Cube",
 64        spawn=sim_utils.MeshCuboidCfg(
 65            size=(0.2, 0.2, 0.2),
 66            deformable_props=sim_utils.DeformableBodyPropertiesCfg(rest_offset=0.0, contact_offset=0.001),
 67            visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.5, 0.1, 0.0)),
 68            physics_material=sim_utils.DeformableBodyMaterialCfg(poissons_ratio=0.4, youngs_modulus=1e5),
 69        ),
 70        init_state=DeformableObjectCfg.InitialStateCfg(pos=(0.0, 0.0, 1.0)),
 71        debug_vis=True,
 72    )
 73    cube_object = DeformableObject(cfg=cfg)
 74
 75    # return the scene information
 76    scene_entities = {"cube_object": cube_object}
 77    return scene_entities, origins
 78
 79
 80def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, DeformableObject], origins: torch.Tensor):
 81    """Runs the simulation loop."""
 82    # Extract scene entities
 83    # note: we only do this here for readability. In general, it is better to access the entities directly from
 84    #   the dictionary. This dictionary is replaced by the InteractiveScene class in the next tutorial.
 85    cube_object = entities["cube_object"]
 86    # Define simulation stepping
 87    sim_dt = sim.get_physics_dt()
 88    sim_time = 0.0
 89    count = 0
 90
 91    # Nodal kinematic targets of the deformable bodies
 92    nodal_kinematic_target = cube_object.data.nodal_kinematic_target.clone()
 93
 94    # Simulate physics
 95    while simulation_app.is_running():
 96        # reset
 97        if count % 250 == 0:
 98            # reset counters
 99            sim_time = 0.0
100            count = 0
101
102            # reset the nodal state of the object
103            nodal_state = cube_object.data.default_nodal_state_w.clone()
104            # apply random pose to the object
105            pos_w = torch.rand(cube_object.num_instances, 3, device=sim.device) * 0.1 + origins
106            quat_w = math_utils.random_orientation(cube_object.num_instances, device=sim.device)
107            nodal_state[..., :3] = cube_object.transform_nodal_pos(nodal_state[..., :3], pos_w, quat_w)
108
109            # write nodal state to simulation
110            cube_object.write_nodal_state_to_sim(nodal_state)
111
112            # write kinematic target to nodal state and free all vertices
113            nodal_kinematic_target[..., :3] = nodal_state[..., :3]
114            nodal_kinematic_target[..., 3] = 1.0
115            cube_object.write_nodal_kinematic_target_to_sim(nodal_kinematic_target)
116
117            # reset buffers
118            cube_object.reset()
119
120            print("----------------------------------------")
121            print("[INFO]: Resetting object state...")
122
123        # update the kinematic target for cubes at index 0 and 3
124        # we slightly move the cube in the z-direction by picking the vertex at index 0
125        nodal_kinematic_target[[0, 3], 0, 2] += 0.001
126        # set vertex at index 0 to be kinematically constrained
127        # 0: constrained, 1: free
128        nodal_kinematic_target[[0, 3], 0, 3] = 0.0
129        # write kinematic target to simulation
130        cube_object.write_nodal_kinematic_target_to_sim(nodal_kinematic_target)
131
132        # write internal data to simulation
133        cube_object.write_data_to_sim()
134        # perform step
135        sim.step()
136        # update sim-time
137        sim_time += sim_dt
138        count += 1
139        # update buffers
140        cube_object.update(sim_dt)
141        # print the root position
142        if count % 50 == 0:
143            print(f"Root position (in world): {cube_object.data.root_pos_w[:, :3]}")
144
145
146def main():
147    """Main function."""
148    # Load kit helper
149    sim_cfg = sim_utils.SimulationCfg()
150    sim = SimulationContext(sim_cfg)
151    # Set main camera
152    sim.set_camera_view(eye=[3.0, 0.0, 1.0], target=[0.0, 0.0, 0.5])
153    # Design scene
154    scene_entities, scene_origins = design_scene()
155    scene_origins = torch.tensor(scene_origins, device=sim.device)
156    # Play the simulator
157    sim.reset()
158    # Now we are ready!
159    print("[INFO]: Setup complete...")
160    # Run the simulator
161    run_simulator(sim, scene_entities, scene_origins)
162
163
164if __name__ == "__main__":
165    # run the main function
166    main()
167    # close sim app
168    simulation_app.close()

The Code Explained#

Designing the scene#

Similar to the Interacting with a rigid object tutorial, we populate the scene with a ground plane and a light source. In addition, we add a deformable object to the scene using the assets.DeformableObject class. This class is responsible for spawning the prims at the input path and initializes their corresponding deformable body physics handles.

In this tutorial, we create a cubical soft object using the spawn configuration similar to the deformable cube in the Spawn Objects tutorial. The only difference is that now we wrap the spawning configuration into the assets.DeformableObjectCfg class. This class contains information about the asset’s spawning strategy and default initial state. When this class is passed to the assets.DeformableObject class, it spawns the object and initializes the corresponding physics handles when the simulation is played.

Note

The deformable object is only supported in GPU simulation and requires a mesh object to be spawned with the deformable body physics properties on it.

As seen in the rigid body tutorial, we can spawn the deformable object into the scene in a similar fashion by creating an instance of the assets.DeformableObject class by passing the configuration object to its constructor.

    # Create separate groups called "Origin1", "Origin2", "Origin3"
    # Each group will have a robot in it
    origins = [[0.25, 0.25, 0.0], [-0.25, 0.25, 0.0], [0.25, -0.25, 0.0], [-0.25, -0.25, 0.0]]
    for i, origin in enumerate(origins):
        prim_utils.create_prim(f"/World/Origin{i}", "Xform", translation=origin)

    # Deformable Object
    cfg = DeformableObjectCfg(
        prim_path="/World/Origin.*/Cube",
        spawn=sim_utils.MeshCuboidCfg(
            size=(0.2, 0.2, 0.2),
            deformable_props=sim_utils.DeformableBodyPropertiesCfg(rest_offset=0.0, contact_offset=0.001),
            visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.5, 0.1, 0.0)),
            physics_material=sim_utils.DeformableBodyMaterialCfg(poissons_ratio=0.4, youngs_modulus=1e5),
        ),
        init_state=DeformableObjectCfg.InitialStateCfg(pos=(0.0, 0.0, 1.0)),
        debug_vis=True,
    )
    cube_object = DeformableObject(cfg=cfg)

Running the simulation loop#

Continuing from the rigid body tutorial, we reset the simulation at regular intervals, apply kinematic commands to the deformable body, step the simulation, and update the deformable object’s internal buffers.

Resetting the simulation state#

Unlike rigid bodies and articulations, deformable objects have a different state representation. The state of a deformable object is defined by the nodal positions and velocities of the mesh. The nodal positions and velocities are defined in the simulation world frame and are stored in the assets.DeformableObject.data attribute.

We use the assets.DeformableObject.data.default_nodal_state_w attribute to get the default nodal state of the spawned object prims. This default state can be configured from the assets.DeformableObjectCfg.init_state attribute, which we left as identity in this tutorial.

Attention

The initial state in the configuration assets.DeformableObjectCfg specifies the pose of the deformable object at the time of spawning. Based on this initial state, the default nodal state is obtained when the simulation is played for the first time.

We apply transformations to the nodal positions to randomize the initial state of the deformable object.

            # reset the nodal state of the object
            nodal_state = cube_object.data.default_nodal_state_w.clone()
            # apply random pose to the object
            pos_w = torch.rand(cube_object.num_instances, 3, device=sim.device) * 0.1 + origins
            quat_w = math_utils.random_orientation(cube_object.num_instances, device=sim.device)
            nodal_state[..., :3] = cube_object.transform_nodal_pos(nodal_state[..., :3], pos_w, quat_w)

To reset the deformable object, we first set the nodal state by calling the assets.DeformableObject.write_nodal_state_to_sim() method. This method writes the nodal state of the deformable object prim into the simulation buffer. Additionally, we free all the kinematic targets set for the nodes in the previous simulation step by calling the assets.DeformableObject.write_nodal_kinematic_target_to_sim() method. We explain the kinematic targets in the next section.

Finally, we call the assets.DeformableObject.reset() method to reset any internal buffers and caches.

            # write nodal state to simulation
            cube_object.write_nodal_state_to_sim(nodal_state)

            # write kinematic target to nodal state and free all vertices
            nodal_kinematic_target[..., :3] = nodal_state[..., :3]
            nodal_kinematic_target[..., 3] = 1.0
            cube_object.write_nodal_kinematic_target_to_sim(nodal_kinematic_target)

            # reset buffers
            cube_object.reset()

Stepping the simulation#

Deformable bodies support user-driven kinematic control where a user can specify position targets for some of the mesh nodes while the rest of the nodes are simulated using the FEM solver. This partial kinematic control is useful for applications where the user wants to interact with the deformable object in a controlled manner.

In this tutorial, we apply kinematic commands to two out of the four cubes in the scene. We set the position targets for the node at index 0 (bottom-left corner) to move the cube along the z-axis.

At every step, we increment the kinematic position target for the node by a small value. Additionally, we set the flag to indicate that the target is a kinematic target for that node in the simulation buffer. These are set into the simulation buffer by calling the assets.DeformableObject.write_nodal_kinematic_target_to_sim() method.

        # update the kinematic target for cubes at index 0 and 3
        # we slightly move the cube in the z-direction by picking the vertex at index 0
        nodal_kinematic_target[[0, 3], 0, 2] += 0.001
        # set vertex at index 0 to be kinematically constrained
        # 0: constrained, 1: free
        nodal_kinematic_target[[0, 3], 0, 3] = 0.0
        # write kinematic target to simulation
        cube_object.write_nodal_kinematic_target_to_sim(nodal_kinematic_target)

Similar to the rigid object and articulation, we perform the assets.DeformableObject.write_data_to_sim() method before stepping the simulation. For deformable objects, this method does not apply any external forces to the object. However, we keep this method for completeness and future extensions.

        # write internal data to simulation
        cube_object.write_data_to_sim()

Updating the state#

After stepping the simulation, we update the internal buffers of the deformable object prims to reflect their new state inside the assets.DeformableObject.data attribute. This is done using the assets.DeformableObject.update() method.

At a fixed interval, we print the root position of the deformable object to the terminal. As mentioned earlier, there is no concept of a root state for deformable objects. However, we compute the root position as the average position of all the nodes in the mesh.

        # update buffers
        cube_object.update(sim_dt)
        # print the root position
        if count % 50 == 0:
            print(f"Root position (in world): {cube_object.data.root_pos_w[:, :3]}")

The Code Execution#

Now that we have gone through the code, let’s run the script and see the result:

./isaaclab.sh -p source/standalone/tutorials/01_assets/run_deformable_object.py

This should open a stage with a ground plane, lights, and several green cubes. Two of the four cubes must be dropping from a height and settling on to the ground. Meanwhile the other two cubes must be moving along the z-axis. You should see a marker showing the kinematic target position for the nodes at the bottom-left corner of the cubes. To stop the simulation, you can either close the window, or press Ctrl+C in the terminal

result of run_deformable_object.py

This tutorial showed how to spawn deformable objects and wrap them in a DeformableObject class to initialize their physics handles which allows setting and obtaining their state. We also saw how to apply kinematic commands to the deformable object to move the mesh nodes in a controlled manner. In the next tutorial, we will see how to create a scene using the InteractiveScene class.