Add Bullet C API and pybullet API to set projective texture matrices.
This commit is contained in:
@@ -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]);
|
||||
|
||||
@@ -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
|
||||
{
|
||||
|
||||
@@ -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;
|
||||
|
||||
|
||||
@@ -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
|
||||
|
||||
|
||||
Reference in New Issue
Block a user