mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 13:50:04 +00:00
Merge pull request #1456 from erwincoumans/master
pybullet: fix numpy compile issue on Windows, another fix
This commit is contained in:
commit
1c8d5cf964
@ -1,48 +1,70 @@
|
||||
import numpy as np
|
||||
import matplotlib.pyplot as plt
|
||||
import pybullet
|
||||
|
||||
pybullet.connect(pybullet.GUI)
|
||||
pybullet.loadURDF("plane.urdf")
|
||||
#testrender.py is a bit slower than testrender_np.py: pixels are copied from C to Python one by one
|
||||
|
||||
|
||||
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")
|
||||
|
||||
camTargetPos = [0.,0.,0.]
|
||||
pybullet.setGravity(0,0,-10)
|
||||
camTargetPos = [0,0,0]
|
||||
cameraUp = [0,0,1]
|
||||
cameraPos = [1,1,1]
|
||||
yaw = 40
|
||||
pitch = 10.0
|
||||
|
||||
pitch = -10.0
|
||||
|
||||
roll=0
|
||||
upAxisIndex = 2
|
||||
camDistance = 4
|
||||
pixelWidth = 320
|
||||
pixelHeight = 240
|
||||
pixelHeight = 200
|
||||
nearPlane = 0.01
|
||||
farPlane = 1000
|
||||
lightDirection = [0.4,0.4,0]
|
||||
lightColor = [.3,.3,.3]#1,1,1]#optional argument
|
||||
farPlane = 100
|
||||
|
||||
fov = 60
|
||||
|
||||
#img_arr = pybullet.renderImage(pixelWidth, pixelHeight)
|
||||
#renderImage(w, h, view[16], projection[16])
|
||||
#img_arr = pybullet.renderImage(pixelWidth, pixelHeight, cameraPos, camTargetPos, cameraUp, nearPlane, farPlane)
|
||||
for pitch in range (0,360,10) :
|
||||
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);
|
||||
#getCameraImage can also use 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)
|
||||
w=img_arr[0]
|
||||
h=img_arr[1]
|
||||
rgb=img_arr[2]
|
||||
dep=img_arr[3]
|
||||
#print 'width = %d height = %d' % (w,h)
|
||||
# reshape creates np array
|
||||
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')
|
||||
|
||||
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, shadow=1,lightDirection=[1,1,1],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
|
||||
stop = time.time()
|
||||
print ("renderImage %f" % (stop - start))
|
||||
|
||||
w=img_arr[0] #width of the image, in pixels
|
||||
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 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))
|
||||
|
||||
pybullet.resetSimulation()
|
||||
|
@ -1,37 +1,53 @@
|
||||
|
||||
#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 matplotlib.pyplot as plt
|
||||
import pybullet
|
||||
import time
|
||||
|
||||
pybullet.connect(pybullet.GUI)
|
||||
|
||||
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)
|
||||
pybullet.loadURDF("plane.urdf",[0,0,-1])
|
||||
pybullet.loadURDF("r2d2.urdf")
|
||||
|
||||
camTargetPos = [0,0,0]
|
||||
cameraUp = [0,0,1]
|
||||
cameraPos = [1,1,1]
|
||||
yaw = 40
|
||||
pitch = 10.0
|
||||
pybullet.setGravity(0,0,-10)
|
||||
|
||||
pitch = -10.0
|
||||
|
||||
roll=0
|
||||
upAxisIndex = 2
|
||||
camDistance = 4
|
||||
pixelWidth = 1024
|
||||
pixelHeight = 768
|
||||
pixelWidth = 320
|
||||
pixelHeight = 200
|
||||
nearPlane = 0.01
|
||||
farPlane = 1000
|
||||
farPlane = 100
|
||||
|
||||
fov = 60
|
||||
|
||||
main_start = time.time()
|
||||
for pitch 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;
|
||||
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()
|
||||
print ("renderImage %f" % (stop - start))
|
||||
|
||||
@ -44,8 +60,21 @@ for pitch in range (0,360,10) :
|
||||
|
||||
#note that sending the data to matplotlib is really slow
|
||||
|
||||
plt.imshow(rgb,interpolation='none')
|
||||
plt.pause(0.001)
|
||||
#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 = 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()
|
||||
|
||||
|
@ -5987,7 +5987,7 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType == CMD_CAMERA_IMAGE_COMPLETED)
|
||||
{
|
||||
PyObject* item2;
|
||||
|
||||
PyObject* pyResultList; // store 4 elements in this result: width,
|
||||
// height, rgbData, depth
|
||||
|
||||
@ -5996,13 +5996,12 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
||||
PyObject* pyDep;
|
||||
PyObject* pySeg;
|
||||
|
||||
int i, j, p;
|
||||
int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values
|
||||
|
||||
|
||||
b3GetCameraImageData(sm, &imageData);
|
||||
// TODO(hellojas): error handling if image size is 0
|
||||
|
||||
{
|
||||
npy_intp rgb_dims[3] = {imageData.m_pixelHeight, imageData.m_pixelWidth,
|
||||
bytesPerPixel};
|
||||
npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth};
|
||||
@ -6027,7 +6026,9 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
||||
PyTuple_SetItem(pyResultList, 2, pyRGB);
|
||||
PyTuple_SetItem(pyResultList, 3, pyDep);
|
||||
PyTuple_SetItem(pyResultList, 4, pySeg);
|
||||
}
|
||||
#else //PYBULLET_USE_NUMPY
|
||||
PyObject* item2;
|
||||
PyObject* pylistRGB;
|
||||
PyObject* pylistDep;
|
||||
PyObject* pylistSeg;
|
||||
@ -6417,7 +6418,7 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args)
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType == CMD_CAMERA_IMAGE_COMPLETED)
|
||||
{
|
||||
PyObject* item2;
|
||||
|
||||
PyObject* pyResultList; // store 4 elements in this result: width,
|
||||
// height, rgbData, depth
|
||||
|
||||
@ -6426,7 +6427,7 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args)
|
||||
PyObject* pyDep;
|
||||
PyObject* pySeg;
|
||||
|
||||
int i, j, p;
|
||||
|
||||
int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values
|
||||
|
||||
b3GetCameraImageData(sm, &imageData);
|
||||
@ -6434,7 +6435,7 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args)
|
||||
pyResultList = PyTuple_New(5);
|
||||
PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth));
|
||||
PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight));
|
||||
|
||||
{
|
||||
npy_intp rgb_dims[3] = {imageData.m_pixelHeight, imageData.m_pixelWidth,
|
||||
bytesPerPixel};
|
||||
npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth};
|
||||
@ -6454,7 +6455,9 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args)
|
||||
PyTuple_SetItem(pyResultList, 2, pyRGB);
|
||||
PyTuple_SetItem(pyResultList, 3, pyDep);
|
||||
PyTuple_SetItem(pyResultList, 4, pySeg);
|
||||
}
|
||||
#else //PYBULLET_USE_NUMPY
|
||||
PyObject* item2;
|
||||
PyObject* pylistRGB;
|
||||
PyObject* pylistDep;
|
||||
PyObject* pylistSeg;
|
||||
|
2
setup.py
2
setup.py
@ -442,7 +442,7 @@ print("-----")
|
||||
|
||||
setup(
|
||||
name = 'pybullet',
|
||||
version='1.7.2',
|
||||
version='1.7.3',
|
||||
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
|
||||
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
|
||||
url='https://github.com/bulletphysics/bullet3',
|
||||
|
Loading…
Reference in New Issue
Block a user