add pybullet render API with yaw/pitch/roll option

add testrender.py file
allow option to enable OpenGL hardware renderer in multithreaded sim

b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL);
This commit is contained in:
Erwin Coumans
2016-08-08 14:23:44 -07:00
parent f5fca86d49
commit b880ddf76b
11 changed files with 219 additions and 81 deletions

View File

@@ -2,6 +2,6 @@
rm CMakeCache.txt rm CMakeCache.txt
mkdir build_cmake mkdir build_cmake
cd build_cmake cd build_cmake
cmake -DBUILD_PYTHON=OFF -CMAKE_BUILD_TYPE=Release .. cmake -DBUILD_PYBULLET=OFF -DCMAKE_BUILD_TYPE=Release ..
make -j12 make -j12
examples/ExampleBrowser/App_ExampleBrowser examples/ExampleBrowser/App_ExampleBrowser

View File

@@ -520,7 +520,7 @@ void MyStatusBarError(const char* msg)
gui2->textOutput(msg); gui2->textOutput(msg);
gui2->forceUpdateScrollBars(); gui2->forceUpdateScrollBars();
} }
btAssert(0); btAssert(0);
} }

View File

@@ -47,6 +47,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
eRobotSimGUIHelperCreateCollisionShapeGraphicsObject, eRobotSimGUIHelperCreateCollisionShapeGraphicsObject,
eRobotSimGUIHelperCreateCollisionObjectGraphicsObject, eRobotSimGUIHelperCreateCollisionObjectGraphicsObject,
eRobotSimGUIHelperRemoveAllGraphicsInstances, eRobotSimGUIHelperRemoveAllGraphicsInstances,
eRobotSimGUIHelperCopyCameraImageData,
}; };
#include <stdio.h> #include <stdio.h>
@@ -152,7 +153,7 @@ void* RobotlsMemoryFunc()
ATTRIBUTE_ALIGNED16(class) MultiThreadedOpenGLGuiHelper : public GUIHelperInterface ATTRIBUTE_ALIGNED16(class) MultiThreadedOpenGLGuiHelper2 : public GUIHelperInterface
{ {
CommonGraphicsApp* m_app; CommonGraphicsApp* m_app;
@@ -185,7 +186,7 @@ public:
int m_instanceId; int m_instanceId;
MultiThreadedOpenGLGuiHelper(CommonGraphicsApp* app, GUIHelperInterface* guiHelper) MultiThreadedOpenGLGuiHelper2(CommonGraphicsApp* app, GUIHelperInterface* guiHelper)
:m_app(app) :m_app(app)
,m_cs(0), ,m_cs(0),
m_texels(0), m_texels(0),
@@ -195,7 +196,7 @@ public:
} }
virtual ~MultiThreadedOpenGLGuiHelper() virtual ~MultiThreadedOpenGLGuiHelper2()
{ {
delete m_childGuiHelper; delete m_childGuiHelper;
} }
@@ -345,10 +346,39 @@ public:
{ {
} }
float m_viewMatrix[16];
float m_projectionMatrix[16];
unsigned char* m_pixelsRGBA;
int m_rgbaBufferSizeInPixels;
float* m_depthBuffer;
int m_depthBufferSizeInPixels;
int m_startPixelIndex;
int m_destinationWidth;
int m_destinationHeight;
int* m_numPixelsCopied;
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied) virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied)
{ {
if (numPixelsCopied) m_cs->lock();
*numPixelsCopied = 0; for (int i=0;i<16;i++)
{
m_viewMatrix[i] = viewMatrix[i];
m_projectionMatrix[i] = projectionMatrix[i];
}
m_pixelsRGBA = pixelsRGBA;
m_rgbaBufferSizeInPixels = rgbaBufferSizeInPixels;
m_depthBuffer = depthBuffer;
m_depthBufferSizeInPixels = depthBufferSizeInPixels;
m_startPixelIndex = startPixelIndex;
m_destinationWidth = destinationWidth;
m_destinationHeight = destinationHeight;
m_numPixelsCopied = numPixelsCopied;
m_cs->setSharedParam(1,eRobotSimGUIHelperCopyCameraImageData);
m_cs->unlock();
while (m_cs->getSharedParam(1)!=eRobotSimGUIHelperIdle)
{
}
} }
virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld)
@@ -375,7 +405,7 @@ struct b3RobotSimAPI_InternalData
b3ThreadSupportInterface* m_threadSupport; b3ThreadSupportInterface* m_threadSupport;
RobotSimArgs m_args[MAX_ROBOT_NUM_THREADS]; RobotSimArgs m_args[MAX_ROBOT_NUM_THREADS];
MultiThreadedOpenGLGuiHelper* m_multiThreadedHelper; MultiThreadedOpenGLGuiHelper2* m_multiThreadedHelper;
bool m_connected; bool m_connected;
@@ -494,6 +524,24 @@ void b3RobotSimAPI::processMultiThreadedGraphicsRequests()
m_data->m_multiThreadedHelper->getCriticalSection()->unlock(); m_data->m_multiThreadedHelper->getCriticalSection()->unlock();
break; break;
} }
case eRobotSimGUIHelperCopyCameraImageData:
{
m_data->m_multiThreadedHelper->m_childGuiHelper->copyCameraImageData(m_data->m_multiThreadedHelper->m_viewMatrix,
m_data->m_multiThreadedHelper->m_projectionMatrix,
m_data->m_multiThreadedHelper->m_pixelsRGBA,
m_data->m_multiThreadedHelper->m_rgbaBufferSizeInPixels,
m_data->m_multiThreadedHelper->m_depthBuffer,
m_data->m_multiThreadedHelper->m_depthBufferSizeInPixels,
m_data->m_multiThreadedHelper->m_startPixelIndex,
m_data->m_multiThreadedHelper->m_destinationWidth,
m_data->m_multiThreadedHelper->m_destinationHeight,
m_data->m_multiThreadedHelper->m_numPixelsCopied);
m_data->m_multiThreadedHelper->getCriticalSection()->lock();
m_data->m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eRobotSimGUIHelperIdle);
m_data->m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eRobotSimGUIHelperIdle: case eRobotSimGUIHelperIdle:
default: default:
{ {
@@ -669,9 +717,9 @@ bool b3RobotSimAPI::loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotS
bool b3RobotSimAPI::connect(GUIHelperInterface* guiHelper) bool b3RobotSimAPI::connect(GUIHelperInterface* guiHelper)
{ {
m_data->m_multiThreadedHelper = new MultiThreadedOpenGLGuiHelper(guiHelper->getAppInterface(),guiHelper); m_data->m_multiThreadedHelper = new MultiThreadedOpenGLGuiHelper2(guiHelper->getAppInterface(),guiHelper);
MultiThreadedOpenGLGuiHelper* guiHelperWrapper = new MultiThreadedOpenGLGuiHelper(guiHelper->getAppInterface(),guiHelper); MultiThreadedOpenGLGuiHelper2* guiHelperWrapper = new MultiThreadedOpenGLGuiHelper2(guiHelper->getAppInterface(),guiHelper);

View File

@@ -825,7 +825,7 @@ void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHa
command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES;
} }
void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, int upAxis) void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis)
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command); b3Assert(command);
@@ -834,47 +834,78 @@ void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandl
b3Vector3 camForward; b3Vector3 camForward;
b3Vector3 camPos; b3Vector3 camPos;
b3Vector3 camTargetPos = b3MakeVector3(cameraTargetPosition[0],cameraTargetPosition[1],cameraTargetPosition[2]); b3Vector3 camTargetPos = b3MakeVector3(cameraTargetPosition[0],cameraTargetPosition[1],cameraTargetPosition[2]);
b3Vector3 eyePos = b3MakeVector3(0,0,0);
int forwardAxis(-1); int forwardAxis(-1);
{
switch (upAxis) switch (upAxis)
{ {
case 1:
forwardAxis = 2; case 1:
camUpVector = b3MakeVector3(0,1,0); {
//gLightPos = b3MakeVector3(-50.f,100,30);
break;
case 2: forwardAxis = 0;
forwardAxis = 1; eyePos[forwardAxis] = -distance;
camUpVector = b3MakeVector3(0,0,1); camForward = b3MakeVector3(eyePos[0],eyePos[1],eyePos[2]);
//gLightPos = b3MakeVector3(-50.f,30,100); if (camForward.length2() < B3_EPSILON)
break; {
default: camForward.setValue(1.f,0.f,0.f);
{ } else
//b3Assert(0); {
return; camForward.normalize();
} }
}; b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547);
b3Quaternion rollRot(camForward,rollRad);
b3Vector3 eyePos = b3MakeVector3(0,0,0);
eyePos[forwardAxis] = -distance; camUpVector = b3QuatRotate(rollRot,b3MakeVector3(0,1,0));
//gLightPos = b3MakeVector3(-50.f,100,30);
camForward = b3MakeVector3(eyePos[0],eyePos[1],eyePos[2]); break;
if (camForward.length2() < B3_EPSILON) }
{ case 2:
camForward.setValue(1.f,0.f,0.f); {
} else
{
camForward.normalize(); forwardAxis = 1;
eyePos[forwardAxis] = -distance;
camForward = b3MakeVector3(eyePos[0],eyePos[1],eyePos[2]);
if (camForward.length2() < B3_EPSILON)
{
camForward.setValue(1.f,0.f,0.f);
} else
{
camForward.normalize();
}
b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547);
b3Quaternion rollRot(camForward,rollRad);
camUpVector = b3QuatRotate(rollRot,b3MakeVector3(0,0,1));
//gLightPos = b3MakeVector3(-50.f,30,100);
break;
}
default:
{
//b3Assert(0);
return;
}
};
} }
b3Scalar rele = yaw * b3Scalar(0.01745329251994329547);// rads per deg b3Scalar yawRad = yaw * b3Scalar(0.01745329251994329547);// rads per deg
b3Scalar razi = pitch * b3Scalar(0.01745329251994329547);// rads per deg b3Scalar pitchRad = pitch * b3Scalar(0.01745329251994329547);// rads per deg
b3Quaternion rot(camUpVector,razi);
b3Quaternion pitchRot(camUpVector,pitchRad);
b3Vector3 right = camUpVector.cross(camForward); b3Vector3 right = camUpVector.cross(camForward);
b3Quaternion roll(right,-rele); b3Quaternion yawRot(right,-yawRad);
eyePos = b3Matrix3x3(rot) * b3Matrix3x3(roll) * eyePos; eyePos = b3Matrix3x3(pitchRot) * b3Matrix3x3(yawRot) * eyePos;
camPos = eyePos; camPos = eyePos;
camPos += camTargetPos; camPos += camTargetPos;

View File

@@ -71,7 +71,7 @@ void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* l
b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient); b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient);
void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]); void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]);
void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle command, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]); void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle command, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]);
void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, int upAxis); void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis);
void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle command, float left, float right, float bottom, float top, float nearVal, float farVal); void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle command, float left, float right, float bottom, float top, float nearVal, float farVal);
void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle command, float fov, float aspect, float nearVal, float farVal); void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle command, float fov, float aspect, float nearVal, float farVal);
void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height ); void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height );

View File

@@ -259,15 +259,15 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle); b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle);
//b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL); //b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL);
float viewMatrix[16]; float viewMatrix[16];
float projectionMatrix[16]; float projectionMatrix[16];
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix); m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix); m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix);
b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix); b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix);
b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight); b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight);
b3SubmitClientCommand(m_physicsClientHandle, commandHandle); b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
break; break;
} }
case CMD_CREATE_BOX_COLLISION_SHAPE: case CMD_CREATE_BOX_COLLISION_SHAPE:
{ {

View File

@@ -609,7 +609,7 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
{ {
SharedMemoryCommand& command = m_data->m_testBlock1->m_clientCommands[0]; SharedMemoryCommand& command = m_data->m_testBlock1->m_clientCommands[0];
if (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0) if (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0 && serverCmd.m_sendPixelDataArguments.m_numPixelsCopied)
{ {

View File

@@ -225,7 +225,7 @@ bool PhysicsDirect::processCamera(const struct SharedMemoryCommand& orgCommand)
= rgbaPixelsReceived[i]; = rgbaPixelsReceived[i];
} }
if (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0) if (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0 && serverCmd.m_sendPixelDataArguments.m_numPixelsCopied)
{ {
@@ -241,7 +241,7 @@ bool PhysicsDirect::processCamera(const struct SharedMemoryCommand& orgCommand)
m_data->m_cachedCameraPixelsHeight = serverCmd.m_sendPixelDataArguments.m_imageHeight; m_data->m_cachedCameraPixelsHeight = serverCmd.m_sendPixelDataArguments.m_imageHeight;
} }
} }
} while (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0); } while (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0 && serverCmd.m_sendPixelDataArguments.m_numPixelsCopied);
return m_data->m_hasStatus; return m_data->m_hasStatus;

View File

@@ -43,6 +43,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
eGUIHelperCreateCollisionShapeGraphicsObject, eGUIHelperCreateCollisionShapeGraphicsObject,
eGUIHelperCreateCollisionObjectGraphicsObject, eGUIHelperCreateCollisionObjectGraphicsObject,
eGUIHelperRemoveAllGraphicsInstances, eGUIHelperRemoveAllGraphicsInstances,
eGUIHelperCopyCameraImageData,
}; };
#include <stdio.h> #include <stdio.h>
@@ -392,11 +393,41 @@ public:
{ {
} }
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int width, int height, int* numPixelsCopied) float m_viewMatrix[16];
float m_projectionMatrix[16];
unsigned char* m_pixelsRGBA;
int m_rgbaBufferSizeInPixels;
float* m_depthBuffer;
int m_depthBufferSizeInPixels;
int m_startPixelIndex;
int m_destinationWidth;
int m_destinationHeight;
int* m_numPixelsCopied;
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied)
{ {
if (numPixelsCopied) m_cs->lock();
*numPixelsCopied = 0; for (int i=0;i<16;i++)
{
m_viewMatrix[i] = viewMatrix[i];
m_projectionMatrix[i] = projectionMatrix[i];
}
m_pixelsRGBA = pixelsRGBA;
m_rgbaBufferSizeInPixels = rgbaBufferSizeInPixels;
m_depthBuffer = depthBuffer;
m_depthBufferSizeInPixels = depthBufferSizeInPixels;
m_startPixelIndex = startPixelIndex;
m_destinationWidth = destinationWidth;
m_destinationHeight = destinationHeight;
m_numPixelsCopied = numPixelsCopied;
m_cs->setSharedParam(1,eGUIHelperCopyCameraImageData);
m_cs->unlock();
while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
{
}
} }
virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld)
{ {
@@ -727,6 +758,24 @@ void PhysicsServerExample::stepSimulation(float deltaTime)
m_multiThreadedHelper->getCriticalSection()->unlock(); m_multiThreadedHelper->getCriticalSection()->unlock();
break; break;
} }
case eGUIHelperCopyCameraImageData:
{
m_multiThreadedHelper->m_childGuiHelper->copyCameraImageData(m_multiThreadedHelper->m_viewMatrix,
m_multiThreadedHelper->m_projectionMatrix,
m_multiThreadedHelper->m_pixelsRGBA,
m_multiThreadedHelper->m_rgbaBufferSizeInPixels,
m_multiThreadedHelper->m_depthBuffer,
m_multiThreadedHelper->m_depthBufferSizeInPixels,
m_multiThreadedHelper->m_startPixelIndex,
m_multiThreadedHelper->m_destinationWidth,
m_multiThreadedHelper->m_destinationHeight,
m_multiThreadedHelper->m_numPixelsCopied);
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIHelperIdle: case eGUIHelperIdle:
default: default:
{ {

View File

@@ -1154,20 +1154,21 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args)
b3RequestCameraImageSetFOVProjectionMatrix(command, fov, aspect, nearVal, farVal); b3RequestCameraImageSetFOVProjectionMatrix(command, fov, aspect, nearVal, farVal);
} }
} }
else if (size==10) else if (size==11)
{ {
int upAxisIndex=1; int upAxisIndex=1;
float camDistance,yaw,pitch; float camDistance,yaw,pitch,roll;
//sometimes more arguments are better :-) //sometimes more arguments are better :-)
if (PyArg_ParseTuple(args, "iiOfffifff", &width, &height, &objTargetPos, &camDistance, &yaw, &pitch, &upAxisIndex, &nearVal, &farVal, &fov)) if (PyArg_ParseTuple(args, "iiOffffifff", &width, &height, &objTargetPos, &camDistance, &yaw, &pitch, &roll, &upAxisIndex, &nearVal, &farVal, &fov))
{ {
b3RequestCameraImageSetPixelResolution(command,width,height);
if (pybullet_internalSetVector(objTargetPos, targetPos)) 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); //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); b3RequestCameraImageSetViewMatrix2(command,targetPos,camDistance,yaw,pitch,roll,upAxisIndex);
aspect = width/height; aspect = width/height;
b3RequestCameraImageSetFOVProjectionMatrix(command, fov, aspect, nearVal, farVal); b3RequestCameraImageSetFOVProjectionMatrix(command, fov, aspect, nearVal, farVal);
} else } else
@@ -1193,6 +1194,9 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args)
{ {
b3SharedMemoryStatusHandle statusHandle; b3SharedMemoryStatusHandle statusHandle;
int statusType; int statusType;
//b3RequestCameraImageSelectRenderer(command,ER_BULLET_HARDWARE_OPENGL);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle); statusType = b3GetStatusType(statusHandle);
if (statusType==CMD_CAMERA_IMAGE_COMPLETED) if (statusType==CMD_CAMERA_IMAGE_COMPLETED)

View File

@@ -6,14 +6,16 @@ pybullet.connect(pybullet.GUI)
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 = [3,3,3] cameraPos = [1,1,1]
yaw = 40.0 yaw = 40
pitch = 0.0 pitch = 10.0
upAxisIndex = 1
camDistance = 3 roll=0
pixelWidth = 640 upAxisIndex = 2
pixelHeight = 480 camDistance = 4
pixelWidth = 320
pixelHeight = 240
nearPlane = 0.01 nearPlane = 0.01
farPlane = 1000 farPlane = 1000
@@ -22,19 +24,23 @@ fov = 60
#img_arr = pybullet.renderImage(pixelWidth, pixelHeight) #img_arr = pybullet.renderImage(pixelWidth, pixelHeight)
#renderImage(w, h, view[16], projection[16]) #renderImage(w, h, view[16], projection[16])
#img_arr = pybullet.renderImage(pixelWidth, pixelHeight, cameraPos, camTargetPos, cameraUp, nearPlane, farPlane) #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) for pitch in range (0,360,10) :
img_arr = pybullet.renderImage(pixelWidth, pixelHeight, camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex, nearPlane, farPlane, fov)
w=img_arr[0] #width of the image, in pixels w=img_arr[0] #width of the image, in pixels
h=img_arr[1] #height of the image, in pixels h=img_arr[1] #height of the image, in pixels
rgb=img_arr[2] #color data RGB rgb=img_arr[2] #color data RGB
dep=img_arr[3] #depth data dep=img_arr[3] #depth data
#print 'width = %d height = %d' % (w,h)
# reshape creates np array # reshape creates np array
np_img_arr = np.reshape(rgb, (pixelHeight, pixelWidth, 4)) np_img_arr = np.reshape(rgb, (h, w, 4))
np_img_arr = np_img_arr*(1./255.) np_img_arr = np_img_arr*(1./255.)
#show #show
plt.imshow(np_img_arr,interpolation='none') plt.imshow(np_img_arr,interpolation='none')
plt.show() #plt.show()
p.resetSimulation() plt.pause(0.01)
pybullet.resetSimulation()