How to automatically make the assets inside Isaac Sim Nucleus SimReady to fix the collision problem?

I have Enterprise Omniverse and Isaac Sim 2023.1.1 and I am using a couple of objects that when I spawn, they collide with each other plus I cannot change their texture since they don’t have the field.

My assumption is that these objects, despite being in Nucleus are not SimReady. Since when I use the certain SimReady assets from NVIDIA I don’t have collision problem and I am able to change their texture/color.

Could you please suggest how to make the assets in Nucleus SimReady hopefully automatically? I am not a 3D artist or computer graphics experts and it’s beyond my level of expertise.

The assets I chose are from

omniverse://localhost/NVIDIA/Assets/DigitalTwin/Assets/Warehouse/

Below, is an example of unpleasant and unrealistic collision (two boxes don’t collide like that)

image

Thank you.

Hi there,

the assets you are using are probably not sim-ready (they have no collisions or physics simulation capabilities yet). You can for example quickly test them by drag and dropping them to stage and pressing play, if the assets are not falling they have no rigid-body simulation enabled. If the assets are falling, they are however not colliding with others they probably have rigid body enabled but no colliders. And if they have collisions, but are not moving, then they probably have colliders but the ribid body simulation disabled.

here is how you can add collision and rigid body simulation capabilities to (non-sim-ready) assets throught he UI:

here is also a short video tutorial on the matter:

here is an example on accessing simready assets through API:

here are code snippets on how you can add this from python using the USD API:

# Iterate descendant prims (including root) and add colliders to mesh or primitive types
def add_colliders(root_prim):
    # Iterate descendant prims and add colliders to mesh or primitive types
    for desc_prim in Usd.PrimRange(root_prim):
        if desc_prim.IsA(UsdGeom.Mesh) or desc_prim.IsA(UsdGeom.Gprim):
            # Add collision properties to the mesh (make sure collision is enabled)
            if not desc_prim.HasAPI(UsdPhysics.CollisionAPI):
                collision_api = UsdPhysics.CollisionAPI.Apply(desc_prim)
            else:
                collision_api = UsdPhysics.CollisionAPI(desc_prim)
            collision_api.CreateCollisionEnabledAttr(True)

            # Add PhysX collision properties to the mesh (e.g. bouncyness)
            if not desc_prim.HasAPI(PhysxSchema.PhysxCollisionAPI):
                physx_collision_api = PhysxSchema.PhysxCollisionAPI.Apply(desc_prim)
            else:
                physx_collision_api = PhysxSchema.PhysxCollisionAPI(desc_prim)
            physx_collision_api.CreateRestOffsetAttr(0.0)

        # Add mesh specific collision properties only to mesh types
        if desc_prim.IsA(UsdGeom.Mesh):
            # Add mesh collision properties to the mesh (e.g. collider aproximation type)
            if not desc_prim.HasAPI(UsdPhysics.MeshCollisionAPI):
                mesh_collision_api = UsdPhysics.MeshCollisionAPI.Apply(desc_prim)
            else:
                mesh_collision_api = UsdPhysics.MeshCollisionAPI(desc_prim)
            mesh_collision_api.CreateApproximationAttr().Set("convexHull")

# Check if prim (or its descendants) has colliders
def has_colliders(root_prim):
    for desc_prim in Usd.PrimRange(root_prim):
        if desc_prim.HasAPI(UsdPhysics.CollisionAPI):
            return True
    return False

# Add dynamics properties to the prim (if mesh or primitive) (rigid body to root + colliders to the meshes)
def add_colliders_and_rigid_body_dynamics(prim):
    # Add colliders to mesh or primitive types of the descendants of the prim (including root)
    add_colliders(prim)

    # Add rigid body dynamics properties to the root only if it has colliders
    if has_colliders(prim):
        if not prim.HasAPI(UsdPhysics.RigidBodyAPI):
            rigid_body_api = UsdPhysics.RigidBodyAPI.Apply(prim)
        else:
            rigid_body_api = UsdPhysics.RigidBodyAPI(prim)
        rigid_body_api.CreateRigidBodyEnabledAttr(True)
    else:
        print(f"Prim '{prim.GetPath()}' has no colliders. Skipping rigid body dynamics properties.")

here is how you can do it with the replicator API:

NOTE: even if an object is simready, if you spawn/teleport them so that they collide, they will overlap eachother, only after starting the simulateion (for at least one step) the collisions will be solved by pushing the objects out of each other. This will also apply force on the objects, so if the simulation continues to run the objects will continue to move until the force is dampened out. In this case you can pause/stop the simulation and set the velocity of the objects to 0.

You can also compute collisions by checking for overlap areas, if the two objects overlap you will get the penetration depth and can apply that distance to move the objects. This can be done without simulation, see here an example using this (search for get_physx_scene_query_interface().overlap_box):

2 Likes

@ahaidu
Do GeometryPrim and RigidPrim do similar things to your code above (Isaac Sim 4.5)? What is the correct way of instantiating the colliders and physics for prims. I would like help in instantiating in python code the same attributes that come with right clicking on a prim->Add->Physics->Rigid Body with Colliders Preset.

I am importing prims downloaded from SimReadyAssets.

prim = isaacsim.core.utils.stage.add_reference_to_stage(usd_file_path, prim_path)
object_view = GeometryPrim(
    prim_paths_expr=prim_path,
    positions=t,      
    orientations=quatWXYZ,       
    scales=torch.tensor([1.0, 1.0, 1.0], device=self.device).unsqueeze(0),
    collisions = [True],
)
object_view.set_collision_approximations("convexHull")

but I get the following error:

[Error] [omni.physx.plugin] PhysicsUSD: Prim at path /World/object is using unknown value for physics:approximation attribute.

I get the same sort of errors when I used RigidPrim from isaacsim.core.prims

object_view = RigidPrim(
    prim_paths_expr=prim_path,
    positions=t,      
    orientations=quatWXYZ,       
    scales=torch.tensor([1.0, 1.0, 1.0], device=self.device).unsqueeze(0),
)
2025-03-04 20:53:47 [123,890ms] [Warning] [omni.physx.plugin] PhysicsUSD: Parse collision - triangle mesh collision (approximation None/MeshSimplification) cannot be a part of a dynamic body, falling back to convexHull approximation: /World/object27/SM_CardBoxD_01/SM_CardBoxD_01. For dynamic collision please use approximations: convex hull, convex decomposition, box, sphere or SDF approximation.

Finally, if you could help with setting linear damping. I am trying to execute your NOTE such that when the sim is played, the objects un collide. I would like to set linear damping so that when they do this process they do not move too quickly.

Thank you!

@chsu8 Any update on this? I’m also trying to spawn a usd with collision/physics and find existing documentation confusing/lacking. It’s hard to say what is the intended way

Currently I am doing it like this:

import isaacsim.core.utils.prims as prims_utils

        prim = prims_utils.create_prim(
            prim_path=prim_path,
            position=t,
            orientation=quatWXYZ,
            scale=Gf.Vec3d(1.0, 1.0, 1.0),  # Use Gf.Vec3d for double precision
            usd_path=usd_file_path,
            semantic_label=label,
        )

        # wrap the prim in a GeometryPrim object with colliders
        geo_prim = SingleGeometryPrim(
            prim_path=prim_path,
            name=prim_path,
            collision=True)
        geo_prim.set_collision_approximation("convexHull")

        # add to isaac sim registry if not already there
        if prim_path not in self.prim_paths:
            self.ros_world.scene.add(geo_prim)