$search
00001 00010 #ifndef TG_CAMERA 00011 #define TG_CAMERA 00012 00013 #include <blort/TomGine/headers.h> 00014 00015 #include <blort/TomGine/tgVector3.h> 00016 #include <blort/TomGine/tgFrustum.h> 00017 #include <blort/TomGine/tgMathlib.h> 00018 #include <blort/TomGine/tgPose.h> 00019 #include <sensor_msgs/CameraInfo.h> 00020 00021 #define GL_ORTHO 0 00022 #define GL_PERSPECTIVE 1 00023 00024 namespace TomGine{ 00025 00029 class tgCamera 00030 { 00031 private: 00032 // tgCamera definition 00033 tgVector3 m_vPos; // Position of tgCamera (absolute) 00034 tgVector3 m_vView; // Viewpoint of tgCamera (absolute) 00035 tgVector3 m_vUp; // The tgCameras upside (relative) 00036 00037 tgVector3 f; // Vector of camera pointing forward 00038 tgVector3 s; // Vector of camera pointing sidewards (right) 00039 tgVector3 u; // Vector of camera pointing up 00040 00041 unsigned m_width, m_height; 00042 float m_fovy; 00043 float m_zNear, m_zFar; 00044 unsigned short m_projection; 00045 mat4 m_extrinsic; 00046 mat4 m_intrinsic; 00047 00048 tgFrustum m_frustum; 00049 00050 public: 00051 tgCamera(); 00052 00053 struct Parameter{ 00054 Parameter(); 00055 Parameter(const sensor_msgs::CameraInfo& cam_info); 00056 void setPose(const TomGine::tgPose& camPose); 00057 // image dimension 00058 unsigned width; 00059 unsigned height; 00060 // Instrinsic parameters: 00061 // entries of the camera matrix 00062 float fx; 00063 float fy; 00064 float cx; 00065 float cy; 00066 // radial distortion parameters 00067 float k1; 00068 float k2; 00069 float k3; 00070 // tangential distortion parameters 00071 float p1; 00072 float p2; 00073 // extrinsic parameters: 3D pose of camera w.r.t. world 00074 mat3 rot; 00075 vec3 pos; 00076 // Clipping planes of virtual camera 00077 float zNear; 00078 float zFar; 00079 00080 void print(){ 00081 printf("%d %d\n", width, height); 00082 printf("%f %f\n", fx, fy); 00083 printf("%f %f\n", cx, cy); 00084 printf("%f %f %f\n", k1, k2, k3); 00085 printf("%f %f\n", p1, p2); 00086 printf("\n %f %f %f\n", rot.mat[0], rot.mat[1], rot.mat[2]); 00087 printf(" %f %f %f\n", rot.mat[3], rot.mat[4], rot.mat[5]); 00088 printf(" %f %f %f\n", rot.mat[6], rot.mat[7], rot.mat[8]); 00089 printf("\n %f %f %f\n", pos.x, pos.y, pos.z); 00090 printf("%f %f\n", zNear, zFar); 00091 } 00092 }; 00093 00094 void Load(tgCamera::Parameter camPar); 00095 00096 // Define tgCamera 00097 void Set( float posx, float posy, float posz, 00098 float viewx, float viewy, float viewz, 00099 float upx, float upy, float upz, 00100 float fovy=45.0f, unsigned width=800, unsigned height=600, 00101 float zNear=0.1f, float zFar=100.0f, 00102 unsigned short projection=GL_PERSPECTIVE ); 00103 void SetExtrinsic(float* M); 00104 void SetIntrinsic(float* M); 00105 void SetIntrinsic(float fovy, unsigned width, unsigned height, float zNear, float zFar, unsigned short projection); 00106 void SetViewport(unsigned w, unsigned h); 00107 void SetZRange(float near, float far); 00108 void SetPerspective(){m_projection=GL_PERSPECTIVE;} 00109 void SetOrtho(){m_projection=GL_ORTHO;} 00110 void SetPos(float x, float y, float z){ m_vPos.x=x; m_vPos.y=y; m_vPos.z=z; } 00111 00112 vec2 ToImageSpace(const vec3 &world_space); 00113 00114 void Activate(); 00115 void Print(); 00116 00117 void pvu2fsu(); 00118 void fsu2pvu(); 00119 void fsu2extrinsic(); 00120 void extrinsic2fsu(); 00121 void fwh2intrinsic(); 00122 00123 // Gets 00124 TomGine::tgPose GetPose(); 00125 00126 tgVector3 GetF(){return f;} 00127 tgVector3 GetS(){return s;} 00128 tgVector3 GetU(){return u;} 00129 00130 tgVector3 GetPos(){return m_vPos;} 00131 tgVector3 GetView(){return m_vView;} 00132 tgVector3 GetUp(){return m_vUp;} 00133 00134 float GetZNear(){ return m_zNear; } 00135 float GetZFar(){ return m_zFar; } 00136 unsigned GetWidth(){ return m_width; } 00137 unsigned GetHeight(){return m_height; } 00138 00139 float GetFOVY(){ return m_fovy; } 00140 unsigned short GetProjection(){ return m_projection; } 00141 mat4 GetIntrinsic(){ return m_intrinsic; } 00142 mat4 GetExtrinsic(){ return m_extrinsic; } 00143 00144 tgFrustum* GetFrustum(){ return &m_frustum; } 00145 00146 // Translations 00147 void Translate(tgVector3 v); 00148 void Translate(float x, float y, float z, float fWay); 00149 void TranslateF(float fWay); 00150 void TranslateS(float fWay); 00151 void TranslateU(float fWay); 00152 00153 // Rotations 00154 void Rotate(float x, float y, float z, float fAngle); 00155 void RotateF(float fAngle); 00156 void RotateS(float fAngle); 00157 void RotateU(float fAngle); 00158 00159 void RotateX(float fAngle); 00160 void RotateY(float fAngle); 00161 void RotateZ(float fAngle); 00162 00163 void Orbit(tgVector3 vPoint, tgVector3 vAxis, float fAngle); 00164 00165 // Movement 00166 void ApplyTransform(); 00167 00168 void DrawFrustum(){ m_frustum.DrawFrustum(); } 00169 00170 }; 00171 00172 } // namespace TomGine 00173 00174 #endif