diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index cb1477b6c..7e615a379 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -1158,6 +1158,7 @@ void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const floa { { m_data->m_glApp->m_window->startRendering(); + m_data->m_glApp->setViewport(sourceWidth, sourceHeight); BT_PROFILE("renderScene"); getRenderInterface()->renderSceneInternal(B3_SEGMENTATION_MASK_RENDERMODE); } diff --git a/examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp b/examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp index 973fc1b68..542196ff1 100644 --- a/examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp @@ -995,7 +995,7 @@ void EGLRendererVisualShapeConverter::copyCameraImageDataGL( int destinationWidth = *widthPtr; int destinationHeight = *heightPtr; - int sourceWidth = btMin(destinationWidth, (int)(m_data->m_window->getWidth() * m_data->m_window->getRetinaScale())); + int sourceWidth = btMin(destinationWidth, (int)(m_data->m_window->getWidth() * m_data->m_window->getRetinaScale())); int sourceHeight = btMin(destinationHeight, (int)(m_data->m_window->getHeight() * m_data->m_window->getRetinaScale())); int numTotalPixels = (*widthPtr) * (*heightPtr); @@ -1006,10 +1006,9 @@ void EGLRendererVisualShapeConverter::copyCameraImageDataGL( { if (startPixelIndex == 0) { - glViewport(0,0, sourceWidth, sourceHeight); m_data->m_window->endRendering(); m_data->m_window->startRendering(); - + glViewport(0,0, sourceWidth, sourceHeight); B3_PROFILE("m_instancingRenderer render"); m_data->m_instancingRenderer->writeTransforms(); if (m_data->m_hasLightDirection) @@ -1097,7 +1096,7 @@ void EGLRendererVisualShapeConverter::copyCameraImageDataGL( { { m_data->m_window->startRendering(); - + glViewport(0,0, sourceWidth, sourceHeight); BT_PROFILE("renderScene"); m_data->m_instancingRenderer->renderSceneInternal(B3_SEGMENTATION_MASK_RENDERMODE); } diff --git a/examples/pybullet/examples/testrender_egl.py b/examples/pybullet/examples/testrender_egl.py index 0f0b89e03..ee25f64b7 100644 --- a/examples/pybullet/examples/testrender_egl.py +++ b/examples/pybullet/examples/testrender_egl.py @@ -21,8 +21,10 @@ ax = plt.gca() pybullet.connect(pybullet.DIRECT) egl = pkgutil.get_loader('eglRenderer') - -pybullet.loadPlugin(egl.get_filename(), "_eglRendererPlugin") +if (egl): + pybullet.loadPlugin(egl.get_filename(), "_eglRendererPlugin") +else: + pybullet.loadPlugin("eglRendererPlugin") pybullet.loadURDF("plane.urdf",[0,0,-1]) pybullet.loadURDF("r2d2.urdf") @@ -52,7 +54,7 @@ while (1): 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, shadow=1,lightDirection=[1,1,1],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL) + img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, shadow=1,flags=pybullet.ER_SEGMENTATION_MASK, lightDirection=[1,1,1],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL) stop = time.time() print ("renderImage %f" % (stop - start))