add one more pybullet renderImage API and testrender.py example

tweak Bullet Inverse Dynamics, work-around compiler issue
This commit is contained in:
Erwin Coumans
2016-08-02 11:12:23 -07:00
parent 7d76183e13
commit f304fd7611
5 changed files with 139 additions and 4 deletions

View File

@@ -1041,6 +1041,8 @@ static int pybullet_internalSetVector(PyObject* objMat, float vector[3])
// renderImage(w, h, cameraPos, targetPos, cameraUp, nearVal, farVal, fov) -
// set resolution and initialize camera based on camera position, target
// position, camera up, fulstrum near/far values and camera field of view.
// renderImage(w, h, targetPos, distance, yaw, pitch, upAxisIndex, nearVal, farVal, fov)
//
// Note if the (w,h) is too small, the objects may not appear based on
// where the camera has been set
@@ -1151,6 +1153,35 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args)
aspect = width/height;
b3RequestCameraImageSetFOVProjectionMatrix(command, fov, aspect, nearVal, farVal);
}
}
else if (size==10)
{
int upAxisIndex=1;
float camDistance,yaw,pitch;
//sometimes more arguments are better :-)
if (PyArg_ParseTuple(args, "iiOfffifff", &width, &height, &objTargetPos, &camDistance, &yaw, &pitch, &upAxisIndex, &nearVal, &farVal, &fov))
{
if (pybullet_internalSetVector(objTargetPos, targetPos))
{
printf("width = %d, height = %d, targetPos = %f,%f,%f, distance = %f, yaw = %f, pitch = %f, upAxisIndex = %d, near=%f, far=%f, fov=%f\n",width,height,targetPos[0],targetPos[1],targetPos[2],camDistance,yaw,pitch,upAxisIndex,nearVal,farVal,fov);
b3RequestCameraImageSetViewMatrix2(command,targetPos,camDistance,yaw,pitch,upAxisIndex);
aspect = width/height;
b3RequestCameraImageSetFOVProjectionMatrix(command, fov, aspect, nearVal, farVal);
} else
{
PyErr_SetString(SpamError, "Error parsing camera target pos");
}
} else
{
PyErr_SetString(SpamError, "Error parsing arguments");
}
}
else
{

View File

@@ -0,0 +1,40 @@
import numpy as np
import matplotlib.pyplot as plt
import pybullet
pybullet.connect(pybullet.GUI)
pybullet.loadURDF("r2d2.urdf")
camTargetPos = [0,0,0]
#cameraUp = [0,0,1]
cameraPos = [3,3,3]
yaw = 40.0
pitch = 0.0
upAxisIndex = 1
camDistance = 3
pixelWidth = 640
pixelHeight = 480
nearPlane = 0.01
farPlane = 1000
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)
img_arr = pybullet.renderImage(pixelWidth, pixelHeight, camTargetPos, camDistance, yaw, pitch, upAxisIndex, nearPlane, farPlane, fov)
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
# reshape creates np array
np_img_arr = np.reshape(rgb, (pixelHeight, pixelWidth, 4))
np_img_arr = np_img_arr*(1./255.)
#show
plt.imshow(np_img_arr,interpolation='none')
plt.show()
p.resetSimulation()