expose some parameters through pybullet.getPhysicsEngineParameters (C-API: b3InitRequestPhysicsParamCommand + b3GetStatusPhysicsSimulationParameters)

This commit is contained in:
erwincoumans
2017-10-05 11:43:14 -07:00
parent 1262adeaec
commit 822ff077c7
10 changed files with 156 additions and 42 deletions

View File

@@ -325,6 +325,32 @@ B3_SHARED_API int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHand
return -1;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestPhysicsParamCommand(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle) command;
}
B3_SHARED_API int b3GetStatusPhysicsSimulationParameters(b3SharedMemoryStatusHandle statusHandle,struct b3PhysicsSimulationParameters* params)
{
const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
b3Assert(status);
b3Assert(status->m_type == CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED);
if (status && status->m_type == CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED)
{
*params = status->m_simulationParameterResultArgs;
return 1;
}
return 0;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
@@ -352,7 +378,7 @@ B3_SHARED_API int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandH
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
command->m_physSimParamArgs.m_allowRealTimeSimulation = (enableRealTimeSimulation!=0);
command->m_physSimParamArgs.m_useRealTimeSimulation = (enableRealTimeSimulation!=0);
command->m_updateFlags |= SIM_PARAM_UPDATE_REAL_TIME_SIMULATION;
return 0;
}
@@ -395,15 +421,11 @@ B3_SHARED_API int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryComman
command->m_updateFlags |= SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD;
return 0;
}
B3_SHARED_API int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHandle, int maxNumCmdPer1ms)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
command->m_physSimParamArgs.m_maxNumCmdPer1ms = maxNumCmdPer1ms;
command->m_updateFlags |= SIM_PARAM_MAX_CMD_PER_1MS;
//obsolete command
return 0;
}
B3_SHARED_API int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle, int enableFileCaching)

View File

@@ -263,14 +263,10 @@ B3_SHARED_API int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandH
B3_SHARED_API int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP);
B3_SHARED_API int b3PhysicsParamSetDefaultNonContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultNonContactERP);
B3_SHARED_API int b3PhysicsParamSetDefaultFrictionERP(b3SharedMemoryCommandHandle commandHandle, double frictionERP);
B3_SHARED_API int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps);
B3_SHARED_API int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation);
B3_SHARED_API int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations);
B3_SHARED_API int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHandle, int filterMode);
B3_SHARED_API int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, int useSplitImpulse);
B3_SHARED_API int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold);
B3_SHARED_API int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold);
@@ -279,6 +275,9 @@ B3_SHARED_API int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle
B3_SHARED_API int b3PhysicsParamSetRestitutionVelocityThreshold(b3SharedMemoryCommandHandle commandHandle, double restitutionVelocityThreshold);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestPhysicsParamCommand(b3PhysicsClientHandle physClient);
B3_SHARED_API int b3GetStatusPhysicsSimulationParameters(b3SharedMemoryStatusHandle statusHandle,struct b3PhysicsSimulationParameters* params);
//b3PhysicsParamSetInternalSimFlags is for internal/temporary/easter-egg/experimental demo purposes
//Use at own risk: magic things may or my not happen when calling this API

View File

@@ -1225,7 +1225,10 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
}
break;
}
case CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED:
{
break;
}
default: {
b3Error("Unknown server status %d\n", serverCmd.m_type);
btAssert(0);

View File

@@ -978,6 +978,10 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
{
break;
}
case CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED:
{
break;
}
default:
{
//b3Warning("Unknown server status type");

View File

@@ -360,7 +360,7 @@ struct CommandLogger
case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS:
{
fwrite((const char*)&command.m_updateFlags,sizeof(int), 1,m_file);
fwrite((const char*)&command.m_physSimParamArgs, sizeof(SendPhysicsSimulationParameters), 1,m_file);
fwrite((const char*)&command.m_physSimParamArgs, sizeof(b3PhysicsSimulationParameters), 1,m_file);
break;
}
case CMD_REQUEST_CONTACT_POINT_INFORMATION:
@@ -564,7 +564,7 @@ struct CommandLogPlayback
cmd->m_physSimParamArgs = unused.m_physSimParamArgs;
#else
fread(&cmd->m_updateFlags,sizeof(int),1,m_file);
fread(&cmd->m_physSimParamArgs ,sizeof(SendPhysicsSimulationParameters),1,m_file);
fread(&cmd->m_physSimParamArgs ,sizeof(b3PhysicsSimulationParameters),1,m_file);
#endif
result = true;
@@ -1440,7 +1440,7 @@ struct PhysicsServerCommandProcessorInternalData
b3PluginManager m_pluginManager;
bool m_allowRealTimeSimulation;
bool m_useRealTimeSimulation;
b3VRControllerEvents m_vrControllerEvents;
@@ -1524,7 +1524,7 @@ struct PhysicsServerCommandProcessorInternalData
PhysicsServerCommandProcessorInternalData(PhysicsCommandProcessorInterface* proc)
:m_pluginManager(proc),
m_allowRealTimeSimulation(false),
m_useRealTimeSimulation(false),
m_commandLogger(0),
m_logPlayback(0),
m_physicsDeltaTime(1./240.),
@@ -5690,6 +5690,33 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
}
break;
}
case CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS:
{
SharedMemoryStatus& serverCmd =serverStatusOut;
serverCmd.m_type = CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED;
serverCmd.m_simulationParameterResultArgs.m_collisionFilterMode = m_data->m_broadphaseCollisionFilterCallback->m_filterMode;
serverCmd.m_simulationParameterResultArgs.m_contactBreakingThreshold = gContactBreakingThreshold;
serverCmd.m_simulationParameterResultArgs.m_defaultContactERP = m_data->m_dynamicsWorld->getSolverInfo().m_erp2;
serverCmd.m_simulationParameterResultArgs.m_defaultNonContactERP = m_data->m_dynamicsWorld->getSolverInfo().m_erp;
serverCmd.m_simulationParameterResultArgs.m_deltaTime = m_data->m_physicsDeltaTime;
serverCmd.m_simulationParameterResultArgs.m_enableFileCaching = b3IsFileCachingEnabled();
serverCmd.m_simulationParameterResultArgs.m_frictionERP = m_data->m_dynamicsWorld->getSolverInfo().m_frictionERP;
btVector3 grav = m_data->m_dynamicsWorld->getGravity();
serverCmd.m_simulationParameterResultArgs.m_gravityAcceleration[0] = grav[0];
serverCmd.m_simulationParameterResultArgs.m_gravityAcceleration[1] = grav[1];
serverCmd.m_simulationParameterResultArgs.m_gravityAcceleration[2] = grav[2];
serverCmd.m_simulationParameterResultArgs.m_internalSimFlags = gInternalSimFlags;
serverCmd.m_simulationParameterResultArgs.m_numSimulationSubSteps = m_data->m_numSimulationSubSteps;
serverCmd.m_simulationParameterResultArgs.m_numSolverIterations = m_data->m_dynamicsWorld->getSolverInfo().m_numIterations;
serverCmd.m_simulationParameterResultArgs.m_restitutionVelocityThreshold = m_data->m_dynamicsWorld->getSolverInfo().m_restitutionVelocityThreshold;
serverCmd.m_simulationParameterResultArgs.m_splitImpulsePenetrationThreshold = m_data->m_dynamicsWorld->getSolverInfo().m_splitImpulsePenetrationThreshold;
serverCmd.m_simulationParameterResultArgs.m_useRealTimeSimulation = m_data->m_useRealTimeSimulation;
serverCmd.m_simulationParameterResultArgs.m_useSplitImpulse = m_data->m_dynamicsWorld->getSolverInfo().m_splitImpulse;
hasStatus = true;
break;
}
case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS:
{
BT_PROFILE("CMD_SEND_PHYSICS_SIMULATION_PARAMETERS");
@@ -5700,7 +5727,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
}
if (clientCmd.m_updateFlags & SIM_PARAM_UPDATE_REAL_TIME_SIMULATION)
{
m_data->m_allowRealTimeSimulation = clientCmd.m_physSimParamArgs.m_allowRealTimeSimulation;
m_data->m_useRealTimeSimulation = (clientCmd.m_physSimParamArgs.m_useRealTimeSimulation!=0);
}
//see
@@ -8351,12 +8378,12 @@ double gSubStep = 0.f;
void PhysicsServerCommandProcessor::enableRealTimeSimulation(bool enableRealTimeSim)
{
m_data->m_allowRealTimeSimulation = enableRealTimeSim;
m_data->m_useRealTimeSimulation = enableRealTimeSim;
}
bool PhysicsServerCommandProcessor::isRealTimeSimulationEnabled() const
{
return m_data->m_allowRealTimeSimulation;
return m_data->m_useRealTimeSimulation;
}
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents)
@@ -8461,7 +8488,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec,const
}
}
if ((m_data->m_allowRealTimeSimulation) && m_data->m_guiHelper)
if ((m_data->m_useRealTimeSimulation) && m_data->m_guiHelper)
{

View File

@@ -428,25 +428,6 @@ enum EnumSimParamInternalSimFlags
///Controlling a robot involves sending the desired state to its joint motor controllers.
///The control mode determines the state variables used for motor control.
struct SendPhysicsSimulationParameters
{
double m_deltaTime;
double m_gravityAcceleration[3];
int m_numSimulationSubSteps;
int m_numSolverIterations;
bool m_allowRealTimeSimulation;
int m_useSplitImpulse;
double m_splitImpulsePenetrationThreshold;
double m_contactBreakingThreshold;
int m_maxNumCmdPer1ms;
int m_internalSimFlags;
double m_defaultContactERP;
int m_collisionFilterMode;
int m_enableFileCaching;
double m_restitutionVelocityThreshold;
double m_defaultNonContactERP;
double m_frictionERP;
};
struct LoadBunnyArgs
{
@@ -971,7 +952,7 @@ struct SharedMemoryCommand
struct ChangeDynamicsInfoArgs m_changeDynamicsInfoArgs;
struct GetDynamicsInfoArgs m_getDynamicsInfoArgs;
struct InitPoseArgs m_initPoseArgs;
struct SendPhysicsSimulationParameters m_physSimParamArgs;
struct b3PhysicsSimulationParameters m_physSimParamArgs;
struct BulletDataStreamArgs m_dataStreamArguments;
struct SendDesiredStateArgs m_sendDesiredStateCommandArgument;
struct RequestActualStateArgs m_requestActualStateInformationCommandArgument;
@@ -1079,7 +1060,7 @@ struct SharedMemoryStatus
struct SendMouseEvents m_sendMouseEvents;
struct b3LoadTextureResultArgs m_loadTextureResultArguments;
struct b3CustomCommandResultArgs m_customCommandResultArgs;
struct b3PhysicsSimulationParameters m_simulationParameterResultArgs;
};
};

View File

@@ -75,6 +75,7 @@ enum EnumSharedMemoryClientCommand
CMD_CHANGE_TEXTURE,
CMD_SET_ADDITIONAL_SEARCH_PATH,
CMD_CUSTOM_COMMAND,
CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS,
//don't go beyond this command!
CMD_MAX_CLIENT_COMMANDS,
@@ -174,7 +175,7 @@ enum EnumSharedMemoryServerStatus
CMD_CHANGE_TEXTURE_COMMAND_FAILED,
CMD_CUSTOM_COMMAND_COMPLETED,
CMD_CUSTOM_COMMAND_FAILED,
CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED,
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
CMD_MAX_SERVER_COMMANDS
};
@@ -640,5 +641,24 @@ struct b3PluginArguments
double m_floats[B3_MAX_PLUGIN_ARG_SIZE];
};
struct b3PhysicsSimulationParameters
{
double m_deltaTime;
double m_gravityAcceleration[3];
int m_numSimulationSubSteps;
int m_numSolverIterations;
int m_useRealTimeSimulation;
int m_useSplitImpulse;
double m_splitImpulsePenetrationThreshold;
double m_contactBreakingThreshold;
int m_internalSimFlags;
double m_defaultContactERP;
int m_collisionFilterMode;
int m_enableFileCaching;
double m_restitutionVelocityThreshold;
double m_defaultNonContactERP;
double m_frictionERP;
};
#endif//SHARED_MEMORY_PUBLIC_H