PyBullet: expose STATE_LOGGING_ALL_COMMANDS and STATE_REPLAY_ALL_COMMANDS

See examples/pybullet/examples/commandLogAndPlayback.py for an example.
This commit is contained in:
erwincoumans
2018-06-12 16:56:45 -07:00
parent 459d07a302
commit 4d6741f5cd
4 changed files with 75 additions and 3 deletions

View File

@@ -1582,8 +1582,10 @@ struct PhysicsServerCommandProcessorInternalData
btAlignedObjectArray<b3MouseEvent> m_mouseEvents;
CommandLogger* m_commandLogger;
CommandLogPlayback* m_logPlayback;
int m_commandLoggingUid;
CommandLogPlayback* m_logPlayback;
int m_logPlaybackUid;
btScalar m_physicsDeltaTime;
btScalar m_numSimulationSubSteps;
@@ -1661,7 +1663,9 @@ struct PhysicsServerCommandProcessorInternalData
:m_pluginManager(proc),
m_useRealTimeSimulation(false),
m_commandLogger(0),
m_commandLoggingUid(-1),
m_logPlayback(0),
m_logPlaybackUid(-1),
m_physicsDeltaTime(1./240.),
m_numSimulationSubSteps(0),
m_userConstraintUIDGenerator(1),
@@ -3090,6 +3094,31 @@ bool PhysicsServerCommandProcessor::processStateLoggingCommand(const struct Shar
if (clientCmd.m_updateFlags & STATE_LOGGING_START_LOG)
{
if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_ALL_COMMANDS)
{
if(m_data->m_commandLogger==0)
{
enableCommandLogging(true, clientCmd.m_stateLoggingArguments.m_fileName);
serverStatusOut.m_type = CMD_STATE_LOGGING_START_COMPLETED;
int loggerUid = m_data->m_stateLoggersUniqueId++;
m_data->m_commandLoggingUid = loggerUid;
serverStatusOut.m_stateLoggingResultArgs.m_loggingUniqueId = loggerUid;
}
}
if (clientCmd.m_stateLoggingArguments.m_logType == STATE_REPLAY_ALL_COMMANDS)
{
if(m_data->m_logPlayback==0)
{
replayFromLogFile(clientCmd.m_stateLoggingArguments.m_fileName);
serverStatusOut.m_type = CMD_STATE_LOGGING_START_COMPLETED;
int loggerUid = m_data->m_stateLoggersUniqueId++;
m_data->m_logPlaybackUid = loggerUid;
serverStatusOut.m_stateLoggingResultArgs.m_loggingUniqueId = loggerUid;
}
}
if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_PROFILE_TIMINGS)
{
if (m_data->m_profileTimingLoggingUid<0)
@@ -3168,6 +3197,9 @@ bool PhysicsServerCommandProcessor::processStateLoggingCommand(const struct Shar
}
}
}
if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_GENERIC_ROBOT)
{
std::string fileName = clientCmd.m_stateLoggingArguments.m_fileName;
@@ -3245,6 +3277,27 @@ bool PhysicsServerCommandProcessor::processStateLoggingCommand(const struct Shar
}
if ((clientCmd.m_updateFlags & STATE_LOGGING_STOP_LOG) && clientCmd.m_stateLoggingArguments.m_loggingUniqueId>=0)
{
if (clientCmd.m_stateLoggingArguments.m_loggingUniqueId == m_data->m_logPlaybackUid)
{
if(m_data->m_logPlayback)
{
delete m_data->m_logPlayback;
m_data->m_logPlayback = 0;
m_data->m_logPlaybackUid = -1;
}
}
if (clientCmd.m_stateLoggingArguments.m_loggingUniqueId == m_data->m_commandLoggingUid)
{
if(m_data->m_commandLogger)
{
enableCommandLogging(false,0);
serverStatusOut.m_type = CMD_STATE_LOGGING_COMPLETED;
m_data->m_commandLoggingUid = -1;
}
}
if (clientCmd.m_stateLoggingArguments.m_loggingUniqueId == m_data->m_profileTimingLoggingUid)
{
serverStatusOut.m_type = CMD_STATE_LOGGING_COMPLETED;

View File

@@ -533,6 +533,8 @@ enum b3StateLoggingType
STATE_LOGGING_COMMANDS = 4,
STATE_LOGGING_CONTACT_POINTS = 5,
STATE_LOGGING_PROFILE_TIMINGS = 6,
STATE_LOGGING_ALL_COMMANDS=7,
STATE_REPLAY_ALL_COMMANDS=8,
};

View File

@@ -0,0 +1,15 @@
import pybullet as p
import time
p.connect(p.GUI)
logId = p.startStateLogging(p.STATE_LOGGING_ALL_COMMANDS,"commandLog.bin")
p.loadURDF("plane.urdf")
p.loadURDF("r2d2.urdf",[0,0,1])
p.stopStateLogging(logId)
p.resetSimulation();
logId = p.startStateLogging(p.STATE_REPLAY_ALL_COMMANDS,"commandLog.bin")
while(p.isConnected()):
time.sleep(1./240.)

View File

@@ -9576,6 +9576,8 @@ initpybullet(void)
PyModule_AddIntConstant(m, "STATE_LOGGING_VIDEO_MP4", STATE_LOGGING_VIDEO_MP4);
PyModule_AddIntConstant(m, "STATE_LOGGING_CONTACT_POINTS", STATE_LOGGING_CONTACT_POINTS);
PyModule_AddIntConstant(m, "STATE_LOGGING_PROFILE_TIMINGS", STATE_LOGGING_PROFILE_TIMINGS);
PyModule_AddIntConstant(m, "STATE_LOGGING_ALL_COMMANDS", STATE_LOGGING_ALL_COMMANDS);
PyModule_AddIntConstant(m, "STATE_REPLAY_ALL_COMMANDS", STATE_REPLAY_ALL_COMMANDS);
PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI);
PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS);