implement pybullet.getDebugVisualizerCamera, width, height, providing viewmatrix, projection matrix

This commit is contained in:
Erwin Coumans
2017-04-10 11:03:41 -07:00
parent 82b6bc8770
commit bdf366b045
16 changed files with 284 additions and 9 deletions

View File

@@ -808,6 +808,12 @@ public:
m_childGuiHelper->resetCamera(camDist,pitch,yaw,camPosX,camPosY,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
{
return m_childGuiHelper->getCameraInfo(width,height,viewMatrix,projectionMatrix,camUp,camForward,hor,vert);
}
float m_viewMatrix[16];
float m_projectionMatrix[16];
unsigned char* m_pixelsRGBA;