implement pybullet.getDebugVisualizerCamera, width, height, providing viewmatrix, projection matrix
This commit is contained in:
@@ -24,6 +24,8 @@ struct CommonCameraInterface
|
||||
|
||||
virtual void setCameraUpVector(float x,float y, float z) = 0;
|
||||
virtual void getCameraUpVector(float up[3]) const = 0;
|
||||
virtual void getCameraForwardVector(float fwd[3]) const = 0;
|
||||
|
||||
///the setCameraUpAxis will call the 'setCameraUpVector' and 'setCameraForwardVector'
|
||||
virtual void setCameraUpAxis(int axis) = 0;
|
||||
virtual int getCameraUpAxis() const = 0;
|
||||
|
||||
@@ -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],
|
||||
|
||||
Reference in New Issue
Block a user