summaryrefslogtreecommitdiff
path: root/examples/pybullet/examples/loadingBench.py
blob: 38a12e12deaac3b44cd5239913d6d406809360ca (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
import pybullet as p
import time
p.connect(p.GUI)

p.resetSimulation()
timinglog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "loadingBenchVR.json")
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
print("load plane.urdf")
p.loadURDF("plane.urdf")
print("load r2d2.urdf")

p.loadURDF("r2d2.urdf", 0, 0, 1)
print("load kitchen/1.sdf")
p.loadSDF("kitchens/1.sdf")
print("load 100 times plate.urdf")
for i in range(100):
  p.loadURDF("dinnerware/plate.urdf", 0, i, 1)

p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)

p.stopStateLogging(timinglog)
print("stopped state logging")
p.getCameraImage(320, 200)

while (1):
  p.stepSimulation()