make pybullet.getMeshData work for softbody

This commit is contained in:
Erwin Coumans
2019-06-17 21:43:38 -07:00
parent 20d9ad5f24
commit 7e76ee0ad7
10 changed files with 244 additions and 198 deletions

View File

@@ -101,9 +101,8 @@ enum EnumSharedMemoryClientCommand
CMD_ADD_USER_DATA,
CMD_REMOVE_USER_DATA,
CMD_COLLISION_FILTER,
CMD_REQUEST_MESH_DATA,
CMD_REQUEST_MESH_DATA,
//don't go beyond this command!
CMD_MAX_CLIENT_COMMANDS,
};
@@ -224,8 +223,8 @@ enum EnumSharedMemoryServerStatus
CMD_REMOVE_STATE_COMPLETED,
CMD_REMOVE_STATE_FAILED,
CMD_REQUEST_MESH_DATA_COMPLETED,
CMD_REQUEST_MESH_DATA_FAILED,
CMD_REQUEST_MESH_DATA_COMPLETED,
CMD_REQUEST_MESH_DATA_FAILED,
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
CMD_MAX_SERVER_COMMANDS
};
@@ -411,10 +410,15 @@ struct b3CameraImageData
const int* m_segmentationMaskValues; //m_pixelWidth*m_pixelHeight ints
};
struct b3MeshVertex
{
double x, y, z, w;
};
struct b3MeshData
{
int m_numVertices;
double* m_vertices;
int m_numVertices;
struct b3MeshVertex* m_vertices;
};
struct b3OpenGLVisualizerCameraInfo