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:
15
examples/pybullet/examples/commandLogAndPlayback.py
Normal file
15
examples/pybullet/examples/commandLogAndPlayback.py
Normal 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.)
|
||||
|
||||
@@ -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);
|
||||
|
||||
Reference in New Issue
Block a user