ATANCamera.h
Go to the documentation of this file.
00001 // *-* c++ *-*
00002 // Copyright 2008 Isis Innovation Limited
00003 
00004 // N-th implementation of a camera model
00005 // GK 2007
00006 // Evolved a half dozen times from the CVD-like model I was given by
00007 // TWD in 2000
00008 // 
00009 // This one uses the ``FOV'' distortion model of
00010 // Deverneay and Faugeras, Straight lines have to be straight, 2001
00011 //
00012 // BEWARE: This camera model caches intermediate results in member variables
00013 // Some functions therefore depend on being called in order: i.e.
00014 // GetProjectionDerivs() uses data stored from the last Project() or UnProject()
00015 // THIS MEANS YOU MUST BE CAREFUL WITH MULTIPLE THREADS
00016 // Best bet is to give each thread its own version of the camera!
00017 //
00018 // Camera parameters are stored in a GVar, but changing the gvar has no effect
00019 // until the next call to RefreshParams() or SetImageSize().
00020 //
00021 // Pixel conventions are as follows:
00022 // For Project() and Unproject(),
00023 // round pixel values - i.e. (0.0, 0.0) - refer to pixel centers
00024 // I.e. the top left pixel in the image covers is centered on (0,0)
00025 // and covers the area (-.5, -.5) to (.5, .5)
00026 //
00027 // Be aware that this is not the same as what opengl uses but makes sense
00028 // for acessing pixels using ImageRef, especially ir_rounded.
00029 //
00030 // What is the UFB?
00031 // This is for projecting the visible image area
00032 // to a unit square coordinate system, with the top-left at 0,0,
00033 // and the bottom-right at 1,1
00034 // This is useful for rendering into textures! The top-left pixel is NOT
00035 // centered at 0,0, rather the top-left corner of the top-left pixel is at 
00036 // 0,0!!! This is the way OpenGL thinks of pixel coords.
00037 // There's the Linear and the Distorting version - 
00038 // For the linear version, can use 
00039 // glMatrixMode(GL_PROJECTION); glLoadIdentity();
00040 // glMultMatrix(Camera.MakeUFBLinearFrustumMatrix(near,far));
00041 // To render un-distorted geometry with full frame coverage.
00042 //
00043 
00044 #ifndef __ATAN_CAMERA_H
00045 #define __ATAN_CAMERA_H
00046 
00047 #include <TooN/TooN.h>
00048 #include <cmath>
00049 using namespace TooN;
00050 #include <cvd/vector_image_ref.h>
00051 #include <gvars3/gvars3.h>
00052 
00053 
00054 #define NUMTRACKERCAMPARAMETERS 5
00055 
00056 class CameraCalibrator;
00057 class CalibImage;
00058 
00059 // The parameters are:
00060 // 0 - normalized x focal length
00061 // 1 - normalized y focal length
00062 // 2 - normalized x offset
00063 // 3 - normalized y offset
00064 // 4 - w (distortion parameter)
00065 
00066 class ATANCamera {
00067  public:
00068   ATANCamera(TooN::Vector<5> params);
00069 
00070   // Image size get/set: updates the internal projection params to that target image size.
00071   void SetImageSize(Vector<2> v2ImageSize);
00072   inline void SetImageSize(CVD::ImageRef irImageSize) {SetImageSize(vec(irImageSize));};
00073   inline Vector<2> GetImageSize() {return mvImageSize;};
00074   void RefreshParams();
00075   
00076   // Various projection functions
00077   Vector<2> Project(const Vector<2>& camframe); // Projects from camera z=1 plane to pixel coordinates, with radial distortion
00078   inline Vector<2> Project(CVD::ImageRef ir) { return Project(vec(ir)); }
00079   Vector<2> UnProject(const Vector<2>& imframe); // Inverse operation
00080   inline Vector<2> UnProject(CVD::ImageRef ir)  { return UnProject(vec(ir)); }
00081   
00082   Vector<2> UFBProject(const Vector<2>& camframe);
00083   Vector<2> UFBUnProject(const Vector<2>& camframe);
00084   inline Vector<2> UFBLinearProject(const Vector<2>& camframe);
00085   inline Vector<2> UFBLinearUnProject(const Vector<2>& fbframe);
00086   
00087   Matrix<2,2> GetProjectionDerivs(); // Projection jacobian
00088   
00089   inline bool Invalid() {  return mbInvalid;}
00090   inline double LargestRadiusInImage() {  return mdLargestRadius; }
00091   inline double OnePixelDist() { return mdOnePixelDist; }
00092   
00093   // The z=1 plane bounding box of what the camera can see
00094   inline Vector<2> ImplaneTL(); 
00095   inline Vector<2> ImplaneBR(); 
00096 
00097   // OpenGL helper function
00098   Matrix<4> MakeUFBLinearFrustumMatrix(double near, double far);
00099 
00100   // Feedback for Camera Calibrator
00101   double PixelAspectRatio() { return mvFocal[1] / mvFocal[0];}
00102   
00103   
00104   // Useful for gvar-related reasons (in case some external func tries to read the camera params gvar, and needs some defaults.)
00105   static const Vector<NUMTRACKERCAMPARAMETERS> mvDefaultParams;
00106   
00107  protected:
00108   GVars3::gvar3<Vector<NUMTRACKERCAMPARAMETERS> > mgvvCameraParams; // The actual camera parameters
00109   
00110   Matrix<2, NUMTRACKERCAMPARAMETERS> GetCameraParameterDerivs();
00111   void UpdateParams(Vector<NUMTRACKERCAMPARAMETERS> vUpdate);
00112   void DisableRadialDistortion();
00113   
00114   // Cached from the last project/unproject:
00115   Vector<2> mvLastCam;      // Last z=1 coord
00116   Vector<2> mvLastIm;       // Last image/UFB coord
00117   Vector<2> mvLastDistCam;  // Last distorted z=1 coord
00118   double mdLastR;           // Last z=1 radius
00119   double mdLastDistR;       // Last z=1 distorted radius
00120   double mdLastFactor;      // Last ratio of z=1 radii
00121   bool mbInvalid;           // Was the last projection invalid?
00122   
00123   // Cached from last RefreshParams:
00124   double mdLargestRadius; // Largest R in the image
00125   double mdMaxR;          // Largest R for which we consider projection valid
00126   double mdOnePixelDist;  // z=1 distance covered by a single pixel offset (a rough estimate!)
00127   double md2Tan;          // distortion model coeff
00128   double mdOneOver2Tan;   // distortion model coeff
00129   double mdW;             // distortion model coeff
00130   double mdWinv;          // distortion model coeff
00131   double mdDistortionEnabled; // One or zero depending on if distortion is on or off.
00132   Vector<2> mvCenter;     // Pixel projection center
00133   Vector<2> mvFocal;      // Pixel focal length
00134   Vector<2> mvInvFocal;   // Inverse pixel focal length
00135   Vector<2> mvImageSize;  
00136   Vector<2> mvUFBLinearFocal;
00137   Vector<2> mvUFBLinearInvFocal;
00138   Vector<2> mvUFBLinearCenter;
00139   Vector<2> mvImplaneTL;   
00140   Vector<2> mvImplaneBR;
00141   
00142   // Radial distortion transformation factor: returns ration of distorted / undistorted radius.
00143   inline double rtrans_factor(double r)
00144   {
00145     if(r < 0.001 || mdW == 0.0)
00146       return 1.0;
00147     else 
00148       return (mdWinv* atan(r * md2Tan) / r);
00149   };
00150 
00151   // Inverse radial distortion: returns un-distorted radius from distorted.
00152   inline double invrtrans(double r)
00153   {
00154     if(mdW == 0.0)
00155       return r;
00156     return(tan(r * mdW) * mdOneOver2Tan);
00157   };
00158   
00159   std::string msName;
00160 
00161   friend class CameraCalibrator;   // friend declarations allow access to calibration jacobian and camera update function.
00162   friend class CalibImage;
00163 };
00164 
00165 // Some inline projection functions:
00166 inline Vector<2> ATANCamera::UFBLinearProject(const Vector<2>& camframe)
00167 {
00168   Vector<2> v2Res;
00169   v2Res[0] = camframe[0] * mvUFBLinearFocal[0] + mvUFBLinearCenter[0];
00170   v2Res[1] = camframe[1] * mvUFBLinearFocal[1] + mvUFBLinearCenter[1];
00171   return v2Res;
00172 }
00173 
00174 inline Vector<2> ATANCamera::UFBLinearUnProject(const Vector<2>& fbframe)
00175 {
00176   Vector<2> v2Res;
00177   v2Res[0] = (fbframe[0] - mvUFBLinearCenter[0]) * mvUFBLinearInvFocal[0];
00178   v2Res[1] = (fbframe[1] - mvUFBLinearCenter[1]) * mvUFBLinearInvFocal[1];
00179   return v2Res;
00180 }
00181 
00182 
00183 #endif
00184 


tum_ardrone
Author(s):
autogenerated on Sat Jun 8 2019 20:27:22