store mass matrix in streaming part of shared memory (no support for unlimited mass matrix sizes at the moment)
This commit is contained in:
@@ -3003,6 +3003,38 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char*
|
||||
bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes )
|
||||
{
|
||||
// BT_PROFILE("processCommand");
|
||||
int szc = sizeof(SharedMemoryCommand);
|
||||
int sz = sizeof(SharedMemoryStatus);
|
||||
|
||||
int sz1 = sizeof(BulletDataStreamArgs);
|
||||
int sz2 = sizeof(SdfLoadedArgs);
|
||||
int sz3 = sizeof(SendActualStateArgs);//30k
|
||||
int sz4= sizeof(SendDebugLinesArgs);
|
||||
int sz5= sizeof(SendPixelDataArgs);
|
||||
int sz6 = sizeof(RigidBodyCreateArgs);
|
||||
int sz7 = sizeof(CalculateInverseDynamicsResultArgs);
|
||||
int sz8 = sizeof(CalculateJacobianResultArgs);
|
||||
int sz9 = sizeof(CalculateMassMatrixResultArgs);//130k
|
||||
int sz10 = sizeof(SendContactDataArgs);
|
||||
int sz11 = sizeof(SendOverlappingObjectsArgs);
|
||||
int sz12 = sizeof(CalculateInverseKinematicsResultArgs);
|
||||
int sz13 = sizeof(SendVisualShapeDataArgs);
|
||||
int sz14 = sizeof(UserDebugDrawResultArgs);
|
||||
int sz15 = sizeof(b3UserConstraint);
|
||||
int sz16 = sizeof(SendVREvents);
|
||||
int sz17 = sizeof(SendKeyboardEvents);
|
||||
int sz18 = sizeof(SendRaycastHits);
|
||||
int sz19 = sizeof(StateLoggingResultArgs);
|
||||
int sz20 = sizeof(b3OpenGLVisualizerCameraInfo);
|
||||
int sz21 = sizeof(b3ObjectArgs);
|
||||
int sz22 = sizeof(b3DynamicsInfo);
|
||||
int sz23 = sizeof(b3CreateCollisionShapeResultArgs);
|
||||
int sz24 = sizeof(b3CreateVisualShapeResultArgs);
|
||||
int sz25 = sizeof(b3CreateMultiBodyResultArgs);
|
||||
int sz26 = sizeof(b3SendCollisionInfoArgs);
|
||||
int sz27 = sizeof(SendMouseEvents);
|
||||
int sz28 = sizeof(b3LoadTextureResultArgs);
|
||||
int sz29 = sizeof(b3CustomCommandResultArgs);
|
||||
|
||||
bool hasStatus = false;
|
||||
|
||||
@@ -6722,10 +6754,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
BT_PROFILE("CMD_CALCULATE_MASS_MATRIX");
|
||||
|
||||
SharedMemoryStatus& serverCmd = serverStatusOut;
|
||||
serverCmd.m_type = CMD_CALCULATED_MASS_MATRIX_FAILED;
|
||||
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_calculateMassMatrixArguments.m_bodyUniqueId);
|
||||
if (bodyHandle && bodyHandle->m_multiBody)
|
||||
{
|
||||
serverCmd.m_type = CMD_CALCULATED_MASS_MATRIX_FAILED;
|
||||
|
||||
btInverseDynamics::MultiBodyTree* tree = m_data->findOrCreateTree(bodyHandle->m_multiBody);
|
||||
|
||||
@@ -6744,20 +6776,23 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
serverCmd.m_massMatrixResultArgs.m_dofCount = totDofs;
|
||||
// Fill in the result into the shared memory.
|
||||
for (int i = 0; i < (totDofs); ++i)
|
||||
{
|
||||
for (int j = 0; j < (totDofs); ++j)
|
||||
{
|
||||
int element = (totDofs) * i + j;
|
||||
serverCmd.m_massMatrixResultArgs.m_massMatrix[element] = massMatrix(i,j);
|
||||
}
|
||||
}
|
||||
serverCmd.m_type = CMD_CALCULATED_MASS_MATRIX_COMPLETED;
|
||||
}
|
||||
else
|
||||
{
|
||||
serverCmd.m_type = CMD_CALCULATED_MASS_MATRIX_FAILED;
|
||||
double* sharedBuf = (double*)bufferServerToClient;
|
||||
int sizeInBytes = totDofs*totDofs*sizeof(double);
|
||||
if (sizeInBytes < bufferSizeInBytes)
|
||||
{
|
||||
for (int i = 0; i < (totDofs); ++i)
|
||||
{
|
||||
for (int j = 0; j < (totDofs); ++j)
|
||||
{
|
||||
int element = (totDofs) * i + j;
|
||||
|
||||
sharedBuf[element] = massMatrix(i,j);
|
||||
}
|
||||
}
|
||||
serverCmd.m_type = CMD_CALCULATED_MASS_MATRIX_COMPLETED;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user