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

@@ -44,12 +44,22 @@ struct GUIHelperInterface
virtual CommonRenderInterface* getRenderInterface()=0;
virtual const CommonRenderInterface* getRenderInterface() const
{
return 0;
}
virtual CommonGraphicsApp* getAppInterface()=0;
virtual void setUpAxis(int axis)=0;
virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)=0;
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 false;
}
virtual void setVisualizerFlag(int flag, int enable){};
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],