make pybullet.getMeshData work for softbody
This commit is contained in:
@@ -7358,46 +7358,57 @@ static PyObject* pybullet_createCollisionShapeArray(PyObject* self, PyObject* ar
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
static PyObject* pybullet_getMeshData(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
{
|
||||
int bodyUniqueId = -1;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
b3SharedMemoryCommandHandle command;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
struct b3MeshData meshData;
|
||||
int statusType;
|
||||
int bodyUniqueId = -1;
|
||||
int linkIndex = -1;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
b3SharedMemoryCommandHandle command;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
struct b3MeshData meshData;
|
||||
int statusType;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char* kwlist[] = {"bodyUniqueId", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &bodyUniqueId, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
if (sm == 0)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
command = b3GetMeshDataCommandInit(sm, bodyUniqueId);
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType == CMD_REQUEST_MESH_DATA_COMPLETED)
|
||||
{
|
||||
b3GetMeshData(sm, &meshData);
|
||||
PyObject* pyListMeshData = PyTuple_New(1);
|
||||
PyTuple_SetItem(pyListMeshData, 0, PyInt_FromLong(meshData.m_numVertices));
|
||||
return pyListMeshData;
|
||||
}
|
||||
}
|
||||
PyErr_SetString(SpamError, "Couldn't get body info");
|
||||
return NULL;
|
||||
int physicsClientId = 0;
|
||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|ii", kwlist, &bodyUniqueId, &linkIndex, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
if (sm == 0)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
command = b3GetMeshDataCommandInit(sm, bodyUniqueId, linkIndex);
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType == CMD_REQUEST_MESH_DATA_COMPLETED)
|
||||
{
|
||||
int i;
|
||||
PyObject* pyVertexData;
|
||||
PyObject* pyListMeshData = PyTuple_New(2);
|
||||
b3GetMeshData(sm, &meshData);
|
||||
PyTuple_SetItem(pyListMeshData, 0, PyInt_FromLong(meshData.m_numVertices));
|
||||
pyVertexData = PyTuple_New(meshData.m_numVertices);
|
||||
PyTuple_SetItem(pyListMeshData, 1, pyVertexData);
|
||||
|
||||
for (i = 0; i < meshData.m_numVertices; i++)
|
||||
{
|
||||
PyObject* pyListVertex = PyTuple_New(3);
|
||||
PyTuple_SetItem(pyListVertex, 0, PyFloat_FromDouble(meshData.m_vertices[i].x));
|
||||
PyTuple_SetItem(pyListVertex, 1, PyFloat_FromDouble(meshData.m_vertices[i].y));
|
||||
PyTuple_SetItem(pyListVertex, 2, PyFloat_FromDouble(meshData.m_vertices[i].z));
|
||||
PyTuple_SetItem(pyVertexData, i, pyListVertex);
|
||||
}
|
||||
|
||||
return pyListMeshData;
|
||||
}
|
||||
|
||||
PyErr_SetString(SpamError, "getMeshData failed");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
|
||||
static PyObject* pybullet_createVisualShape(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int physicsClientId = 0;
|
||||
@@ -10485,7 +10496,7 @@ static PyMethodDef SpamMethods[] = {
|
||||
{"removeCollisionShape", (PyCFunction)pybullet_removeCollisionShape, METH_VARARGS | METH_KEYWORDS,
|
||||
"Remove a collision shape. Only useful when the collision shape is not used in a body (to perform a getClosestPoint query)."},
|
||||
|
||||
{"getMeshData", (PyCFunction)pybullet_getMeshData, METH_VARARGS | METH_KEYWORDS,
|
||||
{"getMeshData", (PyCFunction)pybullet_getMeshData, METH_VARARGS | METH_KEYWORDS,
|
||||
"Get mesh data. Returns vertices etc from the mesh."},
|
||||
|
||||
{"createVisualShape", (PyCFunction)pybullet_createVisualShape, METH_VARARGS | METH_KEYWORDS,
|
||||
|
||||
Reference in New Issue
Block a user