mirror of
https://github.com/bulletphysics/bullet3.git
synced 2026-06-14 03:09:18 +00:00
pybullet: enable getMeshData for multibody/rigid body (and filter on collisionShapeIndex for compound shapes)
This commit is contained in:
@@ -1390,6 +1390,18 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3GetMeshDataCommandInit(b3PhysicsClie
|
||||
return 0;
|
||||
}
|
||||
|
||||
B3_SHARED_API void b3GetMeshDataSetCollisionShapeIndex(b3SharedMemoryCommandHandle commandHandle, int shapeIndex)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_REQUEST_MESH_DATA);
|
||||
if (command->m_type == CMD_REQUEST_MESH_DATA)
|
||||
{
|
||||
command->m_updateFlags = B3_MESH_DATA_COLLISIONSHAPEINDEX;
|
||||
command->m_requestMeshDataArgs.m_collisionShapeIndex = shapeIndex;
|
||||
}
|
||||
}
|
||||
|
||||
B3_SHARED_API void b3GetMeshData(b3PhysicsClientHandle physClient, struct b3MeshData* meshData)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient*)physClient;
|
||||
|
||||
Reference in New Issue
Block a user