From fd7aa8d0e182d132f8c322971f7695c695263ba7 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Sun, 18 Mar 2018 17:01:23 -0700 Subject: [PATCH 1/4] Expose using projective texture as a flag in pybullet getCameraImage API. --- Extras/BulletRobotics/CMakeLists.txt | 2 +- examples/OpenGLWindow/GLInstancingRenderer.cpp | 1 - examples/SharedMemory/CMakeLists.txt | 2 +- examples/SharedMemory/PhysicsClientC_API.h | 3 +++ .../PhysicsServerCommandProcessor.cpp | 15 +++++++++++++-- examples/SharedMemory/SharedMemoryPublic.h | 2 ++ examples/pybullet/examples/projective_texture.py | 1 + examples/pybullet/pybullet.c | 1 + test/SharedMemory/CMakeLists.txt | 2 +- 9 files changed, 23 insertions(+), 6 deletions(-) diff --git a/Extras/BulletRobotics/CMakeLists.txt b/Extras/BulletRobotics/CMakeLists.txt index b2c4523b6..b76984846 100644 --- a/Extras/BulletRobotics/CMakeLists.txt +++ b/Extras/BulletRobotics/CMakeLists.txt @@ -166,7 +166,7 @@ SET_TARGET_PROPERTIES(BulletRobotics PROPERTIES VERSION ${BULLET_VERSION}) SET_TARGET_PROPERTIES(BulletRobotics PROPERTIES SOVERSION ${BULLET_VERSION}) IF (BUILD_SHARED_LIBS) - TARGET_LINK_LIBRARIES(BulletRobotics BulletInverseDynamicsUtils BulletWorldImporter BulletFileLoader BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamics LinearMath Bullet3Common) + TARGET_LINK_LIBRARIES(BulletRobotics BulletInverseDynamicsUtils BulletWorldImporter BulletFileLoader BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamics OpenGLWindow LinearMath Bullet3Common) ENDIF (BUILD_SHARED_LIBS) IF (INSTALL_EXTRA_LIBS) diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index 3533e1fb9..fdaa24440 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -1585,7 +1585,6 @@ void GLInstancingRenderer::renderScene() } else if (useProjectiveTexture) { - //renderSceneInternal(B3_CREATE_SHADOWMAP_RENDERMODE); renderSceneInternal(B3_USE_PROJECTIVE_TEXTURE_RENDERMODE); } else diff --git a/examples/SharedMemory/CMakeLists.txt b/examples/SharedMemory/CMakeLists.txt index 63f61ebaa..48100c10d 100644 --- a/examples/SharedMemory/CMakeLists.txt +++ b/examples/SharedMemory/CMakeLists.txt @@ -97,7 +97,7 @@ IF (USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD) ENDIF() LINK_LIBRARIES( - Bullet3Common BulletWorldImporter BulletFileLoader BulletInverseDynamicsUtils BulletInverseDynamics BulletDynamics BulletCollision LinearMath BussIK + Bullet3Common BulletWorldImporter BulletFileLoader BulletInverseDynamicsUtils BulletInverseDynamics BulletDynamics BulletCollision LinearMath OpenGLWindow BussIK ) diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 7b0799de8..ba9db70ee 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -213,6 +213,9 @@ B3_SHARED_API void b3RequestCameraImageSetFlags(b3SharedMemoryCommandHandle comm B3_SHARED_API void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData); + +///set projective texture camera matrices. +B3_SHARED_API void b3RequestCameraImageSetProjectiveTextureMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[/*16*/], float projectionMatrix[/*16*/]); ///compute a view matrix, helper function for b3RequestCameraImageSetCameraMatrices B3_SHARED_API void b3ComputeViewMatrixFromPositions(const float cameraPosition[/*3*/], const float cameraTargetPosition[/*3*/], const float cameraUp[/*3*/], float viewMatrix[/*16*/]); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 59c078081..2a2488e3b 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1,5 +1,6 @@ #include "PhysicsServerCommandProcessor.h" #include "../CommonInterfaces/CommonRenderInterface.h" +#include "../OpenGLWindow/GLInstancingRenderer.h" #include "../Importers/ImportURDFDemo/BulletUrdfImporter.h" #include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h" @@ -70,8 +71,6 @@ #include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h" #endif - - int gInternalSimFlags = 0; bool gResetSimulation = 0; int gVRTrackingObjectUniqueId = -1; @@ -3109,6 +3108,8 @@ bool PhysicsServerCommandProcessor::processStateLoggingCommand(const struct Shar return hasStatus; } +extern bool useShadowMap; +extern bool useProjectiveTexture; bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) { bool hasStatus = true; @@ -3190,6 +3191,16 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc if ((clientCmd.m_updateFlags & ER_BULLET_HARDWARE_OPENGL)!=0) { + if ((flags & ER_USE_PROJECTIVE_TEXTURE) != 0) + { + useShadowMap = false; + useProjectiveTexture = true; + } + else + { + useShadowMap = true; + useProjectiveTexture = false; + } m_data->m_guiHelper->copyCameraImageData(viewMat, projMat,pixelRGBA,numRequestedPixels, diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 1be0128b9..c1b3b96c3 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -616,7 +616,9 @@ enum EnumRenderer enum EnumRendererAuxFlags { ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX=1, + ER_USE_PROJECTIVE_TEXTURE=2, }; + ///flags to pick the IK solver and other options enum EnumCalculateInverseKinematicsFlags { diff --git a/examples/pybullet/examples/projective_texture.py b/examples/pybullet/examples/projective_texture.py index 576a7a095..e1e4931b7 100644 --- a/examples/pybullet/examples/projective_texture.py +++ b/examples/pybullet/examples/projective_texture.py @@ -25,6 +25,7 @@ if (useRealTimeSimulation): while 1: if (useRealTimeSimulation): + p.getCameraImage(300, 300, lightColor=[1.0,0.0,0.0], renderer=p.ER_BULLET_HARDWARE_OPENGL, flags=p.ER_USE_PROJECTIVE_TEXTURE) p.setGravity(0,0,0) sleep(0.01) # Time in seconds. else: diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 4280fe50c..5bd7e90b9 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -9112,6 +9112,7 @@ initpybullet(void) PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER); PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL); PyModule_AddIntConstant(m, "ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX", ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX); + PyModule_AddIntConstant(m, "ER_USE_PROJECTIVE_TEXTURE", ER_USE_PROJECTIVE_TEXTURE); PyModule_AddIntConstant(m, "IK_DLS", IK_DLS); PyModule_AddIntConstant(m, "IK_SDLS", IK_SDLS); diff --git a/test/SharedMemory/CMakeLists.txt b/test/SharedMemory/CMakeLists.txt index e0798123f..e41b2c06d 100644 --- a/test/SharedMemory/CMakeLists.txt +++ b/test/SharedMemory/CMakeLists.txt @@ -16,7 +16,7 @@ IF (USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD) ENDIF() LINK_LIBRARIES( - BulletInverseDynamicsUtils BulletInverseDynamics BulletFileLoader BulletWorldImporter Bullet3Common BulletDynamics BulletCollision LinearMath gtest BussIK + BulletInverseDynamicsUtils BulletInverseDynamics BulletFileLoader BulletWorldImporter Bullet3Common BulletDynamics BulletCollision LinearMath gtest OpenGLWindow BussIK ) IF (NOT WIN32) From 37696dd87ecfceb328046011dd2206c7ec170d2c Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Sun, 18 Mar 2018 18:45:54 -0700 Subject: [PATCH 2/4] Add Bullet C API and pybullet API to set projective texture matrices. --- .../CommonGUIHelperInterface.h | 5 +++++ .../CommonInterfaces/CommonRenderInterface.h | 1 + examples/ExampleBrowser/OpenGLGuiHelper.cpp | 4 ++++ examples/ExampleBrowser/OpenGLGuiHelper.h | 2 ++ .../OpenGLWindow/GLInstancingRenderer.cpp | 14 ++++++++++++- examples/OpenGLWindow/GLInstancingRenderer.h | 1 + examples/SharedMemory/PhysicsClientC_API.cpp | 13 ++++++++++++ .../PhysicsServerCommandProcessor.cpp | 21 ++++++++++++++++++- .../SharedMemory/PhysicsServerExample.cpp | 5 +++++ examples/SharedMemory/SharedMemoryCommands.h | 3 +++ .../pybullet/examples/projective_texture.py | 8 +++++-- examples/pybullet/pybullet.c | 12 ++++++++--- 12 files changed, 82 insertions(+), 7 deletions(-) diff --git a/examples/CommonInterfaces/CommonGUIHelperInterface.h b/examples/CommonInterfaces/CommonGUIHelperInterface.h index 9171ed5c4..20482d4c8 100644 --- a/examples/CommonInterfaces/CommonGUIHelperInterface.h +++ b/examples/CommonInterfaces/CommonGUIHelperInterface.h @@ -94,6 +94,7 @@ struct GUIHelperInterface int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels, int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied){} + virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16])=0; virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) =0; @@ -178,6 +179,10 @@ struct DummyGUIHelper : public GUIHelperInterface if (numPixelsCopied) *numPixelsCopied = 0; } + + virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]) + { + } virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) { diff --git a/examples/CommonInterfaces/CommonRenderInterface.h b/examples/CommonInterfaces/CommonRenderInterface.h index 50ac24c03..3706d0c6d 100644 --- a/examples/CommonInterfaces/CommonRenderInterface.h +++ b/examples/CommonInterfaces/CommonRenderInterface.h @@ -49,6 +49,7 @@ struct CommonRenderInterface virtual void setLightPosition(const float lightPos[3]) = 0; virtual void setLightPosition(const double lightPos[3]) = 0; + virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]){}; virtual void renderScene()=0; virtual void renderSceneInternal(int renderMode=B3_DEFAULT_RENDERMODE){}; diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 5df588ec3..82fc9a50d 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -1098,6 +1098,10 @@ bool OpenGLGuiHelper::getCameraInfo(int* width, int* height, float viewMatrix[16 return false; } +void OpenGLGuiHelper::setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]) +{ + m_data->m_glApp->m_renderer->setProjectiveTextureMatrices(viewMatrix, projectionMatrix); +} void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.h b/examples/ExampleBrowser/OpenGLGuiHelper.h index 319f2ed21..47854b0f2 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.h +++ b/examples/ExampleBrowser/OpenGLGuiHelper.h @@ -61,6 +61,8 @@ struct OpenGLGuiHelper : public GUIHelperInterface int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels, int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied); + + virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]); virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) ; diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index fdaa24440..0462f053e 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -225,6 +225,8 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData GLfloat m_projectionMatrix[16]; GLfloat m_viewMatrix[16]; + GLfloat m_projectiveTextureProjectionMatrix[16]; + GLfloat m_projectiveTextureViewMatrix[16]; GLfloat m_viewMatrixInverse[16]; b3Vector3 m_lightPos; @@ -257,6 +259,8 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData m_projectionMatrix[i]=0; m_viewMatrix[i]=0; m_viewMatrixInverse[i]=0; + m_projectiveTextureProjectionMatrix[i]=0; + m_projectiveTextureViewMatrix[i]=0; } } @@ -1466,6 +1470,14 @@ void GLInstancingRenderer::setLightPosition(const double lightPos[3]) m_data->m_lightPos[2] = lightPos[2]; } +void GLInstancingRenderer::setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]) +{ + for (int i = 0; i < 16; i++) + { + m_data->m_projectiveTextureViewMatrix[i] = viewMatrix[i]; + m_data->m_projectiveTextureProjectionMatrix[i] = projectionMatrix[i]; + } +} void GLInstancingRenderer::updateCamera(int upAxis) { @@ -2180,7 +2192,7 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode) // TODO: Expose the projective texture matrix setup. Temporarily set it to be the same as camera view projection matrix. GLfloat textureMVP[16]; - b3Matrix4x4Mul16(m_data->m_projectionMatrix,m_data->m_viewMatrix,textureMVP); + b3Matrix4x4Mul16(m_data->m_projectiveTextureProjectionMatrix,m_data->m_projectiveTextureViewMatrix,textureMVP); //float m_frustumZNear=0.1; //float m_frustumZFar=100.f; diff --git a/examples/OpenGLWindow/GLInstancingRenderer.h b/examples/OpenGLWindow/GLInstancingRenderer.h index 073c05349..7f0e5a68e 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.h +++ b/examples/OpenGLWindow/GLInstancingRenderer.h @@ -131,6 +131,7 @@ public: virtual void setLightPosition(const float lightPos[3]); virtual void setLightPosition(const double lightPos[3]); void setLightSpecularIntensity(const float lightSpecularIntensity[3]); + virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]); virtual void resize(int width, int height); virtual int getScreenWidth() diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 2a6009920..f3ddb03cd 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -3081,6 +3081,19 @@ B3_SHARED_API void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle com command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_SHADOW; } +B3_SHARED_API void b3RequestCameraImageSetProjectiveTextureMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16]) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); + for (int i=0;i<16;i++) + { + command->m_requestPixelDataArguments.m_projectiveTextureProjectionMatrix[i] = projectionMatrix[i]; + command->m_requestPixelDataArguments.m_projectiveTextureViewMatrix[i] = viewMatrix[i]; + } + command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_PROJECTIVE_TEXTURE_MATRICES; +} + B3_SHARED_API void b3ComputePositionFromViewMatrix(const float viewMatrix[16], float cameraPosition[3], float cameraTargetPosition[3], float cameraUp[3]) { b3Matrix3x3 r(viewMatrix[0], viewMatrix[4], viewMatrix[8], viewMatrix[1], viewMatrix[5], viewMatrix[9], viewMatrix[2], viewMatrix[6], viewMatrix[10]); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 2a2488e3b..fba94fa52 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -3157,6 +3157,8 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc serverStatusOut.m_numDataStreamBytes = numRequestedPixels * totalBytesPerPixel; float viewMat[16]; float projMat[16]; + float projTextureViewMat[16]; + float projTextureProjMat[16]; for (int i=0;i<16;i++) { viewMat[i] = clientCmd.m_requestPixelDataArguments.m_viewMatrix[i]; @@ -3186,7 +3188,7 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc projMat[i] = tmpCamResult.m_projectionMatrix[i]; } } - } + } bool handled = false; if ((clientCmd.m_updateFlags & ER_BULLET_HARDWARE_OPENGL)!=0) @@ -3195,6 +3197,23 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc { useShadowMap = false; useProjectiveTexture = true; + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_PROJECTIVE_TEXTURE_MATRICES)!=0) + { + for (int i=0;i<16;i++) + { + projTextureViewMat[i] = clientCmd.m_requestPixelDataArguments.m_projectiveTextureViewMatrix[i]; + projTextureProjMat[i] = clientCmd.m_requestPixelDataArguments.m_projectiveTextureProjectionMatrix[i]; + } + } + else // If no specified matrices for projective texture, then use the camera matrices. + { + for (int i=0;i<16;i++) + { + projTextureViewMat[i] = viewMat[i]; + projTextureProjMat[i] = projMat[i]; + } + } + this->m_data->m_guiHelper->setProjectiveTextureMatrices(projTextureViewMat, projTextureProjMat); } else { diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 63af47751..01c712af0 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -1119,6 +1119,11 @@ public: m_cs->setSharedParam(1,eGUIHelperDisplayCameraImageData); workerThreadWait(); } + + virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]) + { + m_childGuiHelper->getAppInterface()->m_renderer->setProjectiveTextureMatrices(viewMatrix, projectionMatrix); + } btDiscreteDynamicsWorld* m_dynamicsWorld; diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index e23eefa69..9331c87d9 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -240,6 +240,8 @@ struct RequestPixelDataArgs float m_lightSpecularCoeff; int m_hasShadow; int m_flags; + float m_projectiveTextureViewMatrix[16]; + float m_projectiveTextureProjectionMatrix[16]; }; enum EnumRequestPixelDataUpdateFlags @@ -254,6 +256,7 @@ enum EnumRequestPixelDataUpdateFlags REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF=128, REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF=256, REQUEST_PIXEL_ARGS_HAS_FLAGS = 512, + REQUEST_PIXEL_ARGS_HAS_PROJECTIVE_TEXTURE_MATRICES=1024, //don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h diff --git a/examples/pybullet/examples/projective_texture.py b/examples/pybullet/examples/projective_texture.py index e1e4931b7..00ae2320d 100644 --- a/examples/pybullet/examples/projective_texture.py +++ b/examples/pybullet/examples/projective_texture.py @@ -25,8 +25,12 @@ if (useRealTimeSimulation): while 1: if (useRealTimeSimulation): - p.getCameraImage(300, 300, lightColor=[1.0,0.0,0.0], renderer=p.ER_BULLET_HARDWARE_OPENGL, flags=p.ER_USE_PROJECTIVE_TEXTURE) + camera = p.getDebugVisualizerCamera() + viewMat = camera[2] + projMat = camera[3] + #An example of setting the view matrix for the projective texture. + #viewMat = p.computeViewMatrix(cameraEyePosition=[7,0,0], cameraTargetPosition=[0,0,0], cameraUpVector=[0,0,1]) + p.getCameraImage(300, 300, renderer=p.ER_BULLET_HARDWARE_OPENGL, flags=p.ER_USE_PROJECTIVE_TEXTURE, projectiveTextureView=viewMat, projectiveTextureProj=projMat) p.setGravity(0,0,0) - sleep(0.01) # Time in seconds. else: p.stepSimulation() diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 5bd7e90b9..761da3f52 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -6761,10 +6761,12 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec { /// request an image from a simulated camera, using software or hardware renderer. struct b3CameraImageData imageData; - PyObject *objViewMat = 0, *objProjMat = 0, *lightDirObj = 0, *lightColorObj = 0; + PyObject *objViewMat = 0, *objProjMat = 0, *lightDirObj = 0, *lightColorObj = 0, *objProjectiveTextureView = 0, *objProjectiveTextureProj = 0; int width, height; float viewMatrix[16]; float projectionMatrix[16]; + float projectiveTextureView[16]; + float projectiveTextureProj[16]; float lightDir[3]; float lightColor[3]; float lightDist = -1; @@ -6779,9 +6781,9 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec int physicsClientId = 0; b3PhysicsClientHandle sm = 0; // set camera resolution, optionally view, projection matrix, light direction, light color, light distance, shadow - static char* kwlist[] = {"width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", "lightDistance", "shadow", "lightAmbientCoeff", "lightDiffuseCoeff", "lightSpecularCoeff", "renderer", "flags", "physicsClientId", NULL}; + static char* kwlist[] = {"width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", "lightDistance", "shadow", "lightAmbientCoeff", "lightDiffuseCoeff", "lightSpecularCoeff", "renderer", "flags", "projectiveTextureView", "projectiveTextureProj", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfifffiii", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow, &lightAmbientCoeff, &lightDiffuseCoeff, &lightSpecularCoeff, &renderer, &flags, &physicsClientId)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfifffiiOOi", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow, &lightAmbientCoeff, &lightDiffuseCoeff, &lightSpecularCoeff, &renderer, &flags, &objProjectiveTextureView, &objProjectiveTextureProj, &physicsClientId)) { return NULL; } @@ -6837,6 +6839,10 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec { b3RequestCameraImageSetFlags(command, flags); } + if (objProjectiveTextureView && objProjectiveTextureProj && pybullet_internalSetMatrix(objProjectiveTextureView, projectiveTextureView) && (pybullet_internalSetMatrix(objProjectiveTextureProj, projectiveTextureProj))) + { + b3RequestCameraImageSetProjectiveTextureMatrices(command, projectiveTextureView, projectiveTextureProj); + } if (renderer>=0) { b3RequestCameraImageSelectRenderer(command, renderer);//renderer could be ER_BULLET_HARDWARE_OPENGL From e42a934e16e11d089468400e85aa5f98f02bb222 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Mon, 19 Mar 2018 10:23:17 -0700 Subject: [PATCH 3/4] Fix compiling error. --- examples/RobotSimulator/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/RobotSimulator/CMakeLists.txt b/examples/RobotSimulator/CMakeLists.txt index 0647edf72..0be4fd7a8 100644 --- a/examples/RobotSimulator/CMakeLists.txt +++ b/examples/RobotSimulator/CMakeLists.txt @@ -116,7 +116,7 @@ ELSE() ENDIF(APPLE) ENDIF(WIN32) -TARGET_LINK_LIBRARIES(App_RobotSimulator_NoGUI BulletRobotics BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath Bullet3Common) +TARGET_LINK_LIBRARIES(App_RobotSimulator_NoGUI BulletRobotics BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow Bullet3Common) From 6b97e1e6047007b5ea4f29348b52de9dbfa6b3bc Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Tue, 20 Mar 2018 21:28:47 -0700 Subject: [PATCH 4/4] Expose API to set projective texture instead of using global. --- Extras/BulletRobotics/CMakeLists.txt | 2 +- examples/CommonInterfaces/CommonGUIHelperInterface.h | 5 +++++ examples/CommonInterfaces/CommonRenderInterface.h | 1 + examples/ExampleBrowser/OpenGLGuiHelper.cpp | 5 +++++ examples/ExampleBrowser/OpenGLGuiHelper.h | 1 + examples/OpenGLWindow/GLInstancingRenderer.cpp | 11 +++++++++-- examples/OpenGLWindow/GLInstancingRenderer.h | 1 + examples/RobotSimulator/CMakeLists.txt | 2 +- examples/SharedMemory/CMakeLists.txt | 2 +- .../SharedMemory/PhysicsServerCommandProcessor.cpp | 9 ++------- examples/SharedMemory/PhysicsServerExample.cpp | 5 +++++ test/SharedMemory/CMakeLists.txt | 2 +- 12 files changed, 33 insertions(+), 13 deletions(-) diff --git a/Extras/BulletRobotics/CMakeLists.txt b/Extras/BulletRobotics/CMakeLists.txt index b76984846..b2c4523b6 100644 --- a/Extras/BulletRobotics/CMakeLists.txt +++ b/Extras/BulletRobotics/CMakeLists.txt @@ -166,7 +166,7 @@ SET_TARGET_PROPERTIES(BulletRobotics PROPERTIES VERSION ${BULLET_VERSION}) SET_TARGET_PROPERTIES(BulletRobotics PROPERTIES SOVERSION ${BULLET_VERSION}) IF (BUILD_SHARED_LIBS) - TARGET_LINK_LIBRARIES(BulletRobotics BulletInverseDynamicsUtils BulletWorldImporter BulletFileLoader BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamics OpenGLWindow LinearMath Bullet3Common) + TARGET_LINK_LIBRARIES(BulletRobotics BulletInverseDynamicsUtils BulletWorldImporter BulletFileLoader BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamics LinearMath Bullet3Common) ENDIF (BUILD_SHARED_LIBS) IF (INSTALL_EXTRA_LIBS) diff --git a/examples/CommonInterfaces/CommonGUIHelperInterface.h b/examples/CommonInterfaces/CommonGUIHelperInterface.h index 20482d4c8..916a82343 100644 --- a/examples/CommonInterfaces/CommonGUIHelperInterface.h +++ b/examples/CommonInterfaces/CommonGUIHelperInterface.h @@ -95,6 +95,7 @@ struct GUIHelperInterface int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied){} virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16])=0; + virtual void setProjectiveTexture(bool useProjectiveTexture)=0; virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) =0; @@ -183,6 +184,10 @@ struct DummyGUIHelper : public GUIHelperInterface virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]) { } + + virtual void setProjectiveTexture(bool useProjectiveTexture) + { + } virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) { diff --git a/examples/CommonInterfaces/CommonRenderInterface.h b/examples/CommonInterfaces/CommonRenderInterface.h index 3706d0c6d..a64fe7dde 100644 --- a/examples/CommonInterfaces/CommonRenderInterface.h +++ b/examples/CommonInterfaces/CommonRenderInterface.h @@ -50,6 +50,7 @@ struct CommonRenderInterface virtual void setLightPosition(const float lightPos[3]) = 0; virtual void setLightPosition(const double lightPos[3]) = 0; virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]){}; + virtual void setProjectiveTexture(bool useProjectiveTexture){}; virtual void renderScene()=0; virtual void renderSceneInternal(int renderMode=B3_DEFAULT_RENDERMODE){}; diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 82fc9a50d..71970893a 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -1103,6 +1103,11 @@ void OpenGLGuiHelper::setProjectiveTextureMatrices(const float viewMatrix[16], c m_data->m_glApp->m_renderer->setProjectiveTextureMatrices(viewMatrix, projectionMatrix); } +void OpenGLGuiHelper::setProjectiveTexture(bool useProjectiveTexture) +{ + m_data->m_glApp->m_renderer->setProjectiveTexture(useProjectiveTexture); +} + void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.h b/examples/ExampleBrowser/OpenGLGuiHelper.h index 47854b0f2..3a43a0221 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.h +++ b/examples/ExampleBrowser/OpenGLGuiHelper.h @@ -63,6 +63,7 @@ struct OpenGLGuiHelper : public GUIHelperInterface int destinationHeight, int* numPixelsCopied); virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]); + virtual void setProjectiveTexture(bool useProjectiveTexture); virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) ; diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index 0462f053e..5d91a3bb6 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -17,7 +17,6 @@ subject to the following restrictions: ///todo: make this configurable in the gui bool useShadowMap = true;// true;//false;//true; -bool useProjectiveTexture = false; int shadowMapWidth= 4096; int shadowMapHeight= 4096; float shadowMapWorldSize=10; @@ -228,6 +227,7 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData GLfloat m_projectiveTextureProjectionMatrix[16]; GLfloat m_projectiveTextureViewMatrix[16]; GLfloat m_viewMatrixInverse[16]; + bool m_useProjectiveTexture; b3Vector3 m_lightPos; b3Vector3 m_lightSpecularIntensity; @@ -263,6 +263,7 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData m_projectiveTextureViewMatrix[i]=0; } + m_useProjectiveTexture = false; } @@ -1479,6 +1480,12 @@ void GLInstancingRenderer::setProjectiveTextureMatrices(const float viewMatrix[1 } } +void GLInstancingRenderer::setProjectiveTexture(bool useProjectiveTexture) +{ + m_data->m_useProjectiveTexture = useProjectiveTexture; + useShadowMap = !useProjectiveTexture; +} + void GLInstancingRenderer::updateCamera(int upAxis) { @@ -1595,7 +1602,7 @@ void GLInstancingRenderer::renderScene() renderSceneInternal(B3_USE_SHADOWMAP_RENDERMODE); } - else if (useProjectiveTexture) + else if (m_data->m_useProjectiveTexture) { renderSceneInternal(B3_USE_PROJECTIVE_TEXTURE_RENDERMODE); } diff --git a/examples/OpenGLWindow/GLInstancingRenderer.h b/examples/OpenGLWindow/GLInstancingRenderer.h index 7f0e5a68e..310d4f03f 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.h +++ b/examples/OpenGLWindow/GLInstancingRenderer.h @@ -132,6 +132,7 @@ public: virtual void setLightPosition(const double lightPos[3]); void setLightSpecularIntensity(const float lightSpecularIntensity[3]); virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]); + virtual void setProjectiveTexture(bool useProjectiveTexture); virtual void resize(int width, int height); virtual int getScreenWidth() diff --git a/examples/RobotSimulator/CMakeLists.txt b/examples/RobotSimulator/CMakeLists.txt index 0be4fd7a8..0647edf72 100644 --- a/examples/RobotSimulator/CMakeLists.txt +++ b/examples/RobotSimulator/CMakeLists.txt @@ -116,7 +116,7 @@ ELSE() ENDIF(APPLE) ENDIF(WIN32) -TARGET_LINK_LIBRARIES(App_RobotSimulator_NoGUI BulletRobotics BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow Bullet3Common) +TARGET_LINK_LIBRARIES(App_RobotSimulator_NoGUI BulletRobotics BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath Bullet3Common) diff --git a/examples/SharedMemory/CMakeLists.txt b/examples/SharedMemory/CMakeLists.txt index 48100c10d..63f61ebaa 100644 --- a/examples/SharedMemory/CMakeLists.txt +++ b/examples/SharedMemory/CMakeLists.txt @@ -97,7 +97,7 @@ IF (USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD) ENDIF() LINK_LIBRARIES( - Bullet3Common BulletWorldImporter BulletFileLoader BulletInverseDynamicsUtils BulletInverseDynamics BulletDynamics BulletCollision LinearMath OpenGLWindow BussIK + Bullet3Common BulletWorldImporter BulletFileLoader BulletInverseDynamicsUtils BulletInverseDynamics BulletDynamics BulletCollision LinearMath BussIK ) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index fba94fa52..4352fd5ba 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1,6 +1,5 @@ #include "PhysicsServerCommandProcessor.h" #include "../CommonInterfaces/CommonRenderInterface.h" -#include "../OpenGLWindow/GLInstancingRenderer.h" #include "../Importers/ImportURDFDemo/BulletUrdfImporter.h" #include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h" @@ -3108,8 +3107,6 @@ bool PhysicsServerCommandProcessor::processStateLoggingCommand(const struct Shar return hasStatus; } -extern bool useShadowMap; -extern bool useProjectiveTexture; bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) { bool hasStatus = true; @@ -3195,8 +3192,7 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc { if ((flags & ER_USE_PROJECTIVE_TEXTURE) != 0) { - useShadowMap = false; - useProjectiveTexture = true; + this->m_data->m_guiHelper->setProjectiveTexture(true); if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_PROJECTIVE_TEXTURE_MATRICES)!=0) { for (int i=0;i<16;i++) @@ -3217,8 +3213,7 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc } else { - useShadowMap = true; - useProjectiveTexture = false; + this->m_data->m_guiHelper->setProjectiveTexture(false); } m_data->m_guiHelper->copyCameraImageData(viewMat, diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 01c712af0..0d2908ae5 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -1124,6 +1124,11 @@ public: { m_childGuiHelper->getAppInterface()->m_renderer->setProjectiveTextureMatrices(viewMatrix, projectionMatrix); } + + virtual void setProjectiveTexture(bool useProjectiveTexture) + { + m_childGuiHelper->getAppInterface()->m_renderer->setProjectiveTexture(useProjectiveTexture); + } btDiscreteDynamicsWorld* m_dynamicsWorld; diff --git a/test/SharedMemory/CMakeLists.txt b/test/SharedMemory/CMakeLists.txt index e41b2c06d..e0798123f 100644 --- a/test/SharedMemory/CMakeLists.txt +++ b/test/SharedMemory/CMakeLists.txt @@ -16,7 +16,7 @@ IF (USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD) ENDIF() LINK_LIBRARIES( - BulletInverseDynamicsUtils BulletInverseDynamics BulletFileLoader BulletWorldImporter Bullet3Common BulletDynamics BulletCollision LinearMath gtest OpenGLWindow BussIK + BulletInverseDynamicsUtils BulletInverseDynamics BulletFileLoader BulletWorldImporter Bullet3Common BulletDynamics BulletCollision LinearMath gtest BussIK ) IF (NOT WIN32)