Merge pull request #2293 from fuchuyuan/getMeshData

get mesh data api
This commit is contained in:
erwincoumans 2019-06-17 20:37:18 -07:00 committed by GitHub
commit bfc390abf9
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
14 changed files with 268 additions and 5 deletions

View File

@ -65,6 +65,8 @@ public:
virtual void getCachedCollisionShapeInformation(struct b3CollisionShapeInformation* collisionShapesInfo) = 0;
virtual void getCachedMeshData(struct b3MeshData* meshData) = 0;
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData) = 0;
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData) = 0;

View File

@ -1210,6 +1210,33 @@ B3_SHARED_API int b3CreateCollisionShapeAddSphere(b3SharedMemoryCommandHandle co
return -1;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3GetMeshDataCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId){
PhysicsClient* cl = (PhysicsClient*)physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
if (cl)
{
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_REQUEST_MESH_DATA;
command->m_updateFlags = 0;
command->m_requestMeshDataArgs.m_bodyUniqueId = bodyUniqueId;
return (b3SharedMemoryCommandHandle)command;
}
return 0;
}
B3_SHARED_API void b3GetMeshData(b3PhysicsClientHandle physClient, struct b3MeshData* meshData){
PhysicsClient* cl = (PhysicsClient*)physClient;
if (cl)
{
cl->getCachedMeshData(meshData);
}
}
B3_SHARED_API int b3CreateVisualShapeAddSphere(b3SharedMemoryCommandHandle commandHandle, double radius)
{
return b3CreateCollisionShapeAddSphere(commandHandle, radius);

View File

@ -491,6 +491,10 @@ extern "C"
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRemoveCollisionShapeCommand(b3PhysicsClientHandle physClient, int collisionShapeId);
B3_SHARED_API b3SharedMemoryCommandHandle b3GetMeshDataCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId);
B3_SHARED_API void b3GetMeshData(b3PhysicsClientHandle physClient, struct b3MeshData* meshData);
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateVisualShapeCommandInit(b3PhysicsClientHandle physClient);
B3_SHARED_API int b3CreateVisualShapeAddSphere(b3SharedMemoryCommandHandle commandHandle, double radius);
B3_SHARED_API int b3CreateVisualShapeAddBox(b3SharedMemoryCommandHandle commandHandle, const double halfExtents[/*3*/]);

View File

@ -53,6 +53,9 @@ struct PhysicsClientSharedMemoryInternalData
btAlignedObjectArray<b3VisualShapeData> m_cachedVisualShapes;
btAlignedObjectArray<b3CollisionShapeData> m_cachedCollisionShapes;
b3MeshData m_cachedMeshData;
btAlignedObjectArray<double> m_cachedVertexPositions;
btAlignedObjectArray<b3VRControllerEvent> m_cachedVREvents;
btAlignedObjectArray<b3KeyboardEvent> m_cachedKeyboardEvents;
btAlignedObjectArray<b3MouseEvent> m_cachedMouseEvents;
@ -1032,6 +1035,15 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus()
b3Warning("Camera image FAILED\n");
break;
}
case CMD_REQUEST_MESH_DATA_COMPLETED:
{
break;
}
case CMD_REQUEST_MESH_DATA_FAILED:
{
b3Warning("Request mesh data failed");
break;
}
case CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED:
{
break;
@ -1758,6 +1770,26 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus()
}
}
if(serverCmd.m_type == CMD_REQUEST_MESH_DATA_COMPLETED)
{
B3_PROFILE("CMD_REQUEST_MESH_DATA_COMPLETED");
SharedMemoryCommand& command = m_data->m_testBlock1->m_clientCommands[0];
if (serverCmd.m_sendMeshDataArgs.m_numVerticesRemaining > 0 && serverCmd.m_sendMeshDataArgs.m_numVerticesCopied)
{
command.m_type = CMD_REQUEST_MESH_DATA;
command.m_requestMeshDataArgs.m_startingVertex=
serverCmd.m_sendMeshDataArgs.m_startingVertex +
serverCmd.m_sendMeshDataArgs.m_numVerticesCopied;
submitClientCommand(command);
return 0;
}
else
{
m_data->m_cachedMeshData.m_numVertices =serverCmd.m_sendMeshDataArgs.m_startingVertex +serverCmd.m_sendMeshDataArgs.m_numVerticesCopied;
}
}
if ((serverCmd.m_type == CMD_DEBUG_LINES_COMPLETED) &&
(serverCmd.m_sendDebugLinesArgs.m_numRemainingDebugLines > 0))
{
@ -1940,6 +1972,11 @@ void PhysicsClientSharedMemory::getCachedCollisionShapeInformation(struct b3Coll
collisionShapesInfo->m_collisionShapeData = collisionShapesInfo->m_numCollisionShapes ? &m_data->m_cachedCollisionShapes[0] : 0;
}
void PhysicsClientSharedMemory::getCachedMeshData(struct b3MeshData* meshData){
*meshData = m_data->m_cachedMeshData;
}
const float* PhysicsClientSharedMemory::getDebugLinesFrom() const
{
if (m_data->m_debugLinesFrom.size())
@ -2051,3 +2088,4 @@ void PhysicsClientSharedMemory::popProfileTiming()
delete sample;
}
}

View File

@ -76,6 +76,8 @@ public:
virtual void getCachedCollisionShapeInformation(struct b3CollisionShapeInformation* collisionShapesInfo);
virtual void getCachedMeshData(struct b3MeshData* meshData);
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData);
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);

View File

@ -66,6 +66,9 @@ struct PhysicsDirectInternalData
btAlignedObjectArray<b3VisualShapeData> m_cachedVisualShapes;
btAlignedObjectArray<b3CollisionShapeData> m_cachedCollisionShapes;
b3MeshData m_cachedMeshData;
btAlignedObjectArray<double> m_cachedVertexPositions;
btAlignedObjectArray<b3VRControllerEvent> m_cachedVREvents;
btAlignedObjectArray<b3KeyboardEvent> m_cachedKeyboardEvents;
@ -586,6 +589,76 @@ bool PhysicsDirect::processCamera(const struct SharedMemoryCommand& orgCommand)
return m_data->m_hasStatus;
}
bool PhysicsDirect::processMeshData(const struct SharedMemoryCommand& orgCommand)
{
SharedMemoryCommand command = orgCommand;
const SharedMemoryStatus& serverCmd = m_data->m_serverStatus;
do
{
bool hasStatus = m_data->m_commandProcessor->processCommand(command, m_data->m_serverStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
b3Clock clock;
double startTime = clock.getTimeInSeconds();
double timeOutInSeconds = m_data->m_timeOutInSeconds;
while ((!hasStatus) && (clock.getTimeInSeconds() - startTime < timeOutInSeconds))
{
const SharedMemoryStatus* stat = processServerStatus();
if (stat)
{
hasStatus = true;
}
}
m_data->m_hasStatus = hasStatus;
if (hasStatus)
{
btAssert(m_data->m_serverStatus.m_type == CMD_REQUEST_MESH_DATA_COMPLETED);
if (m_data->m_verboseOutput)
{
b3Printf("Mesh data OK\n");
}
const b3SendMeshDataArgs& args = serverCmd.m_sendMeshDataArgs;
int numTotalPixels =args.m_startingVertex +
args.m_numVerticesCopied + args.m_numVerticesRemaining;
double* verticesReceived =
(double*)&m_data->m_bulletStreamDataServerToClient[0];
// flattened position
const int dimension = 3;
m_data->m_cachedVertexPositions.resize((args.m_startingVertex +
args.m_numVerticesCopied)*dimension);
for (int i = 0; i < dimension*args.m_numVerticesCopied; i++)
{
m_data->m_cachedVertexPositions[i + dimension*args.m_startingVertex] = verticesReceived[i];
}
if (args.m_numVerticesRemaining > 0 && args.m_numVerticesCopied)
{
m_data->m_hasStatus = false;
// continue requesting remaining vertices
command.m_type = CMD_REQUEST_MESH_DATA;
command.m_requestMeshDataArgs.m_startingVertex =
args.m_startingVertex + args.m_numVerticesCopied;
}
else
{
m_data->m_cachedMeshData.m_numVertices=args.m_startingVertex +
args.m_numVerticesCopied;
}
}
} while (serverCmd.m_sendMeshDataArgs.m_numVerticesRemaining > 0 && serverCmd.m_sendMeshDataArgs.m_numVerticesCopied);
return m_data->m_hasStatus;
}
void PhysicsDirect::processBodyJointInfo(int bodyUniqueId, const SharedMemoryStatus& serverCmd)
{
BodyJointInfoCache2** cachePtr = m_data->m_bodyJointMap[bodyUniqueId];
@ -883,7 +956,6 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
b3Clock clock;
double startTime = clock.getTimeInSeconds();
double timeOutInSeconds = m_data->m_timeOutInSeconds;
while ((!hasStatus) && (clock.getTimeInSeconds() - startTime < timeOutInSeconds))
{
hasStatus = m_data->m_commandProcessor->receiveStatus(m_data->m_tmpInfoStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
@ -958,6 +1030,7 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
b3Warning("createVisualShape failed");
break;
}
case CMD_CREATE_VISUAL_SHAPE_COMPLETED:
{
break;
@ -977,7 +1050,15 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
b3Warning("Request getCollisionInfo failed");
break;
}
case CMD_REQUEST_MESH_DATA_COMPLETED:
{
break;
}
case CMD_REQUEST_MESH_DATA_FAILED:
{
b3Warning("Request mesh data failed");
break;
}
case CMD_CUSTOM_COMMAND_COMPLETED:
{
break;
@ -1203,6 +1284,11 @@ bool PhysicsDirect::submitClientCommand(const struct SharedMemoryCommand& comman
return processOverlappingObjects(command);
}
if (command.m_type == CMD_REQUEST_MESH_DATA)
{
return processMeshData(command);
}
bool hasStatus = m_data->m_commandProcessor->processCommand(command, m_data->m_serverStatus, &m_data->m_bulletStreamDataServerToClient[0], SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
m_data->m_hasStatus = hasStatus;
@ -1440,6 +1526,9 @@ void PhysicsDirect::getCachedCameraImage(b3CameraImageData* cameraData)
}
}
void PhysicsDirect::getCachedMeshData(struct b3MeshData* meshData){
*meshData = m_data->m_cachedMeshData;
}
void PhysicsDirect::getCachedContactPointInformation(struct b3ContactInformation* contactPointData)
{
contactPointData->m_numContactPoints = m_data->m_cachedContactPoints.size();

View File

@ -22,6 +22,8 @@ protected:
bool processVisualShapeData(const struct SharedMemoryCommand& orgCommand);
bool processMeshData(const struct SharedMemoryCommand& orgCommand);
void processBodyJointInfo(int bodyUniqueId, const struct SharedMemoryStatus& serverCmd);
void processAddUserData(const struct SharedMemoryStatus& serverCmd);
@ -96,6 +98,8 @@ public:
virtual void getCachedCollisionShapeInformation(struct b3CollisionShapeInformation* collisionShapesInfo);
virtual void getCachedMeshData(struct b3MeshData* meshData);
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData);
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);

View File

@ -178,8 +178,10 @@ void PhysicsLoopBack::getCachedCameraImage(struct b3CameraImageData* cameraData)
return m_data->m_physicsClient->getCachedCameraImage(cameraData);
}
void PhysicsLoopBack::getCachedMeshData(struct b3MeshData* meshData)
{
return m_data->m_physicsClient->getCachedMeshData(meshData);
}
void PhysicsLoopBack::getCachedContactPointInformation(struct b3ContactInformation* contactPointData)
{

View File

@ -76,6 +76,8 @@ public:
virtual void getCachedCollisionShapeInformation(struct b3CollisionShapeInformation* collisionShapesInfo);
virtual void getCachedMeshData(struct b3MeshData* meshData);
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData);
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);

View File

@ -4626,6 +4626,28 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
return hasStatus;
}
bool PhysicsServerCommandProcessor::processRequestMeshDataCommand(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;
serverStatusOut.m_numDataStreamBytes = 0;
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_requestMeshDataArgs.m_bodyUniqueId);
if (bodyHandle)
{
serverStatusOut.m_type = CMD_REQUEST_MESH_DATA_COMPLETED;
serverStatusOut.m_sendMeshDataArgs.m_numVerticesCopied = 1;
serverStatusOut.m_sendMeshDataArgs.m_startingVertex = 0;
serverStatusOut.m_sendMeshDataArgs.m_numVerticesRemaining = 0;
}
serverStatusOut.m_numDataStreamBytes = 0;
return hasStatus;
}
bool PhysicsServerCommandProcessor::processCreateVisualShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
bool hasStatus = true;
@ -11287,7 +11309,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
hasStatus = processCreateVisualShapeCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes);
break;
}
case CMD_REQUEST_MESH_DATA:{
hasStatus = processRequestMeshDataCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes);
break;
}
case CMD_CREATE_MULTI_BODY:
{
hasStatus = processCreateMultiBodyCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes);

View File

@ -26,6 +26,7 @@ protected:
bool processSaveWorldCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processCreateCollisionShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processCreateVisualShapeCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processRequestMeshDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processCustomCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processUserDebugDrawCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processSetVRCameraStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);

View File

@ -1054,6 +1054,17 @@ struct AddUserDataRequestArgs
// Value data stored in m_bulletStreamDataServerToClientRefactor.
};
struct b3RequestMeshDataArgs{
int m_bodyUniqueId;
int m_startingVertex;
};
struct b3SendMeshDataArgs{
int m_numVerticesCopied;
int m_startingVertex;
int m_numVerticesRemaining;
};
struct SharedMemoryCommand
{
int m_type;
@ -1113,6 +1124,7 @@ struct SharedMemoryCommand
struct AddUserDataRequestArgs m_addUserDataRequestArgs;
struct UserDataRequestArgs m_removeUserDataRequestArgs;
struct b3CollisionFilterArgs m_collisionFilterArgs;
struct b3RequestMeshDataArgs m_requestMeshDataArgs;
};
};
@ -1188,6 +1200,7 @@ struct SharedMemoryStatus
struct UserDataResponseArgs m_userDataResponseArgs;
struct UserDataRequestArgs m_removeUserDataResponseArgs;
struct b3ForwardDynamicsAnalyticsArgs m_forwardDynamicsAnalyticsArgs;
struct b3SendMeshDataArgs m_sendMeshDataArgs;
};
};

View File

@ -101,6 +101,8 @@ enum EnumSharedMemoryClientCommand
CMD_ADD_USER_DATA,
CMD_REMOVE_USER_DATA,
CMD_COLLISION_FILTER,
CMD_REQUEST_MESH_DATA,
//don't go beyond this command!
CMD_MAX_CLIENT_COMMANDS,
@ -221,6 +223,9 @@ enum EnumSharedMemoryServerStatus
CMD_REMOVE_USER_DATA_FAILED,
CMD_REMOVE_STATE_COMPLETED,
CMD_REMOVE_STATE_FAILED,
CMD_REQUEST_MESH_DATA_COMPLETED,
CMD_REQUEST_MESH_DATA_FAILED,
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
CMD_MAX_SERVER_COMMANDS
};
@ -406,6 +411,12 @@ struct b3CameraImageData
const int* m_segmentationMaskValues; //m_pixelWidth*m_pixelHeight ints
};
struct b3MeshData
{
int m_numVertices;
double* m_vertices;
};
struct b3OpenGLVisualizerCameraInfo
{
int m_width;

View File

@ -7358,6 +7358,46 @@ 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 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;
}
static PyObject* pybullet_createVisualShape(PyObject* self, PyObject* args, PyObject* keywds)
{
int physicsClientId = 0;
@ -10445,6 +10485,9 @@ 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,
"Get mesh data. Returns vertices etc from the mesh."},
{"createVisualShape", (PyCFunction)pybullet_createVisualShape, METH_VARARGS | METH_KEYWORDS,
"Create a visual shape. Returns a non-negative (int) unique id, if successfull, negative otherwise."},