Expose using projective texture as a flag in pybullet getCameraImage API.

This commit is contained in:
yunfeibai
2018-03-18 17:01:23 -07:00
parent 680ce39e96
commit fd7aa8d0e1
9 changed files with 23 additions and 6 deletions

View File

@@ -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
)

View File

@@ -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*/]);

View File

@@ -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,

View File

@@ -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
{