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

@@ -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.)