How to access collision shape

Hello,

we need to access the collision shape that is used during physics simulation.
Firstly, we want to inspect them and compare with the base mesh.
And secondly, we need to compute certain distances between the collision shape and other points.

So far we found that we can access the vertices and face indices of the mesh via UsdGeom.Mesh(mesh_prim).GetPointsAttr().Get() and GetFaceVertexIndicesAttr().
However, we need the final shape after the convex decomposition.
PhysxSchema.PhysxConvexDecompositionCollisionAPI(mesh_prim) seems to hold only “config data”.
And PhysxSchema.PhysxCookedDataAPI(mesh_prim, "convexDecomposition").GetBufferAttr().Get() seems be a binary blob.

Is there an intended way to find the true collision shapes?
Would it be possible to extract the information from the cooked data array? Could you give us any hints how to do this?

Thank you,
Johannes

Hi,
Currently you can get only the convex mesh data through the cooking interface.
You can check the ConvexMeshDataDemo in Window->Simulation->Demos. In the python file there you can see how to extract the cooked data.
Note that this works only when the physics is loaded, meaning when simulation is running or you force load the data.

from omni.physx import get_physx_cooking_interface, get_physx_interface

        # force Physx to cook everything in the scene so it get cached
        get_physx_interface().force_load_physics_from_usd()

        # do stuff like this
        num_convex_hulls = get_physx_cooking_interface().get_nb_convex_mesh_data(str(self._path))
        source_to_world = UsdGeom.Xformable(self._mesh_prim).ComputeLocalToWorldTransform(Usd.TimeCode.Default())
        for index in range(num_convex_hulls):
            convex_hull_data = get_physx_cooking_interface().get_convex_mesh_data(str(self._path), index)
            if convex_hull_data["num_polygons"] and convex_hull_data["num_polygons"] > 0:
                indices = convex_hull_data["indices"]
                vertices = convex_hull_data["vertices"]
                polygons = convex_hull_data["polygons"]
                for poly_index in range(convex_hull_data["num_polygons"]):
                    index_base = polygons[poly_index]["index_base"]
                    previous_index = -1
                    for vertex_index in range(polygons[poly_index]["num_vertices"]):
                        current_index = indices[index_base + vertex_index]
                        if previous_index != -1:
                            color = 0xffffff00
                            point0 = to_world(vertices[previous_index], source_to_world)
                            point1 = to_world(vertices[current_index], source_to_world)
                            self._debugDraw.draw_line(point0 ,color, point1, color)
                        previous_index = current_index
                    point0 = to_world(vertices[previous_index], source_to_world)
                    point1 = to_world(vertices[indices[index_base]], source_to_world)
                    self._debugDraw.draw_line(point0 ,color, 1.0, point1, color, 1.0)


        # then release it
        get_physx_interface().release_physics_objects()

Regards,
Ales

1 Like

Thank you, this is exactly what we were looking for!

This topic was automatically closed 14 days after the last reply. New replies are no longer allowed.