extending wrapper

This commit is contained in:
Maarten Behn 2022-12-22 19:27:16 +01:00
parent 2b4757f512
commit 54cdf39933
12 changed files with 90 additions and 9 deletions

View File

@ -67,6 +67,8 @@ public:
virtual void getCachedMeshData(struct b3MeshData* meshData) = 0;
virtual void getCachedTetraMeshData(struct b3TetraMeshData* meshData) = 0;
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData) = 0;
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData) = 0;

View File

@ -1567,6 +1567,18 @@ B3_SHARED_API void b3GetMeshDataSetFlags(b3SharedMemoryCommandHandle commandHand
}
}
B3_SHARED_API void b3GetTetraMeshDataSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_REQUEST_TETRA_MESH_DATA);
if (command->m_type == CMD_REQUEST_TETRA_MESH_DATA)
{
command->m_updateFlags = B3_TETRA_MESH_DATA_FLAGS;
command->m_requestMeshDataArgs.m_flags = flags;
}
}
B3_SHARED_API void b3GetMeshDataSimulationMesh(b3SharedMemoryCommandHandle commandHandle)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
@ -1592,6 +1604,15 @@ B3_SHARED_API void b3GetMeshData(b3PhysicsClientHandle physClient, struct b3Mesh
}
}
B3_SHARED_API void b3GetTetraMeshData(b3PhysicsClientHandle physClient, struct b3TetraMeshData* meshData)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
if (cl)
{
cl->getCachedTetraMeshData(meshData);
}
}
B3_SHARED_API int b3CreateVisualShapeAddSphere(b3SharedMemoryCommandHandle commandHandle, double radius)
{
return b3CreateCollisionShapeAddSphere(commandHandle, radius);

View File

@ -538,8 +538,10 @@ extern "C"
B3_SHARED_API void b3MeshDataSimulationMeshVelocity(b3SharedMemoryCommandHandle commandHandle);
B3_SHARED_API void b3GetMeshDataSetCollisionShapeIndex(b3SharedMemoryCommandHandle commandHandle, int shapeIndex);
B3_SHARED_API void b3GetMeshDataSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags);
B3_SHARED_API void b3GetTetraMeshDataSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags);
B3_SHARED_API void b3GetMeshData(b3PhysicsClientHandle physClient, struct b3MeshData* meshData);
B3_SHARED_API void b3GetTetraMeshData(b3PhysicsClientHandle physClient, struct b3TetraMeshData* meshData);
B3_SHARED_API b3SharedMemoryCommandHandle b3ResetMeshDataCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int num_vertices, const double* vertices);

View File

@ -54,6 +54,7 @@ struct PhysicsClientSharedMemoryInternalData
btAlignedObjectArray<b3CollisionShapeData> m_cachedCollisionShapes;
b3MeshData m_cachedMeshData;
b3TetraMeshData m_cachedTetraMeshData;
btAlignedObjectArray<b3MeshVertex> m_cachedVertexPositions;
btAlignedObjectArray<b3VRControllerEvent> m_cachedVREvents;
@ -1074,6 +1075,24 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus()
b3Warning("Request mesh data failed");
break;
}
case CMD_REQUEST_TETRA_MESH_DATA_COMPLETED:
{
m_data->m_cachedVertexPositions.resize(serverCmd.m_sendMeshDataArgs.m_startingVertex + serverCmd.m_sendMeshDataArgs.m_numVerticesCopied);
btVector3* verticesReceived = (btVector3*)m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor;
for (int i = 0; i < serverCmd.m_sendMeshDataArgs.m_numVerticesCopied; i++)
{
m_data->m_cachedVertexPositions[i + serverCmd.m_sendMeshDataArgs.m_startingVertex].x = verticesReceived[i].x();
m_data->m_cachedVertexPositions[i + serverCmd.m_sendMeshDataArgs.m_startingVertex].y = verticesReceived[i].y();
m_data->m_cachedVertexPositions[i + serverCmd.m_sendMeshDataArgs.m_startingVertex].z = verticesReceived[i].z();
m_data->m_cachedVertexPositions[i + serverCmd.m_sendMeshDataArgs.m_startingVertex].w = verticesReceived[i].w();
}
break;
}
case CMD_REQUEST_TETRA_MESH_DATA_FAILED:
{
b3Warning("Request tetra mesh data failed");
break;
}
case CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED:
{
break;
@ -2088,6 +2107,15 @@ void PhysicsClientSharedMemory::getCachedMeshData(struct b3MeshData* meshData)
*meshData = m_data->m_cachedMeshData;
}
void PhysicsClientSharedMemory::getCachedTetraMeshData(struct b3TetraMeshData* meshData)
{
m_data->m_cachedTetraMeshData.m_numVertices = m_data->m_cachedVertexPositions.size();
m_data->m_cachedTetraMeshData.m_vertices = m_data->m_cachedTetraMeshData.m_numVertices ? &m_data->m_cachedVertexPositions[0] : 0;
*meshData = m_data->m_cachedTetraMeshData;
}
const float* PhysicsClientSharedMemory::getDebugLinesFrom() const
{
if (m_data->m_debugLinesFrom.size())

View File

@ -80,6 +80,8 @@ public:
virtual void getCachedMeshData(struct b3MeshData* meshData);
virtual void getCachedTetraMeshData(struct b3TetraMeshData* meshData);
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData);
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);

View File

@ -67,6 +67,7 @@ struct PhysicsDirectInternalData
btAlignedObjectArray<b3CollisionShapeData> m_cachedCollisionShapes;
b3MeshData m_cachedMeshData;
b3TetraMeshData m_cachedTetraMeshData;
btAlignedObjectArray<b3MeshVertex> m_cachedVertexPositions;
btAlignedObjectArray<b3VRControllerEvent> m_cachedVREvents;
@ -99,6 +100,7 @@ struct PhysicsDirectInternalData
m_timeOutInSeconds(1e30)
{
memset(&m_cachedMeshData.m_numVertices, 0, sizeof(b3MeshData));
memset(&m_cachedTetraMeshData.m_numVertices, 0, sizeof(b3TetraMeshData));
memset(&m_command, 0, sizeof(m_command));
memset(&m_serverStatus, 0, sizeof(m_serverStatus));
memset(m_bulletStreamDataServerToClient, 0, sizeof(m_bulletStreamDataServerToClient));
@ -1691,6 +1693,16 @@ void PhysicsDirect::getCachedMeshData(struct b3MeshData* meshData)
*meshData = m_data->m_cachedMeshData;
}
void PhysicsDirect::getCachedTetraMeshData(struct b3TetraMeshData* meshData)
{
m_data->m_cachedTetraMeshData.m_numVertices = m_data->m_cachedVertexPositions.size();
m_data->m_cachedTetraMeshData.m_vertices = m_data->m_cachedTetraMeshData.m_numVertices ? &m_data->m_cachedVertexPositions[0] : 0;
*meshData = m_data->m_cachedTetraMeshData;
}
void PhysicsDirect::getCachedContactPointInformation(struct b3ContactInformation* contactPointData)
{
contactPointData->m_numContactPoints = m_data->m_cachedContactPoints.size();

View File

@ -106,6 +106,8 @@ public:
virtual void getCachedMeshData(struct b3MeshData* meshData);
virtual void getCachedTetraMeshData(struct b3TetraMeshData* meshData);
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData);
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);

View File

@ -183,6 +183,11 @@ void PhysicsLoopBack::getCachedMeshData(struct b3MeshData* meshData)
return m_data->m_physicsClient->getCachedMeshData(meshData);
}
void PhysicsLoopBack::getCachedTetraMeshData(struct b3TetraMeshData* meshData)
{
return m_data->m_physicsClient->getCachedTetraMeshData(meshData);
}
void PhysicsLoopBack::getCachedContactPointInformation(struct b3ContactInformation* contactPointData)
{
return m_data->m_physicsClient->getCachedContactPointInformation(contactPointData);

View File

@ -78,6 +78,8 @@ public:
virtual void getCachedMeshData(struct b3MeshData* meshData);
virtual void getCachedTetraMeshData(struct b3TetraMeshData* meshData);
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData);
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);

View File

@ -5721,8 +5721,8 @@ bool PhysicsServerCommandProcessor::processRequestMeshDataCommand(const struct S
bool PhysicsServerCommandProcessor::processRequestTetraMeshDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
bool hasStatus = true;
BT_PROFILE("CMD_REQUEST_MESH_DATA");
serverStatusOut.m_type = CMD_REQUEST_MESH_DATA_FAILED;
BT_PROFILE("CMD_REQUEST_TETRA_MESH_DATA");
serverStatusOut.m_type = CMD_REQUEST_TETRA_MESH_DATA_FAILED;
serverStatusOut.m_numDataStreamBytes = 0;
int sizeInBytes = 0;
@ -5733,8 +5733,6 @@ bool PhysicsServerCommandProcessor::processRequestTetraMeshDataCommand(const str
btVector3* verticesOut = (btVector3*)bufferServerToClient;
const btCollisionShape* colShape = 0;
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
if (bodyHandle->m_softBody)
{
btSoftBody* psb = bodyHandle->m_softBody;
@ -5758,7 +5756,6 @@ bool PhysicsServerCommandProcessor::processRequestTetraMeshDataCommand(const str
serverStatusOut.m_sendMeshDataArgs.m_startingVertex = clientCmd.m_requestMeshDataArgs.m_startingVertex;
serverStatusOut.m_sendMeshDataArgs.m_numVerticesRemaining = numVerticesRemaining - verticesCopied;
}
#endif //SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
}
serverStatusOut.m_numDataStreamBytes = sizeInBytes;

View File

@ -486,6 +486,11 @@ struct b3MeshData
struct b3MeshVertex* m_vertices;
};
enum eTetraMeshDataEnum
{
B3_TETRA_MESH_DATA_FLAGS=2,
};
struct b3TetraMeshData
{
int m_numVertices;

View File

@ -9196,7 +9196,7 @@ static PyObject* pybullet_getTetraMeshData(PyObject* self, PyObject* args, PyObj
b3PhysicsClientHandle sm = 0;
b3SharedMemoryCommandHandle command;
b3SharedMemoryStatusHandle statusHandle;
struct b3MeshData meshData;
struct b3TetraMeshData meshData;
int statusType;
int flags = -1;
@ -9215,7 +9215,7 @@ static PyObject* pybullet_getTetraMeshData(PyObject* self, PyObject* args, PyObj
command = b3GetTetraMeshDataCommandInit(sm, bodyUniqueId);
if (flags >= 0)
{
b3GetMeshDataSetFlags(command, flags);
b3GetTetraMeshDataSetFlags(command, flags);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
@ -9225,7 +9225,7 @@ static PyObject* pybullet_getTetraMeshData(PyObject* self, PyObject* args, PyObj
int i;
PyObject* pyVertexData;
PyObject* pyListMeshData = PyTuple_New(2);
b3GetMeshData(sm, &meshData);
b3GetTetraMeshData(sm, &meshData);
PyTuple_SetItem(pyListMeshData, 0, PyInt_FromLong(meshData.m_numVertices));
pyVertexData = PyTuple_New(meshData.m_numVertices);
PyTuple_SetItem(pyListMeshData, 1, pyVertexData);
@ -9242,7 +9242,7 @@ static PyObject* pybullet_getTetraMeshData(PyObject* self, PyObject* args, PyObj
return pyListMeshData;
}
PyErr_SetString(SpamError, "getMeshData failed");
PyErr_SetString(SpamError, "getTetraMeshData failed");
return NULL;
}
@ -12702,6 +12702,9 @@ static PyMethodDef SpamMethods[] = {
{"getMeshData", (PyCFunction)pybullet_getMeshData, METH_VARARGS | METH_KEYWORDS,
"Get mesh data. Returns vertices etc from the mesh."},
{"getTetraMeshData", (PyCFunction)pybullet_getTetraMeshData, METH_VARARGS | METH_KEYWORDS,
"Get mesh data. Returns tetra from the mesh."},
{"resetMeshData", (PyCFunction)pybullet_resetMeshData, METH_VARARGS | METH_KEYWORDS,
"Reset mesh data. Only implemented for deformable bodies."},