pybullet.ER_BULLET_HARDWARE_OPENGL and ER_TINY_RENDERER exposed (for getCameraImage, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)

improve performance of getCameraImage when using ER_BULLET_HARDWARE_OPENGL
This commit is contained in:
Erwin Coumans
2017-03-09 17:42:59 -08:00
parent 4ea9fa54bb
commit ca31bb2bbd
4 changed files with 58 additions and 32 deletions

View File

@@ -5380,6 +5380,10 @@ initpybullet(void)
PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI);
PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS);
PyModule_AddIntConstant(m, "COV_ENABLE_WIREFRAME", COV_ENABLE_WIREFRAME);
PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER);
PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL);
PyModule_AddIntConstant(m,"B3G_F1",B3G_F1);
PyModule_AddIntConstant(m,"B3G_F2",B3G_F2);
PyModule_AddIntConstant(m,"B3G_F3",B3G_F3);

View File

@@ -29,7 +29,8 @@ for pitch in range (0,360,10) :
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, lightDirection,lightColor)
#getCameraImage can also use renderer=pybullet.ER_BULLET_HARDWARE_OPENGL
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, lightDirection,lightColor,renderer=pybullet.ER_TINY_RENDERER)
w=img_arr[0]
h=img_arr[1]
rgb=img_arr[2]

View File

@@ -6,7 +6,7 @@ import matplotlib.pyplot as plt
import pybullet
import time
pybullet.connect(pybullet.DIRECT)
pybullet.connect(pybullet.GUI)
pybullet.loadURDF("r2d2.urdf")
camTargetPos = [0,0,0]
@@ -18,8 +18,8 @@ pitch = 10.0
roll=0
upAxisIndex = 2
camDistance = 4
pixelWidth = 1920
pixelHeight = 1080
pixelWidth = 1024
pixelHeight = 768
nearPlane = 0.01
farPlane = 1000
@@ -31,7 +31,7 @@ for pitch in range (0,360,10) :
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, [0,1,0])
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, [0,1,0],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
stop = time.time()
print ("renderImage %f" % (stop - start))
@@ -40,13 +40,12 @@ for pitch in range (0,360,10) :
rgb=img_arr[2] #color data RGB
dep=img_arr[3] #depth data
print 'width = %d height = %d' % (w,h)
print ('width = %d height = %d' % (w,h))
#note that sending the data to matplotlib is really slow
#show
plt.imshow(rgb,interpolation='none')
#plt.show()
plt.pause(0.01)
plt.imshow(rgb,interpolation='none')
plt.pause(0.001)
main_stop = time.time()