implement pybullet.getDebugVisualizerCamera, width, height, providing viewmatrix, projection matrix
This commit is contained in:
@@ -190,6 +190,11 @@ struct CommonRenderInterface* OpenGLGuiHelper::getRenderInterface()
|
||||
return m_data->m_glApp->m_renderer;
|
||||
}
|
||||
|
||||
const struct CommonRenderInterface* OpenGLGuiHelper::getRenderInterface() const
|
||||
{
|
||||
return m_data->m_glApp->m_renderer;
|
||||
}
|
||||
|
||||
void OpenGLGuiHelper::createRigidBodyGraphicsObject(btRigidBody* body, const btVector3& color)
|
||||
{
|
||||
createCollisionObjectGraphicsObject(body,color);
|
||||
@@ -386,6 +391,57 @@ void OpenGLGuiHelper::resetCamera(float camDist, float pitch, float yaw, float c
|
||||
}
|
||||
}
|
||||
|
||||
bool OpenGLGuiHelper::getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3] ) const
|
||||
{
|
||||
if (getRenderInterface() && getRenderInterface()->getActiveCamera())
|
||||
{
|
||||
*width = m_data->m_glApp->m_window->getWidth()*m_data->m_glApp->m_window->getRetinaScale();
|
||||
*height = m_data->m_glApp->m_window->getHeight()*m_data->m_glApp->m_window->getRetinaScale();
|
||||
getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix);
|
||||
getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
|
||||
getRenderInterface()->getActiveCamera()->getCameraUpVector(camUp);
|
||||
getRenderInterface()->getActiveCamera()->getCameraForwardVector(camForward);
|
||||
float frustumNearPlane = getRenderInterface()->getActiveCamera()->getCameraFrustumNear();
|
||||
float frustumFarPlane = getRenderInterface()->getActiveCamera()->getCameraFrustumFar();
|
||||
|
||||
float top = 1.f;
|
||||
float bottom = -1.f;
|
||||
float tanFov = (top-bottom)*0.5f / frustumNearPlane;
|
||||
float fov = btScalar(2.0) * btAtan(tanFov);
|
||||
btVector3 camPos,camTarget;
|
||||
getRenderInterface()->getActiveCamera()->getCameraPosition(camPos);
|
||||
getRenderInterface()->getActiveCamera()->getCameraTargetPosition(camTarget);
|
||||
btVector3 rayFrom = camPos;
|
||||
btVector3 rayForward = (camTarget-camPos);
|
||||
rayForward.normalize();
|
||||
float farPlane = 10000.f;
|
||||
rayForward*= farPlane;
|
||||
|
||||
btVector3 rightOffset;
|
||||
btVector3 cameraUp=btVector3(camUp[0],camUp[1],camUp[2]);
|
||||
btVector3 vertical = cameraUp;
|
||||
btVector3 hori;
|
||||
hori = rayForward.cross(vertical);
|
||||
hori.normalize();
|
||||
vertical = hori.cross(rayForward);
|
||||
vertical.normalize();
|
||||
float tanfov = tanf(0.5f*fov);
|
||||
hori *= 2.f * farPlane * tanfov;
|
||||
vertical *= 2.f * farPlane * tanfov;
|
||||
btScalar aspect = *width / *height;
|
||||
hori*=aspect;
|
||||
//compute 'hor' and 'vert' vectors, useful to generate raytracer rays
|
||||
hor[0] = hori[0];
|
||||
hor[1] = hori[1];
|
||||
hor[2] = hori[2];
|
||||
vert[0] = vertical[0];
|
||||
vert[1] = vertical[1];
|
||||
vert[2] = vertical[2];
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],
|
||||
unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
|
||||
|
||||
@@ -15,6 +15,7 @@ struct OpenGLGuiHelper : public GUIHelperInterface
|
||||
virtual ~OpenGLGuiHelper();
|
||||
|
||||
virtual struct CommonRenderInterface* getRenderInterface();
|
||||
virtual const struct CommonRenderInterface* getRenderInterface() const;
|
||||
|
||||
virtual void createRigidBodyGraphicsObject(btRigidBody* body, const btVector3& color);
|
||||
|
||||
@@ -44,7 +45,8 @@ struct OpenGLGuiHelper : public GUIHelperInterface
|
||||
|
||||
|
||||
virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ);
|
||||
|
||||
virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3] ) const;
|
||||
|
||||
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],
|
||||
unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
|
||||
float* depthBuffer, int depthBufferSizeInPixels,
|
||||
|
||||
Reference in New Issue
Block a user