From fd7aa8d0e182d132f8c322971f7695c695263ba7 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Sun, 18 Mar 2018 17:01:23 -0700 Subject: [PATCH] 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)