summaryrefslogtreecommitdiff
path: root/examples/pybullet/examples/rendertest.py
blob: 6e3d14b89ee62dfd952f80a86401e931414dfffc (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
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
#make sure to compile pybullet with PYBULLET_USE_NUMPY enabled
#otherwise use testrender.py (slower but compatible without numpy)
#you can also use GUI mode, for faster OpenGL rendering (instead of TinyRender CPU)

import os
import sys
import time
import itertools
import subprocess
import numpy as np
import pybullet
from multiprocessing import Process

camTargetPos = [0, 0, 0]
cameraUp = [0, 0, 1]
cameraPos = [1, 1, 1]

pitch = -10.0
roll = 0
upAxisIndex = 2
camDistance = 4
pixelWidth = 84  # 320
pixelHeight = 84  # 200
nearPlane = 0.01
farPlane = 100
fov = 60

import matplotlib.pyplot as plt


class BulletSim():

  def __init__(self, connection_mode, *argv):
    self.connection_mode = connection_mode
    self.argv = argv

  def __enter__(self):
    print("connecting")
    optionstring = '--width={} --height={}'.format(pixelWidth, pixelHeight)
    optionstring += ' --window_backend=2 --render_device=0'

    print(self.connection_mode, optionstring, *self.argv)
    cid = pybullet.connect(self.connection_mode, options=optionstring, *self.argv)
    if cid < 0:
      raise ValueError
    print("connected")
    pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_GUI, 0)
    pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_SEGMENTATION_MARK_PREVIEW, 0)
    pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_DEPTH_BUFFER_PREVIEW, 0)
    pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_RGB_BUFFER_PREVIEW, 0)

    pybullet.resetSimulation()
    pybullet.loadURDF("plane.urdf", [0, 0, -1])
    pybullet.loadURDF("r2d2.urdf")
    pybullet.loadURDF("duck_vhacd.urdf")
    pybullet.setGravity(0, 0, -10)

  def __exit__(self, *_, **__):
    pybullet.disconnect()


def test(num_runs=300, shadow=1, log=True, plot=False):
  if log:
    logId = pybullet.startStateLogging(pybullet.STATE_LOGGING_PROFILE_TIMINGS, "renderTimings")

  if plot:
    plt.ion()

    img = np.random.rand(200, 320)
    #img = [tandard_normal((50,100))
    image = plt.imshow(img, interpolation='none', animated=True, label="blah")
    ax = plt.gca()

  times = np.zeros(num_runs)
  yaw_gen = itertools.cycle(range(0, 360, 10))
  for i, yaw in zip(range(num_runs), yaw_gen):
    pybullet.stepSimulation()
    start = time.time()
    viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch,
                                                            roll, upAxisIndex)
    aspect = pixelWidth / pixelHeight
    projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane)
    img_arr = pybullet.getCameraImage(pixelWidth,
                                      pixelHeight,
                                      viewMatrix,
                                      projectionMatrix,
                                      shadow=shadow,
                                      lightDirection=[1, 1, 1],
                                      renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
    #renderer=pybullet.ER_TINY_RENDERER)
    stop = time.time()
    duration = (stop - start)
    if (duration):
      fps = 1. / duration
      #print("fps=",fps)
    else:
      fps = 0
      #print("fps=",fps)
    #print("duraction=",duration)
    #print("fps=",fps)
    times[i] = fps

    if plot:
      rgb = img_arr[2]
      image.set_data(rgb)  #np_img_arr)
      ax.plot([0])
      #plt.draw()
      #plt.show()
      plt.pause(0.01)

  mean_time = float(np.mean(times))
  print("mean: {0} for {1} runs".format(mean_time, num_runs))
  print("")
  if log:
    pybullet.stopStateLogging(logId)
  return mean_time


if __name__ == "__main__":

  res = []

  with BulletSim(pybullet.DIRECT):
    print("\nTesting DIRECT")
    mean_time = test(log=False, plot=True)
    res.append(("tiny", mean_time))

  with BulletSim(pybullet.DIRECT):
    plugin_fn = os.path.join(
        pybullet.__file__.split("bullet3")[0],
        "bullet3/build/lib.linux-x86_64-3.5/eglRenderer.cpython-35m-x86_64-linux-gnu.so")
    plugin = pybullet.loadPlugin(plugin_fn, "_tinyRendererPlugin")
    if plugin < 0:
      print("\nPlugin Failed to load!\n")
      sys.exit()

    print("\nTesting DIRECT+OpenGL")
    mean_time = test(log=True)
    res.append(("plugin", mean_time))

  with BulletSim(pybullet.GUI):
    print("\nTesting GUI")
    mean_time = test(log=False)
    res.append(("egl", mean_time))

  print()
  print("rendertest.py")
  print("back nenv fps fps_tot")
  for r in res:
    print(r[0], "\t", 1, round(r[1]), "\t", round(r[1]))