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

@@ -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;