Skip to content

[Bug Report] Deformables visualization issues on IsaacLab 2.3.1 and 3.0.0 #5159

@XiRouz

Description

@XiRouz

Describe the bug

Deformable primitive meshes spawned with IsaacLab CFGs are not visualized correctly

Steps to reproduce

Create a sample scene for IsaacLab using DeformableObject and DeformableObjectCfg from isaaclab_physx.assets

In my code snippet (full code is at the end of this issue) I am dropping one of the capsules on the edge of a cube to see how it would bend.

System Info

Describe the characteristic of your environment:

  • Commit: [tag v3.0.0-beta, v2.3.1]
  • Isaac Sim Version: [5.1.0, 6.0.0]
  • OS: [Ubuntu 22.04]
  • GPU: [RTX 5080]
  • CUDA: [13.0]
  • GPU Driver: [580.95.05]

Additional context

Image Image

Tested a similar script but on IsaacLab v2.3.1, rendering looks the same.

Found a post on forums about a similar issue happening on IsaacSim 4.5.0. Post URL

The render seems to just draw shortest lines from each ends of the cylinder instead of realistically bending, but the ends of capsule seem to be rendered properly, where they should be pointing.

Wanted to try preparing a deformable USD in IsaacSim 6.0.0 and 5.1.0, this process is strange on newer versions rather than on IsaacSim 4.5.0, ended up adding OmniPhysics schemas via script editor snippets from OmniPhysics docs, but they seem to be badly reimported even in the same IsaacSim versions. When I tried to save mesh and material as USD and then add it to a new scene with a ground plane, collision became confusing. Also these prepared deformable USDs are not suitable for importing to IsaacLab, as it can't find PhysXDeformableAPI on the prim.

Also I tried enabling Beta Deformable Schema in Preferences->Rendering to see if the debug visualization would show proper deformable visualization, but simulation and collision meshes are not seen at all.

Checklist

  • I have checked that there is no similar issue in the repo (required)
  • I have checked that the issue is not in running Isaac Sim itself and is related to the repo

Acceptance Criteria

Add the criteria for which this task is considered done. If not known at issue creation time, you can add this once the issue is assigned.

  • Criteria 1
  • Criteria 2
My snippet based on `run_deformable_object.py`:
import argparse
from isaaclab.app import AppLauncher

parser = argparse.ArgumentParser(description="Tutorial on interacting with a deformable object.")
AppLauncher.add_app_launcher_args(parser)
args_cli = parser.parse_args()

app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app

import torch
import warp as wp
from isaaclab.assets import RigidObject, RigidObjectCfg
from isaaclab_physx.assets import DeformableObject, DeformableObjectCfg

import isaaclab.sim as sim_utils
from isaaclab.sim import SimulationContext


def design_scene():
    """Designs the scene."""
    cfg = sim_utils.GroundPlaneCfg()
    cfg.func("/World/defaultGroundPlane", cfg)
    cfg = sim_utils.DomeLightCfg(intensity=2000.0, color=(0.8, 0.8, 0.8))
    cfg.func("/World/Light", cfg)

    # Cube params
    cube_spawn_func_cfg = sim_utils.CuboidCfg(
        size=(0.5, 0.5, 0.7),
        rigid_props=sim_utils.RigidBodyPropertiesCfg(),
        mass_props=sim_utils.MassPropertiesCfg(mass=10.0),
        collision_props=sim_utils.CollisionPropertiesCfg(
            collision_enabled=True, contact_offset=0.01, rest_offset=0.001
        ),
        visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.5, 0.0, 0.0), metallic=0),
        physics_material=sim_utils.RigidBodyMaterialCfg(
            friction_combine_mode="max",
            restitution_combine_mode="min",
            static_friction=10,
            dynamic_friction=1.5,
            restitution=0.01,
        ),
    )

    # Capsule params
    deformable_capsule_phys_mat = sim_utils.DeformableBodyMaterialCfg(
        # density=None,
        dynamic_friction=0.95,
        poissons_ratio=0.4,
        youngs_modulus=1e5,
        # elasticity_damping=0.005,
        # damping_scale=1.0,
    )
    deformable_capsule_spawn_func_cfg = sim_utils.MeshCapsuleCfg(
        radius=0.008,
        height=0.5,
        axis="X",
        mass_props=sim_utils.MassPropertiesCfg(mass=0.1),
        deformable_props=sim_utils.DeformableBodyPropertiesCfg(
            contact_offset=0.01,
            rest_offset=0.001,
            simulation_hexahedral_resolution=30,
        ),
        visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.5, 0.1, 0.0)),
        physics_material=deformable_capsule_phys_mat,
    )

    cube_cfg = RigidObjectCfg(
        prim_path="/World/Cube",
        init_state=RigidObjectCfg.InitialStateCfg(pos=[-1.1, -0.5, 0.35], rot=[1, 0, 0, 0]),
        spawn=cube_spawn_func_cfg,
        debug_vis=True,
    )
    capsule_cfg = DeformableObjectCfg(
        prim_path="/World/Capsule",
        init_state=DeformableObjectCfg.InitialStateCfg(pos=[-1.1, -0.35, 0.75]),
        spawn=deformable_capsule_spawn_func_cfg,
        debug_vis=True,
    )

    cube_dropping_cfg = RigidObjectCfg(
        prim_path="/World/Cube_Dropping",
        init_state=RigidObjectCfg.InitialStateCfg(pos=[-1.1, -1.35, 0.35], rot=[1, 0, 0, 0]),
        spawn=cube_spawn_func_cfg,
        debug_vis=True,
    )
    capsule_dropping_cfg = DeformableObjectCfg(
        prim_path="/World/Capsule_Dropping",
        init_state=DeformableObjectCfg.InitialStateCfg(pos=[-1.4, -1.35, 0.75]),
        spawn=deformable_capsule_spawn_func_cfg,
        debug_vis=True,
    )

    cube = RigidObject(cfg=cube_cfg)
    capsule = DeformableObject(cfg=capsule_cfg)
    cube_dropping = RigidObject(cfg=cube_dropping_cfg)
    capsule_dropping = DeformableObject(cfg=capsule_dropping_cfg)

    # return the scene information
    scene_entities = {
        "cube": cube,
        "capsule": capsule,
        "cube_dropping": cube_dropping,
        "capsule_dropping": capsule_dropping,
    }
    return scene_entities, []


def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, DeformableObject], origins: torch.Tensor):
    """Runs the simulation loop."""
    # Define simulation stepping
    sim_dt = sim.get_physics_dt()
    sim_time = 0.0
    count = 0

    while simulation_app.is_running():
        # perform step
        sim.step()
        # update sim-time
        sim_time += sim_dt
        count += 1
        # update buffers
        # cube_object.update(sim_dt)
        # entities["cube"].update(sim_dt)
        # entities["capsule"].update(sim_dt)
        # entities["cube_dropping"].update(sim_dt)
        # entities["capsule_dropping"].update(sim_dt)

def main():
    """Main function."""
    sim_cfg = sim_utils.SimulationCfg(device=args_cli.device)
    sim = SimulationContext(sim_cfg)
    sim.set_camera_view(eye=(0.0, 0.0, 0.0), target=(0.0, 0.0, 0.0))
    scene_entities, scene_origins = design_scene()
    scene_origins = torch.tensor(scene_origins, device=sim.device)
    sim.reset()
    print("[INFO]: Setup complete...")
    run_simulator(sim, scene_entities, scene_origins)


if __name__ == "__main__":
    main()
    simulation_app.close()

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't working

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions