summaryrefslogtreecommitdiff
path: root/examples/pybullet/examples/logMinitaur.py
blob: b995ee8f7de69495e195da1fda1b5cf2f03e9719 (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
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)