summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorerwincoumans <erwin.coumans@gmail.com>2018-06-12 16:56:45 -0700
committererwincoumans <erwin.coumans@gmail.com>2018-06-12 16:56:45 -0700
commit4d6741f5cd8c1c5f6511d38161480e5ddcc21744 (patch)
treeb570fcaeab6d3c324b0783aabbc3453ae45db8a9
parent459d07a302cae23febd752b4b2b1d0b2f28143ca (diff)
downloadbullet3-4d6741f5cd8c1c5f6511d38161480e5ddcc21744.tar.gz
PyBullet: expose STATE_LOGGING_ALL_COMMANDS and STATE_REPLAY_ALL_COMMANDS
See examples/pybullet/examples/commandLogAndPlayback.py for an example.
-rw-r--r--examples/SharedMemory/PhysicsServerCommandProcessor.cpp57
-rw-r--r--examples/SharedMemory/SharedMemoryPublic.h2
-rw-r--r--examples/pybullet/examples/commandLogAndPlayback.py15
-rw-r--r--examples/pybullet/pybullet.c4
4 files changed, 75 insertions, 3 deletions
diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
index 3f582d0f3..d10df0cdc 100644
--- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
+++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
@@ -1582,9 +1582,11 @@ 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;
btAlignedObjectArray<btMultiBodyJointFeedback*> m_multiBodyJointFeedbacks;
@@ -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;
diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h
index 25ba5128b..933d5b266 100644
--- a/examples/SharedMemory/SharedMemoryPublic.h
+++ b/examples/SharedMemory/SharedMemoryPublic.h
@@ -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,
};
diff --git a/examples/pybullet/examples/commandLogAndPlayback.py b/examples/pybullet/examples/commandLogAndPlayback.py
new file mode 100644
index 000000000..6cacda6b3
--- /dev/null
+++ b/examples/pybullet/examples/commandLogAndPlayback.py
@@ -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.)
+
diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c
index 7bb9cdfcf..5d027125d 100644
--- a/examples/pybullet/pybullet.c
+++ b/examples/pybullet/pybullet.c
@@ -9576,7 +9576,9 @@ 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);
PyModule_AddIntConstant(m, "COV_ENABLE_WIREFRAME", COV_ENABLE_WIREFRAME);