initial implementation of state logging.
see examples/pybullet/logMinitaur.py for example. Other state logging will include general robot states and VR controllers state.
This commit is contained in:
15
examples/pybullet/logMinitaur.py
Normal file
15
examples/pybullet/logMinitaur.py
Normal file
@@ -0,0 +1,15 @@
|
||||
import pybullet as p
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid < 0) :
|
||||
p.connect(p.GUI)
|
||||
p.loadURDF("plane.urdf")
|
||||
|
||||
quadruped = p.loadURDF("quadruped/quadruped.urdf")
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_MINITAUR,"LOG00048.TXT",[quadruped])
|
||||
p.stepSimulation()
|
||||
p.stepSimulation()
|
||||
p.stepSimulation()
|
||||
p.stepSimulation()
|
||||
p.stepSimulation()
|
||||
|
||||
p.stopStateLogging(logId)
|
||||
Reference in New Issue
Block a user