Dynamically Create Attachments at Runtime

Isaac Sim Version

4.2.0
4.1.0
4.0.0
4.5.0
2023.1.1
2023.1.0-hotfix.1
Other (please specify):

Operating System

Ubuntu 22.04
Ubuntu 20.04
Windows 11
Windows 10
Other (please specify):

GPU Information

  • Model: RTX 3090
  • Driver Version: 535.183.01

Topic Description

Detailed Description

I am currently attempting to collect data on deformable object manipulations. However, grasping deformable objects does not seem robust enough yet for this type of data collection (How to grasp deformable object?). Instead of grasping I would like to create an attachment between the robot and deformable body at runtime so random manipulation points can be used. When I attempt to create the attachment though, the points do not seem to populate, and I receive the error message shown below. Is there a way to dynamically create these attachments at runtime or must they be predefined before starting the simulation? Here is the code I am currently using to generate the attachments:

def create_attachment(self):
        world = World.instance()
        current_stage = world.scene.stage
        attachment_path = self.cube.cube_mesh.GetPath().AppendElementString("attachment")
        attachment = PhysxSchema.PhysxPhysicsAttachment.Define(current_stage, attachment_path)
        attachment.GetActor0Rel().SetTargets([self.cube.cube_mesh.GetPath()])
        gripper_mesh_path = self.robot_path + "/psm_tool_gripper2_link/collisions"
        attachment.GetActor1Rel().SetTargets([gripper_mesh_path])
        PhysxSchema.PhysxAutoAttachmentAPI.Apply(attachment.GetPrim())

Error Messages

[Error] [omni.physx.plugin] PhysX error: PxDeformableElementFilter: No support for deformable group element count of 0 when filtering against a rigid body, FILE /builds/omniverse/physics/physx/source/physx/src/NpDeformableElementFilter.cpp, LINE 137

Screenshots or Videos

This is what the attachment looks like after being created by the function above.

Additional Information

Related Issues

I believe this may be related to an earlier post I made for Isaac Sim 4.2 in which the meshes of deformable objects do not appear to update correctly in python standalone applications: Discrepancy Between Deformable and Visual Meshes in Python Standalone Application

I have a follow-up question on this topic. I’m trying to change the attachment position at runtime.

attachment = PhysxSchema.PhysxPhysicsAttachment.Define(stage_utils.get_current_stage(), tumor_attached_path)
attachment.GetActor0Rel().SetTargets([tumor_path])
attachment.GetActor1Rel().SetTargets([attachment_path])
attachment.CreatePoints0Attr().Set([(0.0, 0.0, 0.0)])
attachment.CreatePoints1Attr().Set([(0.0, 0.0, 0.0)])
attachment.CreateAttachmentEnabledAttr().Set(True)

It appears that the attachment positions are not being updated correctly. I also can not find any attachment position when trying to visualize.

Where I encounter this error:
[Error] [omni.physx.plugin] PhysX error: PxDeformableElementFilter: No support for deformable group element count of 0 when filtering against a rigid body, FILE /builds/omniverse/physics/physx/source/physx/src/NpDeformableElementFilter.cpp, LINE 137

What would be the best way to dynamically create attachments?

Hi @lyx010318 and @jordan.thompson6560, sorry this has taken a long time to be answered. I am actually unable to reproduce that error maybe because I cannot reproduce how your deformable is configured. Here is what I have working with a dynamically created attachment using two primitive shapes:

# Copyright (c) 2022-2024, NVIDIA CORPORATION. All rights reserved.
#
# NVIDIA CORPORATION and its licensors retain all intellectual property
# and proprietary rights in and to this software, related documentation
# and any modifications thereto. Any use, reproduction, disclosure or
# distribution of this software and related documentation without an express
# license agreement from NVIDIA CORPORATION is strictly prohibited.
#

from isaacsim import SimulationApp
simulation_app = SimulationApp({"headless": False})

from isaacsim.core.api import World
from isaacsim.core.utils.stage import create_new_stage
from pxr import UsdGeom, Gf, UsdPhysics, PhysxSchema
import math
from omni.physx.scripts import physicsUtils
from isaacsim.core.api.materials.deformable_material import DeformableMaterial
from isaacsim.core.prims import SingleDeformablePrim

def create_cylinder_mesh(radius=0.5, height=1.0, num_segments=16):
    points, indices = [], []
    for i in range(num_segments):
        angle = 2 * math.pi * i / num_segments
        x, y = radius * math.cos(angle), radius * math.sin(angle)
        points.append(Gf.Vec3f(x, y, -height/2))
        points.append(Gf.Vec3f(x, y, height/2))
    bottom_center = len(points)
    points.append(Gf.Vec3f(0, 0, -height/2))
    top_center = len(points)
    points.append(Gf.Vec3f(0, 0, height/2))
    for i in range(num_segments):
        ni = (i + 1) % num_segments
        b0, b1 = i*2, ni*2
        t0, t1 = i*2+1, ni*2+1
        indices += [b0, t0, b1, t0, t1, b1]
    for i in range(num_segments):
        ni = (i + 1) % num_segments
        indices += [bottom_center, i*2, ni*2]
        indices += [top_center, ni*2+1, i*2+1]
    return points, indices

create_new_stage()
stage = simulation_app.context.get_stage()
my_world = World(stage_units_in_meters=1.0, backend="torch", device="cuda")
my_world.scene.add_default_ground_plane()
my_world.reset()

UsdPhysics.Scene.Define(stage, "/physicsScene")
cylinder_radius, cylinder_height = 0.5, 1.0
overlap = cylinder_radius * 1.8

# Rigid cube
cube_path = "/World/Cube1"
cube = UsdGeom.Cube.Define(stage, cube_path)
cube.CreateSizeAttr(cylinder_height)
cube.AddTranslateOp().Set(Gf.Vec3f(0, 0, 0.75))
cube_prim = cube.GetPrim()
UsdPhysics.CollisionAPI.Apply(cube_prim)

# Deformable cylinder
cyl_path = "/World/Cylinder2"
cyl_xform = UsdGeom.Xform.Define(stage, cyl_path)
mesh_path = cyl_xform.GetPrim().GetPath().AppendChild("cylinder").pathString
cyl_mesh = UsdGeom.Mesh.Define(stage, mesh_path)
pts, idxs = create_cylinder_mesh(cylinder_radius, cylinder_height, 16)
physicsUtils.set_or_add_translate_op(cyl_mesh, Gf.Vec3f(overlap, 0, 0.75))
cyl_mesh.GetPointsAttr().Set(pts)
cyl_mesh.GetFaceVertexIndicesAttr().Set(idxs)
cyl_mesh.GetFaceVertexCountsAttr().Set([3] * (len(idxs)//3))

mat = DeformableMaterial(prim_path=cyl_path + "/deformableMaterial", dynamic_friction=0.1, youngs_modulus=5e6, poissons_ratio=0.4, damping_scale=0.1, elasticity_damping=0.1)
deformable = SingleDeformablePrim(name="deformableCylinder2", prim_path=mesh_path, deformable_material=mat, self_collision=True)
my_world.scene.add(deformable)

def create_attachment():
    att_path = mesh_path + "/attachment"
    att = PhysxSchema.PhysxPhysicsAttachment.Define(stage, att_path)
    att.GetActor0Rel().SetTargets([mesh_path])
    att.GetActor1Rel().SetTargets([cube_path])
    PhysxSchema.PhysxAutoAttachmentAPI.Apply(att.GetPrim())
    print("Attachment created")
    return att

my_world.reset()
attachment_created = False
try:
    while simulation_app.is_running():
        if not attachment_created and my_world.current_time >= 0.1:
            create_attachment()
            attachment_created = True
        my_world.step(render=True)
except KeyboardInterrupt:
    pass
finally:
    simulation_app.close()

Hopefully this is helpful. Let me know if you have further questions.

Hi @michalin, thanks for the example. We are trying to repeatedly attach and detach the deformables dynamically. I don’t think the code shown above solves this problem.

Hi @lyx010318 and @jordan.thompson6560, I apologize for the very very late reply. The way to attach and detach deformables dynamically is to create attachments like with the script above and set those as inactive when you want them to detach.

It is not very scalable, but is the only way to do it without having to reset the Physics Simulation Context. Deleting a prim will cause Isaac Sim and Physics layer to go out of sync, so we only allow adding prims dynamically.

Here is a video of dynamically attaching and detaching a deformable:


The script for this is like this:

# Copyright (c) 2022-2024, NVIDIA CORPORATION. All rights reserved.
#
# NVIDIA CORPORATION and its licensors retain all intellectual property
# and proprietary rights in and to this software, related documentation
# and any modifications thereto. Any use, reproduction, disclosure or
# distribution of this software and related documentation without an express
# license agreement from NVIDIA CORPORATION is strictly prohibited.
#

from isaacsim import SimulationApp
simulation_app = SimulationApp({"headless": False})

from isaacsim.core.api import World
from isaacsim.core.utils.stage import create_new_stage
from pxr import UsdGeom, Gf, UsdPhysics, PhysxSchema
import math
from omni.physx.scripts import physicsUtils
from isaacsim.core.api.materials.deformable_material import DeformableMaterial
from isaacsim.core.prims import SingleDeformablePrim

def create_cylinder_mesh(radius=0.5, height=1.0, num_segments=16):
    points, indices = [], []
    for i in range(num_segments):
        angle = 2 * math.pi * i / num_segments
        x, y = radius * math.cos(angle), radius * math.sin(angle)
        points.append(Gf.Vec3f(x, y, -height/2))
        points.append(Gf.Vec3f(x, y, height/2))
    bottom_center = len(points)
    points.append(Gf.Vec3f(0, 0, -height/2))
    top_center = len(points)
    points.append(Gf.Vec3f(0, 0, height/2))
    for i in range(num_segments):
        ni = (i + 1) % num_segments
        b0, b1 = i*2, ni*2
        t0, t1 = i*2+1, ni*2+1
        indices += [b0, t0, b1, t0, t1, b1]
    for i in range(num_segments):
        ni = (i + 1) % num_segments
        indices += [bottom_center, i*2, ni*2]
        indices += [top_center, ni*2+1, i*2+1]
    return points, indices

create_new_stage()
stage = simulation_app.context.get_stage()
my_world = World(stage_units_in_meters=1.0, backend="torch", device="cuda")
my_world.scene.add_default_ground_plane()
my_world.reset()

UsdPhysics.Scene.Define(stage, "/physicsScene")
cylinder_radius, cylinder_height = 0.5, 1.0
overlap = cylinder_radius * 1.8

# Rigid cube
cube_path = "/World/Cube1"
cube = UsdGeom.Cube.Define(stage, cube_path)
cube.CreateSizeAttr(cylinder_height)
cube.AddTranslateOp().Set(Gf.Vec3f(0, 0, 0.75))
cube_rotate_op = cube.AddRotateXYZOp()
cube_rotate_op.Set(Gf.Vec3f(0, 0, 0))
cube_prim = cube.GetPrim()
UsdPhysics.CollisionAPI.Apply(cube_prim)

# Deformable cylinder
cyl_path = "/World/Cylinder2"
cyl_xform = UsdGeom.Xform.Define(stage, cyl_path)
mesh_path = cyl_xform.GetPrim().GetPath().AppendChild("cylinder").pathString
cyl_mesh = UsdGeom.Mesh.Define(stage, mesh_path)
pts, idxs = create_cylinder_mesh(cylinder_radius, cylinder_height, 16)
physicsUtils.set_or_add_translate_op(cyl_mesh, Gf.Vec3f(overlap, 0, 0.75))
cyl_mesh.GetPointsAttr().Set(pts)
cyl_mesh.GetFaceVertexIndicesAttr().Set(idxs)
cyl_mesh.GetFaceVertexCountsAttr().Set([3] * (len(idxs)//3))

mat = DeformableMaterial(prim_path=cyl_path + "/deformableMaterial", dynamic_friction=0.1, youngs_modulus=5e6, poissons_ratio=0.4, damping_scale=0.1, elasticity_damping=0.1)
deformable = SingleDeformablePrim(name="deformableCylinder2", prim_path=mesh_path, deformable_material=mat, self_collision=True)
my_world.scene.add(deformable)

attachment_counter = 0

def create_attachment():
    global attachment_counter
    attachment_counter += 1
    att_path = mesh_path + f"/attachment_{attachment_counter}"
    att = PhysxSchema.PhysxPhysicsAttachment.Define(stage, att_path)
    att.GetActor0Rel().SetTargets([mesh_path])
    att.GetActor1Rel().SetTargets([cube_path])
    PhysxSchema.PhysxAutoAttachmentAPI.Apply(att.GetPrim())
    print(f"Attachment {attachment_counter} created at time {my_world.current_time:.2f}s")
    return att

my_world.reset()
attachments = []  # List of (attachment, creation_time) tuples
last_creation_time = -5.0  # Allow first attachment at 0.1s

try:
    while simulation_app.is_running():
        current_time = my_world.current_time
        
        # Rotate cube slowly over time (10 degrees per second around Z-axis)
        rotation_speed = 10.0  # degrees per second
        rotation_angle = current_time * rotation_speed
        cube_rotate_op.Set(Gf.Vec3f(0, 0, rotation_angle))
        
        # Create new attachment every 5 seconds (starting at 0.1s)
        if current_time >= 0.1 and current_time - last_creation_time >= 5.0:
            att = create_attachment()
            attachments.append((att, current_time))
            last_creation_time = current_time
        
        # Deactivate attachments after 2 seconds
        for att, creation_time in attachments:
            if current_time - creation_time >= 2.0 and att.GetPrim().IsActive():
                att.GetPrim().SetActive(False)
                print(f"Attachment deactivated at time {current_time:.2f}s (created at {creation_time:.2f}s)")
        
        my_world.step(render=True)
except KeyboardInterrupt:
    pass
finally:
    simulation_app.close()

Hello!

We noticed that this topic hasn’t received any recent responses, so we are closing it for now to help keep the forum organized.

If you’re still experiencing this issue or have additional questions, please feel free to create a new topic with updated details. When doing so, we recommend mentioning or linking to this original topic in your new post—this helps provide context and makes it easier for others to assist you.

Thank you for being part of the NVIDIA Isaac Sim community.

Best regards,
The NVIDIA Isaac Sim Forum Team