only report solver analytics if enabled using setPhysicsEngineParameter(reportSolverAnalytics=1)

This commit is contained in:
erwincoumans
2019-04-14 18:20:20 -07:00
parent 219970c09e
commit e97a7d77af
8 changed files with 61 additions and 35 deletions

View File

@@ -689,6 +689,17 @@ B3_SHARED_API int b3PhysicsParameterSetMinimumSolverIslandSize(b3SharedMemoryCom
return 0; return 0;
} }
B3_SHARED_API int b3PhysicsParamSetSolverAnalytics(b3SharedMemoryCommandHandle commandHandle, int reportSolverAnalytics)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
command->m_physSimParamArgs.m_reportSolverAnalytics = reportSolverAnalytics;
command->m_updateFlags |= SIM_PARAM_REPORT_CONSTRAINT_SOLVER_ANALYTICS;
return 0;
}
B3_SHARED_API int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHandle, int filterMode) B3_SHARED_API int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHandle, int filterMode)
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;

View File

@@ -349,7 +349,8 @@ extern "C"
B3_SHARED_API int b3PhysicsParameterSetEnableSAT(b3SharedMemoryCommandHandle commandHandle, int enableSAT); B3_SHARED_API int b3PhysicsParameterSetEnableSAT(b3SharedMemoryCommandHandle commandHandle, int enableSAT);
B3_SHARED_API int b3PhysicsParameterSetConstraintSolverType(b3SharedMemoryCommandHandle commandHandle, int constraintSolverType); B3_SHARED_API int b3PhysicsParameterSetConstraintSolverType(b3SharedMemoryCommandHandle commandHandle, int constraintSolverType);
B3_SHARED_API int b3PhysicsParameterSetMinimumSolverIslandSize(b3SharedMemoryCommandHandle commandHandle, int minimumSolverIslandSize); B3_SHARED_API int b3PhysicsParameterSetMinimumSolverIslandSize(b3SharedMemoryCommandHandle commandHandle, int minimumSolverIslandSize);
B3_SHARED_API int b3PhysicsParamSetSolverAnalytics(b3SharedMemoryCommandHandle commandHandle, int reportSolverAnalytics);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestPhysicsParamCommand(b3PhysicsClientHandle physClient); B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestPhysicsParamCommand(b3PhysicsClientHandle physClient);
B3_SHARED_API int b3GetStatusPhysicsSimulationParameters(b3SharedMemoryStatusHandle statusHandle, struct b3PhysicsSimulationParameters* params); B3_SHARED_API int b3GetStatusPhysicsSimulationParameters(b3SharedMemoryStatusHandle statusHandle, struct b3PhysicsSimulationParameters* params);

View File

@@ -7605,7 +7605,7 @@ bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct S
} }
btScalar deltaTimeScaled = m_data->m_physicsDeltaTime * simTimeScalingFactor; btScalar deltaTimeScaled = m_data->m_physicsDeltaTime * simTimeScalingFactor;
m_data->m_dynamicsWorld->getSolverInfo().m_reportSolverAnalytics = true;
int numSteps = 0; int numSteps = 0;
if (m_data->m_numSimulationSubSteps > 0) if (m_data->m_numSimulationSubSteps > 0)
{ {
@@ -8426,6 +8426,11 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st
m_data->m_pluginManager.getFileIOInterface()->enableFileCaching(clientCmd.m_physSimParamArgs.m_enableFileCaching!=0); m_data->m_pluginManager.getFileIOInterface()->enableFileCaching(clientCmd.m_physSimParamArgs.m_enableFileCaching!=0);
} }
if (clientCmd.m_updateFlags & SIM_PARAM_REPORT_CONSTRAINT_SOLVER_ANALYTICS)
{
m_data->m_dynamicsWorld->getSolverInfo().m_reportSolverAnalytics = clientCmd.m_physSimParamArgs.m_reportSolverAnalytics;
}
SharedMemoryStatus& serverCmd = serverStatusOut; SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED; serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
return hasStatus; return hasStatus;

View File

@@ -456,31 +456,32 @@ enum EnumSimDesiredStateUpdateFlags
enum EnumSimParamUpdateFlags enum EnumSimParamUpdateFlags
{ {
SIM_PARAM_UPDATE_DELTA_TIME = 1, SIM_PARAM_UPDATE_DELTA_TIME = 1,
SIM_PARAM_UPDATE_GRAVITY = 2, SIM_PARAM_UPDATE_GRAVITY = 1<<1,
SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS = 4, SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS = 1<<2,
SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS = 8, SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS = 1<<3,
SIM_PARAM_UPDATE_REAL_TIME_SIMULATION = 16, SIM_PARAM_UPDATE_REAL_TIME_SIMULATION = 1<<4,
SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP = 32, SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP = 1<<5,
SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS = 64, SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS = 1<<6,
SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE = 128, SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE = 1<<7,
SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD = 256, SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD = 1<<8,
SIM_PARAM_UPDATE_COLLISION_FILTER_MODE = 512, SIM_PARAM_UPDATE_COLLISION_FILTER_MODE = 1 << 9,
SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD = 1024, SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD = 1 << 10,
SIM_PARAM_ENABLE_CONE_FRICTION = 2048, SIM_PARAM_ENABLE_CONE_FRICTION = 1 << 11,
SIM_PARAM_ENABLE_FILE_CACHING = 4096, SIM_PARAM_ENABLE_FILE_CACHING = 1 << 12,
SIM_PARAM_UPDATE_RESTITUTION_VELOCITY_THRESHOLD = 8192, SIM_PARAM_UPDATE_RESTITUTION_VELOCITY_THRESHOLD = 1 << 13,
SIM_PARAM_UPDATE_DEFAULT_NON_CONTACT_ERP = 16384, SIM_PARAM_UPDATE_DEFAULT_NON_CONTACT_ERP = 1 << 14,
SIM_PARAM_UPDATE_DEFAULT_FRICTION_ERP = 32768, SIM_PARAM_UPDATE_DEFAULT_FRICTION_ERP = 1 << 15,
SIM_PARAM_UPDATE_DETERMINISTIC_OVERLAPPING_PAIRS = 65536, SIM_PARAM_UPDATE_DETERMINISTIC_OVERLAPPING_PAIRS = 1 << 16,
SIM_PARAM_UPDATE_CCD_ALLOWED_PENETRATION = 131072, SIM_PARAM_UPDATE_CCD_ALLOWED_PENETRATION = 1 << 17,
SIM_PARAM_UPDATE_JOINT_FEEDBACK_MODE = 262144, SIM_PARAM_UPDATE_JOINT_FEEDBACK_MODE = 1 << 18,
SIM_PARAM_UPDATE_DEFAULT_GLOBAL_CFM = 524288, SIM_PARAM_UPDATE_DEFAULT_GLOBAL_CFM = 1 << 19,
SIM_PARAM_UPDATE_DEFAULT_FRICTION_CFM = 1048576, SIM_PARAM_UPDATE_DEFAULT_FRICTION_CFM = 1 << 20,
SIM_PARAM_UPDATE_SOLVER_RESIDULAL_THRESHOLD = 2097152, SIM_PARAM_UPDATE_SOLVER_RESIDULAL_THRESHOLD = 1 << 21,
SIM_PARAM_UPDATE_CONTACT_SLOP = 4194304, SIM_PARAM_UPDATE_CONTACT_SLOP = 1 << 22,
SIM_PARAM_ENABLE_SAT = 8388608, SIM_PARAM_ENABLE_SAT = 1 << 23,
SIM_PARAM_CONSTRAINT_SOLVER_TYPE = 16777216, SIM_PARAM_CONSTRAINT_SOLVER_TYPE = 1 << 24,
SIM_PARAM_CONSTRAINT_MIN_SOLVER_ISLAND_SIZE = 33554432, SIM_PARAM_CONSTRAINT_MIN_SOLVER_ISLAND_SIZE = 1 << 25,
SIM_PARAM_REPORT_CONSTRAINT_SOLVER_ANALYTICS = 1 << 26,
}; };

View File

@@ -903,7 +903,7 @@ struct b3PluginArguments
struct b3PhysicsSimulationParameters struct b3PhysicsSimulationParameters
{ {
double m_deltaTime; double m_deltaTime;
double m_simulationTimestamp; // Output only timestamp of simulation. double m_simulationTimestamp; // user logging timestamp of simulation.
double m_gravityAcceleration[3]; double m_gravityAcceleration[3];
int m_numSimulationSubSteps; int m_numSimulationSubSteps;
int m_numSolverIterations; int m_numSolverIterations;
@@ -929,6 +929,7 @@ struct b3PhysicsSimulationParameters
int m_enableSAT; int m_enableSAT;
int m_constraintSolverType; int m_constraintSolverType;
int m_minimumSolverIslandSize; int m_minimumSolverIslandSize;
int m_reportSolverAnalytics;
}; };

View File

@@ -1567,8 +1567,9 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
double globalCFM = -1; double globalCFM = -1;
int minimumSolverIslandSize = -1; int minimumSolverIslandSize = -1;
int reportSolverAnalytics = -1;
int physicsClientId = 0; int physicsClientId = 0;
static char* kwlist[] = {"fixedTimeStep", static char* kwlist[] = {"fixedTimeStep",
"numSolverIterations", "numSolverIterations",
"useSplitImpulse", "useSplitImpulse",
@@ -1592,10 +1593,12 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
"constraintSolverType", "constraintSolverType",
"globalCFM", "globalCFM",
"minimumSolverIslandSize", "minimumSolverIslandSize",
"reportSolverAnalytics",
"physicsClientId", NULL}; "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidiiddddiididdiidii", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps, if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidiiddddiididdiidiii", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps,
&collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &enableFileCaching, &restitutionVelocityThreshold, &erp, &contactERP, &frictionERP, &enableConeFriction, &deterministicOverlappingPairs, &allowedCcdPenetration, &jointFeedbackMode, &solverResidualThreshold, &contactSlop, &enableSAT, &constraintSolverType, &globalCFM, &minimumSolverIslandSize, &physicsClientId)) &collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &enableFileCaching, &restitutionVelocityThreshold, &erp, &contactERP, &frictionERP, &enableConeFriction, &deterministicOverlappingPairs, &allowedCcdPenetration, &jointFeedbackMode, &solverResidualThreshold, &contactSlop, &enableSAT, &constraintSolverType, &globalCFM, &minimumSolverIslandSize,
&reportSolverAnalytics, &physicsClientId))
{ {
return NULL; return NULL;
} }
@@ -1712,6 +1715,10 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
{ {
b3PhysicsParamSetDefaultGlobalCFM(command, globalCFM); b3PhysicsParamSetDefaultGlobalCFM(command, globalCFM);
} }
if (reportSolverAnalytics >= 0)
{
b3PhysicsParamSetSolverAnalytics(command, reportSolverAnalytics);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
} }

View File

@@ -64,7 +64,7 @@ struct btContactSolverInfoData
btScalar m_restitutionVelocityThreshold; btScalar m_restitutionVelocityThreshold;
bool m_jointFeedbackInWorldSpace; bool m_jointFeedbackInWorldSpace;
bool m_jointFeedbackInJointFrame; bool m_jointFeedbackInJointFrame;
bool m_reportSolverAnalytics; int m_reportSolverAnalytics;
}; };
struct btContactSolverInfo : public btContactSolverInfoData struct btContactSolverInfo : public btContactSolverInfoData
@@ -99,7 +99,7 @@ struct btContactSolverInfo : public btContactSolverInfoData
m_restitutionVelocityThreshold = 0.2f; //if the relative velocity is below this threshold, there is zero restitution m_restitutionVelocityThreshold = 0.2f; //if the relative velocity is below this threshold, there is zero restitution
m_jointFeedbackInWorldSpace = false; m_jointFeedbackInWorldSpace = false;
m_jointFeedbackInJointFrame = false; m_jointFeedbackInJointFrame = false;
m_reportSolverAnalytics = false; m_reportSolverAnalytics = 0;
} }
}; };

View File

@@ -274,7 +274,7 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::
{ {
///we don't split islands, so all constraints/contact manifolds/bodies are passed into the solver regardless the island id ///we don't split islands, so all constraints/contact manifolds/bodies are passed into the solver regardless the island id
m_solver->solveMultiBodyGroup(bodies, numBodies, manifolds, numManifolds, m_sortedConstraints, m_numConstraints, &m_multiBodySortedConstraints[0], m_numConstraints, *m_solverInfo, m_debugDrawer, m_dispatcher); m_solver->solveMultiBodyGroup(bodies, numBodies, manifolds, numManifolds, m_sortedConstraints, m_numConstraints, &m_multiBodySortedConstraints[0], m_numConstraints, *m_solverInfo, m_debugDrawer, m_dispatcher);
if (m_solverInfo->m_reportSolverAnalytics) if (m_solverInfo->m_reportSolverAnalytics&1)
{ {
m_solver->m_analyticsData.m_islandId = islandId; m_solver->m_analyticsData.m_islandId = islandId;
m_islandAnalyticsData.push_back(m_solver->m_analyticsData); m_islandAnalyticsData.push_back(m_solver->m_analyticsData);
@@ -363,7 +363,7 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::
//printf("mb contacts = %d, mb constraints = %d\n", mbContacts, m_multiBodyConstraints.size()); //printf("mb contacts = %d, mb constraints = %d\n", mbContacts, m_multiBodyConstraints.size());
m_solver->solveMultiBodyGroup(bodies, m_bodies.size(), manifold, m_manifolds.size(), constraints, m_constraints.size(), multiBodyConstraints, m_multiBodyConstraints.size(), *m_solverInfo, m_debugDrawer, m_dispatcher); m_solver->solveMultiBodyGroup(bodies, m_bodies.size(), manifold, m_manifolds.size(), constraints, m_constraints.size(), multiBodyConstraints, m_multiBodyConstraints.size(), *m_solverInfo, m_debugDrawer, m_dispatcher);
if (m_bodies.size() && m_solverInfo->m_reportSolverAnalytics) if (m_bodies.size() && (m_solverInfo->m_reportSolverAnalytics&1))
{ {
m_solver->m_analyticsData.m_islandId = islandId; m_solver->m_analyticsData.m_islandId = islandId;
m_islandAnalyticsData.push_back(m_solver->m_analyticsData); m_islandAnalyticsData.push_back(m_solver->m_analyticsData);