add pybullet render API with yaw/pitch/roll option
add testrender.py file allow option to enable OpenGL hardware renderer in multithreaded sim b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL);
This commit is contained in:
@@ -825,7 +825,7 @@ void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHa
|
||||
command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES;
|
||||
}
|
||||
|
||||
void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, int upAxis)
|
||||
void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
@@ -834,47 +834,78 @@ void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandl
|
||||
b3Vector3 camForward;
|
||||
b3Vector3 camPos;
|
||||
b3Vector3 camTargetPos = b3MakeVector3(cameraTargetPosition[0],cameraTargetPosition[1],cameraTargetPosition[2]);
|
||||
|
||||
b3Vector3 eyePos = b3MakeVector3(0,0,0);
|
||||
|
||||
int forwardAxis(-1);
|
||||
|
||||
{
|
||||
|
||||
switch (upAxis)
|
||||
{
|
||||
case 1:
|
||||
forwardAxis = 2;
|
||||
camUpVector = b3MakeVector3(0,1,0);
|
||||
//gLightPos = b3MakeVector3(-50.f,100,30);
|
||||
break;
|
||||
case 2:
|
||||
forwardAxis = 1;
|
||||
camUpVector = b3MakeVector3(0,0,1);
|
||||
//gLightPos = b3MakeVector3(-50.f,30,100);
|
||||
break;
|
||||
default:
|
||||
{
|
||||
//b3Assert(0);
|
||||
return;
|
||||
}
|
||||
};
|
||||
|
||||
b3Vector3 eyePos = b3MakeVector3(0,0,0);
|
||||
eyePos[forwardAxis] = -distance;
|
||||
|
||||
camForward = b3MakeVector3(eyePos[0],eyePos[1],eyePos[2]);
|
||||
if (camForward.length2() < B3_EPSILON)
|
||||
{
|
||||
camForward.setValue(1.f,0.f,0.f);
|
||||
} else
|
||||
{
|
||||
camForward.normalize();
|
||||
|
||||
case 1:
|
||||
{
|
||||
|
||||
|
||||
forwardAxis = 0;
|
||||
eyePos[forwardAxis] = -distance;
|
||||
camForward = b3MakeVector3(eyePos[0],eyePos[1],eyePos[2]);
|
||||
if (camForward.length2() < B3_EPSILON)
|
||||
{
|
||||
camForward.setValue(1.f,0.f,0.f);
|
||||
} else
|
||||
{
|
||||
camForward.normalize();
|
||||
}
|
||||
b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547);
|
||||
b3Quaternion rollRot(camForward,rollRad);
|
||||
|
||||
camUpVector = b3QuatRotate(rollRot,b3MakeVector3(0,1,0));
|
||||
//gLightPos = b3MakeVector3(-50.f,100,30);
|
||||
break;
|
||||
}
|
||||
case 2:
|
||||
{
|
||||
|
||||
|
||||
forwardAxis = 1;
|
||||
eyePos[forwardAxis] = -distance;
|
||||
camForward = b3MakeVector3(eyePos[0],eyePos[1],eyePos[2]);
|
||||
if (camForward.length2() < B3_EPSILON)
|
||||
{
|
||||
camForward.setValue(1.f,0.f,0.f);
|
||||
} else
|
||||
{
|
||||
camForward.normalize();
|
||||
}
|
||||
|
||||
b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547);
|
||||
b3Quaternion rollRot(camForward,rollRad);
|
||||
|
||||
camUpVector = b3QuatRotate(rollRot,b3MakeVector3(0,0,1));
|
||||
//gLightPos = b3MakeVector3(-50.f,30,100);
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
//b3Assert(0);
|
||||
return;
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
b3Scalar rele = yaw * b3Scalar(0.01745329251994329547);// rads per deg
|
||||
b3Scalar razi = pitch * b3Scalar(0.01745329251994329547);// rads per deg
|
||||
b3Quaternion rot(camUpVector,razi);
|
||||
b3Scalar yawRad = yaw * b3Scalar(0.01745329251994329547);// rads per deg
|
||||
b3Scalar pitchRad = pitch * b3Scalar(0.01745329251994329547);// rads per deg
|
||||
|
||||
b3Quaternion pitchRot(camUpVector,pitchRad);
|
||||
|
||||
b3Vector3 right = camUpVector.cross(camForward);
|
||||
b3Quaternion roll(right,-rele);
|
||||
b3Quaternion yawRot(right,-yawRad);
|
||||
|
||||
|
||||
|
||||
eyePos = b3Matrix3x3(rot) * b3Matrix3x3(roll) * eyePos;
|
||||
eyePos = b3Matrix3x3(pitchRot) * b3Matrix3x3(yawRot) * eyePos;
|
||||
camPos = eyePos;
|
||||
camPos += camTargetPos;
|
||||
|
||||
|
||||
@@ -71,7 +71,7 @@ void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* l
|
||||
b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient);
|
||||
void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]);
|
||||
void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle command, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]);
|
||||
void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, int upAxis);
|
||||
void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis);
|
||||
void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle command, float left, float right, float bottom, float top, float nearVal, float farVal);
|
||||
void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle command, float fov, float aspect, float nearVal, float farVal);
|
||||
void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height );
|
||||
|
||||
@@ -259,15 +259,15 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle);
|
||||
//b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL);
|
||||
|
||||
float viewMatrix[16];
|
||||
float projectionMatrix[16];
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
|
||||
float viewMatrix[16];
|
||||
float projectionMatrix[16];
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix);
|
||||
|
||||
b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix);
|
||||
b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
break;
|
||||
b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
break;
|
||||
}
|
||||
case CMD_CREATE_BOX_COLLISION_SHAPE:
|
||||
{
|
||||
|
||||
@@ -609,7 +609,7 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
{
|
||||
SharedMemoryCommand& command = m_data->m_testBlock1->m_clientCommands[0];
|
||||
|
||||
if (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0)
|
||||
if (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0 && serverCmd.m_sendPixelDataArguments.m_numPixelsCopied)
|
||||
{
|
||||
|
||||
|
||||
|
||||
@@ -225,7 +225,7 @@ bool PhysicsDirect::processCamera(const struct SharedMemoryCommand& orgCommand)
|
||||
= rgbaPixelsReceived[i];
|
||||
}
|
||||
|
||||
if (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0)
|
||||
if (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0 && serverCmd.m_sendPixelDataArguments.m_numPixelsCopied)
|
||||
{
|
||||
|
||||
|
||||
@@ -241,7 +241,7 @@ bool PhysicsDirect::processCamera(const struct SharedMemoryCommand& orgCommand)
|
||||
m_data->m_cachedCameraPixelsHeight = serverCmd.m_sendPixelDataArguments.m_imageHeight;
|
||||
}
|
||||
}
|
||||
} while (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0);
|
||||
} while (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0 && serverCmd.m_sendPixelDataArguments.m_numPixelsCopied);
|
||||
|
||||
return m_data->m_hasStatus;
|
||||
|
||||
|
||||
@@ -43,6 +43,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
|
||||
eGUIHelperCreateCollisionShapeGraphicsObject,
|
||||
eGUIHelperCreateCollisionObjectGraphicsObject,
|
||||
eGUIHelperRemoveAllGraphicsInstances,
|
||||
eGUIHelperCopyCameraImageData,
|
||||
};
|
||||
|
||||
#include <stdio.h>
|
||||
@@ -392,11 +393,41 @@ public:
|
||||
{
|
||||
}
|
||||
|
||||
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int width, int height, int* numPixelsCopied)
|
||||
float m_viewMatrix[16];
|
||||
float m_projectionMatrix[16];
|
||||
unsigned char* m_pixelsRGBA;
|
||||
int m_rgbaBufferSizeInPixels;
|
||||
float* m_depthBuffer;
|
||||
int m_depthBufferSizeInPixels;
|
||||
int m_startPixelIndex;
|
||||
int m_destinationWidth;
|
||||
int m_destinationHeight;
|
||||
int* m_numPixelsCopied;
|
||||
|
||||
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied)
|
||||
{
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = 0;
|
||||
m_cs->lock();
|
||||
for (int i=0;i<16;i++)
|
||||
{
|
||||
m_viewMatrix[i] = viewMatrix[i];
|
||||
m_projectionMatrix[i] = projectionMatrix[i];
|
||||
}
|
||||
m_pixelsRGBA = pixelsRGBA;
|
||||
m_rgbaBufferSizeInPixels = rgbaBufferSizeInPixels;
|
||||
m_depthBuffer = depthBuffer;
|
||||
m_depthBufferSizeInPixels = depthBufferSizeInPixels;
|
||||
m_startPixelIndex = startPixelIndex;
|
||||
m_destinationWidth = destinationWidth;
|
||||
m_destinationHeight = destinationHeight;
|
||||
m_numPixelsCopied = numPixelsCopied;
|
||||
|
||||
m_cs->setSharedParam(1,eGUIHelperCopyCameraImageData);
|
||||
m_cs->unlock();
|
||||
while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld)
|
||||
{
|
||||
@@ -727,6 +758,24 @@ void PhysicsServerExample::stepSimulation(float deltaTime)
|
||||
m_multiThreadedHelper->getCriticalSection()->unlock();
|
||||
break;
|
||||
}
|
||||
|
||||
case eGUIHelperCopyCameraImageData:
|
||||
{
|
||||
m_multiThreadedHelper->m_childGuiHelper->copyCameraImageData(m_multiThreadedHelper->m_viewMatrix,
|
||||
m_multiThreadedHelper->m_projectionMatrix,
|
||||
m_multiThreadedHelper->m_pixelsRGBA,
|
||||
m_multiThreadedHelper->m_rgbaBufferSizeInPixels,
|
||||
m_multiThreadedHelper->m_depthBuffer,
|
||||
m_multiThreadedHelper->m_depthBufferSizeInPixels,
|
||||
m_multiThreadedHelper->m_startPixelIndex,
|
||||
m_multiThreadedHelper->m_destinationWidth,
|
||||
m_multiThreadedHelper->m_destinationHeight,
|
||||
m_multiThreadedHelper->m_numPixelsCopied);
|
||||
m_multiThreadedHelper->getCriticalSection()->lock();
|
||||
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
|
||||
m_multiThreadedHelper->getCriticalSection()->unlock();
|
||||
break;
|
||||
}
|
||||
case eGUIHelperIdle:
|
||||
default:
|
||||
{
|
||||
|
||||
Reference in New Issue
Block a user