diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 1c5893ce6..2107c8bb3 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -427,47 +427,67 @@ void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const floa SimpleCamera tempCam; getRenderInterface()->setActiveCamera(&tempCam); getRenderInterface()->getActiveCamera()->setVRCamera(viewMatrix,projectionMatrix); - getRenderInterface()->renderScene(); + { + BT_PROFILE("renderScene"); + getRenderInterface()->renderScene(); + } getRenderInterface()->setActiveCamera(oldCam); { + BT_PROFILE("copy pixels"); btAlignedObjectArray sourceRgbaPixelBuffer; btAlignedObjectArray sourceDepthBuffer; //copy the image into our local cache sourceRgbaPixelBuffer.resize(sourceWidth*sourceHeight*numBytesPerPixel); sourceDepthBuffer.resize(sourceWidth*sourceHeight); - m_data->m_glApp->getScreenPixels(&(sourceRgbaPixelBuffer[0]),sourceRgbaPixelBuffer.size(), &sourceDepthBuffer[0],sizeof(float)*sourceDepthBuffer.size()); + { + BT_PROFILE("getScreenPixels"); + m_data->m_glApp->getScreenPixels(&(sourceRgbaPixelBuffer[0]),sourceRgbaPixelBuffer.size(), &sourceDepthBuffer[0],sizeof(float)*sourceDepthBuffer.size()); + } m_data->m_rgbaPixelBuffer1.resize(destinationWidth*destinationHeight*numBytesPerPixel); m_data->m_depthBuffer1.resize(destinationWidth*destinationHeight); //rescale and flip - - for (int i=0;im_rgbaPixelBuffer1[(i+j*destinationWidth)*4+0]; + int* src = (int*)&sourceRgbaPixelBuffer[sourcePixelIndex+0]; + *dst = *src; + +#else + m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+0] = sourceRgbaPixelBuffer[sourcePixelIndex+0]; + m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+1] = sourceRgbaPixelBuffer[sourcePixelIndex+1]; + m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+2] = sourceRgbaPixelBuffer[sourcePixelIndex+2]; + m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+3] = 255; +#endif + if (depthBuffer) + { + m_data->m_depthBuffer1[i+j*destinationWidth] = sourceDepthBuffer[sourceDepthIndex]; + } - m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+0] = sourceRgbaPixelBuffer[sourcePixelIndex+0]; - m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+1] = sourceRgbaPixelBuffer[sourcePixelIndex+1]; - m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+2] = sourceRgbaPixelBuffer[sourcePixelIndex+2]; - m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+3] = 255; - - m_data->m_depthBuffer1[i+j*destinationWidth] = sourceDepthBuffer[sourceDepthIndex]; - - } + } + } } } } if (pixelsRGBA) { + BT_PROFILE("copy rgba pixels"); + for (int i=0;im_rgbaPixelBuffer1[i+startPixelIndex*numBytesPerPixel]; @@ -475,6 +495,8 @@ void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const floa } if (depthBuffer) { + BT_PROFILE("copy depth buffer pixels"); + for (int i=0;im_depthBuffer1[i+startPixelIndex]; diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 30d49562b..c0465f7fb 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -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); diff --git a/examples/pybullet/testrender.py b/examples/pybullet/testrender.py index 0d3475c84..72fa9e27e 100644 --- a/examples/pybullet/testrender.py +++ b/examples/pybullet/testrender.py @@ -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] diff --git a/examples/pybullet/testrender_np.py b/examples/pybullet/testrender_np.py index b8fca10eb..c008da09f 100644 --- a/examples/pybullet/testrender_np.py +++ b/examples/pybullet/testrender_np.py @@ -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()