pybullet testrender.py/testrender_np.py examples, improve matplotlib rendering performance (headless DIRECT and OpenGL/GUI)
This commit is contained in:
@@ -1,48 +1,56 @@
|
|||||||
import numpy as np
|
|
||||||
import matplotlib.pyplot as plt
|
|
||||||
import pybullet
|
|
||||||
|
|
||||||
pybullet.connect(pybullet.GUI)
|
#testrender.py is a bit slower than testrender_np.py: pixels are copied from C to Python one by one
|
||||||
pybullet.loadURDF("plane.urdf")
|
|
||||||
|
|
||||||
|
import matplotlib.pyplot as plt
|
||||||
|
import pybullet
|
||||||
|
import time
|
||||||
|
|
||||||
|
pybullet.connect(pybullet.DIRECT)
|
||||||
|
pybullet.loadURDF("plane.urdf",[0,0,-1])
|
||||||
pybullet.loadURDF("r2d2.urdf")
|
pybullet.loadURDF("r2d2.urdf")
|
||||||
|
|
||||||
camTargetPos = [0.,0.,0.]
|
camTargetPos = [0,0,0]
|
||||||
cameraUp = [0,0,1]
|
cameraUp = [0,0,1]
|
||||||
cameraPos = [1,1,1]
|
cameraPos = [1,1,1]
|
||||||
yaw = 40
|
|
||||||
pitch = 10.0
|
pitch = -10.0
|
||||||
|
|
||||||
roll=0
|
roll=0
|
||||||
upAxisIndex = 2
|
upAxisIndex = 2
|
||||||
camDistance = 4
|
camDistance = 4
|
||||||
pixelWidth = 320
|
pixelWidth = 320
|
||||||
pixelHeight = 240
|
pixelHeight = 200
|
||||||
nearPlane = 0.01
|
nearPlane = 0.01
|
||||||
farPlane = 1000
|
farPlane = 100
|
||||||
lightDirection = [0.4,0.4,0]
|
|
||||||
lightColor = [.3,.3,.3]#1,1,1]#optional argument
|
|
||||||
fov = 60
|
fov = 60
|
||||||
|
|
||||||
#img_arr = pybullet.renderImage(pixelWidth, pixelHeight)
|
main_start = time.time()
|
||||||
#renderImage(w, h, view[16], projection[16])
|
for yaw in range (0,360,10) :
|
||||||
#img_arr = pybullet.renderImage(pixelWidth, pixelHeight, cameraPos, camTargetPos, cameraUp, nearPlane, farPlane)
|
start = time.time()
|
||||||
for pitch in range (0,360,10) :
|
|
||||||
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
|
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
|
||||||
aspect = pixelWidth / pixelHeight;
|
aspect = pixelWidth / pixelHeight;
|
||||||
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
|
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
|
||||||
#getCameraImage can also use renderer=pybullet.ER_BULLET_HARDWARE_OPENGL
|
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, shadow=1,lightDirection=[1,1,1],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
|
||||||
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, lightAmbientCoeff = 0.3, lightDiffuseCoeff = 0.4, shadow=1, renderer=pybullet.ER_TINY_RENDERER)
|
stop = time.time()
|
||||||
w=img_arr[0]
|
print ("renderImage %f" % (stop - start))
|
||||||
h=img_arr[1]
|
|
||||||
rgb=img_arr[2]
|
w=img_arr[0] #width of the image, in pixels
|
||||||
dep=img_arr[3]
|
h=img_arr[1] #height of the image, in pixels
|
||||||
#print 'width = %d height = %d' % (w,h)
|
rgb=img_arr[2] #color data RGB
|
||||||
# reshape creates np array
|
dep=img_arr[3] #depth data
|
||||||
np_img_arr = np.reshape(rgb, (h, w, 4))
|
|
||||||
np_img_arr = np_img_arr*(1./255.)
|
print ('width = %d height = %d' % (w,h))
|
||||||
#show
|
|
||||||
plt.imshow(np_img_arr,interpolation='none')
|
#note that sending the data to matplotlib is really slow
|
||||||
|
|
||||||
plt.pause(0.01)
|
plt.imshow(rgb,interpolation='none')
|
||||||
|
plt.show(block=False)
|
||||||
|
plt.pause(0.001)
|
||||||
|
|
||||||
|
main_stop = time.time()
|
||||||
|
|
||||||
|
print ("Total time %f" % (main_stop - main_start))
|
||||||
|
|
||||||
pybullet.resetSimulation()
|
pybullet.resetSimulation()
|
||||||
|
|||||||
@@ -1,37 +1,48 @@
|
|||||||
|
|
||||||
#make sure to compile pybullet with PYBULLET_USE_NUMPY enabled, otherwise use testrender.py (slower but compatible without numpy)
|
#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 numpy as np
|
import numpy as np
|
||||||
import matplotlib.pyplot as plt
|
import matplotlib.pyplot as plt
|
||||||
import pybullet
|
import pybullet
|
||||||
import time
|
import time
|
||||||
|
from pylab import *
|
||||||
|
|
||||||
pybullet.connect(pybullet.GUI)
|
ion()
|
||||||
|
img = standard_normal((50,100))
|
||||||
|
image = imshow(img,interpolation='none',animated=True,label="blah")
|
||||||
|
|
||||||
|
|
||||||
|
#pybullet.connect(pybullet.GUI)
|
||||||
|
pybullet.connect(pybullet.DIRECT)
|
||||||
|
pybullet.loadURDF("plane.urdf",[0,0,-1])
|
||||||
pybullet.loadURDF("r2d2.urdf")
|
pybullet.loadURDF("r2d2.urdf")
|
||||||
|
|
||||||
camTargetPos = [0,0,0]
|
camTargetPos = [0,0,0]
|
||||||
cameraUp = [0,0,1]
|
cameraUp = [0,0,1]
|
||||||
cameraPos = [1,1,1]
|
cameraPos = [1,1,1]
|
||||||
yaw = 40
|
|
||||||
pitch = 10.0
|
pitch = -10.0
|
||||||
|
|
||||||
roll=0
|
roll=0
|
||||||
upAxisIndex = 2
|
upAxisIndex = 2
|
||||||
camDistance = 4
|
camDistance = 4
|
||||||
pixelWidth = 1024
|
pixelWidth = 320
|
||||||
pixelHeight = 768
|
pixelHeight = 200
|
||||||
nearPlane = 0.01
|
nearPlane = 0.01
|
||||||
farPlane = 1000
|
farPlane = 100
|
||||||
|
|
||||||
fov = 60
|
fov = 60
|
||||||
|
|
||||||
main_start = time.time()
|
main_start = time.time()
|
||||||
for pitch in range (0,360,10) :
|
while (1):
|
||||||
|
for yaw in range (0,360,10):
|
||||||
start = time.time()
|
start = time.time()
|
||||||
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
|
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
|
||||||
aspect = pixelWidth / pixelHeight;
|
aspect = pixelWidth / pixelHeight;
|
||||||
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
|
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
|
||||||
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, [0,1,0],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
|
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, shadow=1,lightDirection=[1,1,1],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
|
||||||
stop = time.time()
|
stop = time.time()
|
||||||
print ("renderImage %f" % (stop - start))
|
print ("renderImage %f" % (stop - start))
|
||||||
|
|
||||||
@@ -44,8 +55,13 @@ for pitch in range (0,360,10) :
|
|||||||
|
|
||||||
#note that sending the data to matplotlib is really slow
|
#note that sending the data to matplotlib is really slow
|
||||||
|
|
||||||
plt.imshow(rgb,interpolation='none')
|
np_img_arr = np.reshape(rgb, (h, w, 4))
|
||||||
plt.pause(0.001)
|
np_img_arr = np_img_arr*(1./255.)
|
||||||
|
#show
|
||||||
|
#plt.imshow(np_img_arr,interpolation='none',extent=(0,1600,0,1200))
|
||||||
|
image.set_data(np_img_arr)
|
||||||
|
#draw()
|
||||||
|
plt.pause(0.0001)
|
||||||
|
|
||||||
main_stop = time.time()
|
main_stop = time.time()
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user