improve testrender/np to render faster/interactive on Mac with matplotlib

This commit is contained in:
Erwin Coumans
2017-11-24 18:57:16 -08:00
parent 2e247fb406
commit 6baf82d6d8
2 changed files with 43 additions and 16 deletions

View File

@@ -6,10 +6,19 @@ import matplotlib.pyplot as plt
import pybullet
import time
plt.ion()
img = [[1,2,3]*50]*100#np.random.rand(200, 320)
#img = [tandard_normal((50,100))
image = plt.imshow(img,interpolation='none',animated=True,label="blah")
ax = plt.gca()
pybullet.connect(pybullet.DIRECT)
pybullet.loadURDF("plane.urdf",[0,0,-1])
pybullet.loadURDF("r2d2.urdf")
pybullet.setGravity(0,0,-10)
camTargetPos = [0,0,0]
cameraUp = [0,0,1]
cameraPos = [1,1,1]
@@ -27,7 +36,9 @@ farPlane = 100
fov = 60
main_start = time.time()
for yaw in range (0,360,10) :
while(1):
for yaw in range (0,360,10) :
pybullet.stepSimulation()
start = time.time()
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
aspect = pixelWidth / pixelHeight;
@@ -40,15 +51,18 @@ for yaw in range (0,360,10) :
h=img_arr[1] #height of the image, in pixels
rgb=img_arr[2] #color data RGB
dep=img_arr[3] #depth data
#print(rgb)
print ('width = %d height = %d' % (w,h))
#note that sending the data to matplotlib is really slow
plt.imshow(rgb,interpolation='none')
plt.show(block=False)
plt.pause(0.001)
#note that sending the data using imshow to matplotlib is really slow, so we use set_data
#plt.imshow(rgb,interpolation='none')
image.set_data(rgb)
ax.plot([0])
#plt.draw()
#plt.show()
plt.pause(0.01)
main_stop = time.time()
print ("Total time %f" % (main_stop - main_start))

View File

@@ -7,12 +7,14 @@ import numpy as np
import matplotlib.pyplot as plt
import pybullet
import time
from pylab import *
ion()
img = standard_normal((50,100))
image = imshow(img,interpolation='none',animated=True,label="blah")
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()
#pybullet.connect(pybullet.GUI)
pybullet.connect(pybullet.DIRECT)
@@ -22,6 +24,7 @@ pybullet.loadURDF("r2d2.urdf")
camTargetPos = [0,0,0]
cameraUp = [0,0,1]
cameraPos = [1,1,1]
pybullet.setGravity(0,0,-10)
pitch = -10.0
@@ -38,7 +41,9 @@ fov = 60
main_start = time.time()
while (1):
for yaw in range (0,360,10):
pybullet.stepSimulation()
start = time.time()
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
aspect = pixelWidth / pixelHeight;
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
@@ -55,13 +60,21 @@ while (1):
#note that sending the data to matplotlib is really slow
np_img_arr = np.reshape(rgb, (h, w, 4))
np_img_arr = np_img_arr*(1./255.)
#reshape is not needed
#np_img_arr = np.reshape(rgb, (h, w, 4))
#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)
#image = plt.imshow(np_img_arr,interpolation='none',animated=True,label="blah")
image.set_data(rgb)#np_img_arr)
ax.plot([0])
#plt.draw()
#plt.show()
plt.pause(0.01)
#image.draw()
main_stop = time.time()