camera.h
Go to the documentation of this file.
00001 /****************************************************************************
00002 * VCGLib                                                            o o     *
00003 * Visual and Computer Graphics Library                            o     o   *
00004 *                                                                _   O  _   *
00005 * Copyright(C) 2004                                                \/)\/    *
00006 * Visual Computing Lab                                            /\/|      *
00007 * ISTI - Italian National Research Council                           |      *
00008 *                                                                    \      *
00009 * All rights reserved.                                                      *
00010 *                                                                           *
00011 * This program is free software; you can redistribute it and/or modify      *
00012 * it under the terms of the GNU General Public License as published by      *
00013 * the Free Software Foundation; either version 2 of the License, or         *
00014 * (at your option) any later version.                                       *
00015 *                                                                           *
00016 * This program is distributed in the hope that it will be useful,           *
00017 * but WITHOUT ANY WARRANTY; without even the implied warranty of            *
00018 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the             *
00019 * GNU General Public License (http://www.gnu.org/licenses/gpl.txt)          *
00020 * for more details.                                                         *
00021 *                                                                           *
00022 ****************************************************************************/
00023 /****************************************************************************
00024   History
00025 $Log: not supported by cvs2svn $
00026 
00027 Revision 1.28  2008/09/09 11:13:27  dellepiane
00028 new functions to handle distortion: should not affect previous stuff. tested but still error prone...
00029 
00030 Revision 1.28  2006/12/21 00:13:27  cignoni
00031 Corrected a syntax error detected only by gcc.
00032 Corrected the order of initialization in the constructor to match the declaration order
00033 
00034 Revision 1.27  2006/12/18 16:02:55  matteodelle
00035 minor eroor correction on variable names
00036 
00037 Revision 1.26  2006/12/18 09:46:38  callieri
00038 camera+shot revamp: changed field names to something with more sense, cleaning of various functions, correction of minor bugs/incongruences, removal of the infamous reference in shot.
00039 
00040 Revision 1.25  2005/12/12 16:52:55  callieri
00041 Added Unproject, from 2D local space + Zdepth to 3D camera space. Added ViewportToLocal, inverse of LocalToViewport
00042 
00043 Revision 1.24  2005/12/01 01:03:37  cignoni
00044 Removed excess ';' from end of template functions, for gcc compiling
00045 
00046 Revision 1.23  2005/10/12 16:43:32  ponchio
00047 Added IsOrtho...
00048 
00049 Revision 1.22  2005/07/11 13:12:34  cignoni
00050 small gcc-related compiling issues (typenames,ending cr, initialization order)
00051 
00052 Revision 1.21  2005/07/01 10:55:42  cignoni
00053 Removed default values from the implementation of SetCavalieri and SetIsometric
00054 
00055 Revision 1.20  2005/06/29 14:59:03  spinelli
00056 aggiunto:
00057 - l' enum dei tipi  PERSPECTIVE,  ORTHO, ISOMETRIC,  CAVALIERI
00058 - inline void SetCavalieri(...)
00059 - inline void SetIsometric(...)
00060 
00061 - modificato
00062 - void SetOrtho( .. )
00063 
00064 Revision 1.19  2005/02/22 10:57:58  tommyfranken
00065 Corrected declaration and some syntax errors in GetFrustum
00066 
00067 Revision 1.18  2005/02/21 18:11:07  ganovelli
00068 GetFrustum moved from gl/camera to math/camera.h
00069 
00070 Revision 1.17  2005/02/15 14:55:52  tommyfranken
00071 added principal point
00072 
00073 Revision 1.16  2005/01/18 16:40:50  ricciodimare
00074 *** empty log message ***
00075 
00076 Revision 1.15  2005/01/18 15:14:22  ponchio
00077 Far and end are reserved.
00078 
00079 Revision 1.14  2005/01/14 15:28:33  ponchio
00080 vcg/Point.h -> vcg/point.h   (again!)
00081 
00082 Revision 1.13  2005/01/05 13:25:29  ganovelli
00083 aggiunte conversione di coordinate
00084 
00085 Revision 1.12  2004/12/16 11:22:30  ricciodimare
00086 *** empty log message ***
00087 
00088 Revision 1.11  2004/12/16 11:21:03  ricciodimare
00089 *** empty log message ***
00090 
00091 Revision 1.10  2004/12/15 18:45:50  tommyfranken
00092 *** empty log message ***
00093 
00094 <<<<<<< camera.h
00095 =======
00096 Revision 1.8  2004/11/23 10:15:38  cignoni
00097 removed comment in comment gcc warning
00098 
00099 Revision 1.7  2004/11/03 09:40:53  ganovelli
00100 Point?.h to point?.h
00101 
00102 Revision 1.6  2004/11/03 09:32:50  ganovelli
00103 SetPerspective and SetFrustum added (same parameters as in opengl)
00104 
00105 >>>>>>> 1.8
00106 Revision 1.4  2004/10/07 14:39:57  fasano
00107 Remove glew.h include
00108 
00109 Revision 1.3  2004/10/07 14:22:38  ganovelli
00110 y axis reverse in projecting (!)
00111 
00112 Revision 1.2  2004/10/05 19:04:25  ganovelli
00113 version 5-10-2004 in progress
00114 
00115 Revision 1.1  2004/09/15 22:58:05  ganovelli
00116 re-creation
00117 
00118 Revision 1.2  2004/09/06 21:41:30  ganovelli
00119 *** empty log message ***
00120 
00121 Revision 1.1  2004/09/03 13:01:51  ganovelli
00122 creation
00123 
00124 ****************************************************************************/
00125 
00126 
00127 #ifndef __VCGLIB_CAMERA
00128 #define __VCGLIB_CAMERA
00129 
00130 // VCG
00131 #include <vcg/space/point3.h>
00132 #include <vcg/space/point2.h>
00133 #include <vcg/math/similarity.h>
00134 
00135 
00136 
00137 namespace vcg{
00138 
00139 
00140 template<class S>
00141 class Camera
00142 {
00143 public:
00144     typedef S ScalarType;
00145     enum {
00146         PERSPECTIVE =   0,
00147         ORTHO       =   1,
00148         ISOMETRIC       =   2,
00149         CAVALIERI       =   3
00150     };
00151 
00152     Camera():
00153         FocalMm(0.f),
00154         ViewportPx(vcg::Point2<int>(0,0)),
00155         PixelSizeMm(vcg::Point2<S>(0.0,0.0)),
00156         CenterPx(vcg::Point2<S>(0.0,0.0)),
00157         DistorCenterPx(vcg::Point2<S>(0.0,0.0)),
00158         cameraType(0)
00159     {
00160         k[0] = k[1] = k[2] = k[3] = 0;
00161     }
00162 
00163     //------ camera intrinsics
00164     ScalarType  FocalMm;                        
00165     Point2<int> ViewportPx;                     
00166     Point2<S>   PixelSizeMm;            
00167     Point2<S>   CenterPx;                       
00168 
00169     Point2<S>   DistorCenterPx;         
00170     S                   k[4];                           
00171     //------------------------
00172 
00173     int cameraType;                                     
00174 
00175 
00176 
00177     template <class Q>
00178     static inline Camera Construct( const Camera<Q> &t)
00179     {
00180       Camera n;
00181       n.FocalMm = t.FocalMm;
00182       n.ViewportPx.Import(t.ViewportPx);
00183       n.PixelSizeMm.Import(t.PixelSizeMm);
00184       n.CenterPx.Import(t.CenterPx);
00185       n.DistorCenterPx.Import(t.DistorCenterPx);
00186       n.cameraType =t.cameraType;
00187       n.k[0] = t.k[0];
00188       n.k[1] = t.k[1];
00189       n.k[2] = t.k[2];
00190       n.k[3] = t.k[3];
00191       return n;
00192     }
00193 
00194     void SetOrtho( S l,S r, S b, S t,  vcg::Point2<int> viewport)
00195     {
00196         cameraType = ORTHO;
00197         ViewportPx = viewport;
00198 
00199         PixelSizeMm[0] = (r-l) / (S)ViewportPx[0];
00200         PixelSizeMm[1] = (t-b) / (S)ViewportPx[1];
00201 
00202         CenterPx[0] = -l/(r-l) * (S)ViewportPx[0];
00203         CenterPx[1] = -b/(t-b) * (S)ViewportPx[1];
00204 
00205     };
00206 
00207 
00208     bool IsOrtho() const
00209     {
00210         return ( cameraType == ORTHO );
00211     }
00212 
00213     //--- Set-up methods
00214 
00216     inline void SetPerspective(S AngleDeg, S AspectRatio, S Focal, vcg::Point2<int> Viewport);
00217 
00219     inline void SetCavalieri(S sx, S dx, S bt, S tp, S Focal, vcg::Point2<int> Viewport);
00220 
00222     inline void SetIsometric(S sx, S dx, S bt, S tp, S Focal, vcg::Point2<int> Viewport);
00223 
00225     inline void SetFrustum(S dx, S sx, S bt, S tp, S Focal, vcg::Point2<int> Viewport);
00226     //------------------
00227 
00229     vcg::Matrix44<S> GetMatrix(S nearVal, S farVal);
00230 
00232     inline void GetFrustum(S & sx, S & dx, S & bt, S & tp, S & nr);
00233 
00234     //--- Space transformation methods
00235 
00237     inline vcg::Point2<S> Project(const vcg::Point3<S> & p) const;
00238 
00240     inline vcg::Point3<S> UnProject(const vcg::Point2<S> & p, const S & d) const;
00241 
00243     inline vcg::Point2<S> LocalToViewportPx(const vcg::Point2<S> & p) const;
00244 
00246     inline vcg::Point2<S> ViewportPxToLocal(const vcg::Point2<S> & p) const;
00247 
00249     inline vcg::Point2<S> ViewportPxTo_neg1_1(const vcg::Point2<S> & p) const;
00250 
00252     inline vcg::Point2<S> Neg1_1ToViewportPx(const vcg::Point2<S> & p) const;
00253 
00255     inline vcg::Point2<S> LocalTo_0_1(const vcg::Point2<S> & p) const;
00256 
00258     inline vcg::Point2<S> LocalTo_neg1_1(const vcg::Point2<S> & p) const;
00259 
00261     vcg::Point2<S> UndistortedToDistorted(vcg::Point2<S> u) const;
00262 
00264     vcg::Point2<S> DistortedToUndistorted(vcg::Point2<S> d) const;
00265     //--------------------------------
00266 };
00267 
00268 
00269 
00271 template<class S>
00272 vcg::Point2<S> Camera<S>::Project(const vcg::Point3<S> & p) const
00273 {
00274     vcg::Point2<S> q =  Point2<S>(p[0],p[1]);
00275 //    vcg::Point2<S> d =  Point2<S>(p[0],p[1]);
00276 
00277     if(!IsOrtho())
00278     {
00279         q[0] *= FocalMm/p.Z();
00280         q[1] *= FocalMm/p.Z();
00281 
00282         if(k[0]!=0)
00283         {
00284             vcg::Point2<S> d;
00285             d=UndistortedToDistorted(q);
00286             q=d;
00287         }
00288 
00289     }
00290 
00291 
00292     return q;
00293 }
00294 
00295 template <class S> vcg::Matrix44<S> Camera<S>::GetMatrix(S nearVal, S farVal) {
00296     S left, right, bottom, top, nr;
00297     GetFrustum(left, right, bottom,top, nr);
00298 
00299     if(cameraType == PERSPECTIVE) {
00300       S ratio = nearVal/nr;
00301       left *= ratio;
00302       right *= ratio;
00303       bottom *= ratio;
00304       top *= ratio;
00305     }
00306     vcg::Matrix44<S> m;
00307     m[0][0] = 2.0*nearVal/(right - left);
00308     m[0][1] = 0;
00309     m[0][2] = (right + left)/(right - left);
00310     m[0][3] = 0;
00311 
00312     m[1][0] = 0;
00313     m[1][1] = 2*nearVal/(top - bottom);
00314     m[1][2] = (top + bottom)/(top - bottom);
00315     m[1][3] = 0;
00316 
00317     m[2][0] = 0;
00318     m[2][1] = 0;
00319     m[2][2] = -(farVal + nearVal)/(farVal - nearVal);
00320     m[2][3] =  - 2*farVal*nearVal/(farVal - nearVal);
00321 
00322     m[3][0] = 0;
00323     m[3][1] = 0;
00324     m[3][2] = -1;
00325     m[3][3] = 0;
00326 
00327     return m;
00328 }
00329 
00331 template<class S>
00332 vcg::Point3<S> Camera<S>::UnProject(const vcg::Point2<S> & p, const S & d) const
00333 {
00334     vcg::Point3<S> np = Point3<S>(p[0], p[1], d);
00335 
00336     if(!IsOrtho())
00337     {
00338         if(k[0]!=0)
00339         {
00340             vcg::Point2<S> d = Point2<S>(p[0], p[1]);
00341             vcg::Point2<S> u=DistortedToUndistorted(d);
00342             np[0]=u[0];
00343             np[1]=u[1];
00344         }
00345 
00346         np[0] /= FocalMm/d;
00347         np[1] /= FocalMm/d;
00348     }
00349 
00350     return np;
00351 }
00352 
00354 template<class S>
00355 vcg::Point2<S> Camera<S>::LocalToViewportPx(const vcg::Point2<S> & p) const
00356 {
00357     vcg::Point2<S> np;
00358 
00359     np[0] = (p[0] / PixelSizeMm.X()) + CenterPx.X();
00360     np[1] = (p[1] / PixelSizeMm.Y()) + CenterPx.Y();
00361 
00362     return np;
00363 }
00364 
00366 template<class S>
00367 vcg::Point2<S> Camera<S>::ViewportPxToLocal(const vcg::Point2<S> & p) const
00368 {
00369     vcg::Point2<S>  ps;
00370     ps[0] = (p[0]-CenterPx.X()) * PixelSizeMm.X();
00371     ps[1] = (p[1]-CenterPx.Y()) * PixelSizeMm.Y();
00372     return ps;
00373 }
00374 
00376 template<class S>
00377 vcg::Point2<S> Camera<S>::ViewportPxTo_neg1_1(const vcg::Point2<S> & p) const
00378 {
00379     vcg::Point2<S>  ps;
00380     ps[0] = 2.0f * ((p[0]-CenterPx.X()) * PixelSizeMm.X())/ ( PixelSizeMm.X() * (S)ViewportPx[0] );
00381     ps[1] = 2.0f * ((p[1]-CenterPx.Y()) * PixelSizeMm.Y())/ ( PixelSizeMm.Y() * (S)ViewportPx[1] );
00382     return ps;
00383 }
00384 
00386 template<class S>
00387 vcg::Point2<S> Camera<S>::Neg1_1ToViewportPx(const vcg::Point2<S> & p) const
00388 {
00389     vcg::Point2<S>  ps;
00390     ps[0] = ((PixelSizeMm.X() * (S)ViewportPx[0] *p[0])/(2.0f * PixelSizeMm.X()))+CenterPx.X();
00391     ps[1] = ((PixelSizeMm.Y() * (S)ViewportPx[1] *p[1])/(2.0f * PixelSizeMm.Y()))+CenterPx.Y();
00392     return ps;
00393 }
00394 
00396 template<class S>
00397 vcg::Point2<S> Camera<S>::LocalTo_0_1(const vcg::Point2<S> & p) const
00398 {
00399     vcg::Point2<S>  ps;
00400     ps[0] = ( p[0]/PixelSizeMm.X() + CenterPx.X() ) / (S)ViewportPx[0];
00401     ps[1] = ( p[1]/PixelSizeMm.Y() + CenterPx.Y() ) / (S)ViewportPx[1];
00402     return ps;
00403 }
00404 
00406 template<class S>
00407 vcg::Point2<S> Camera<S>::LocalTo_neg1_1(const vcg::Point2<S> & p) const
00408 {
00409     vcg::Point2<S>  ps;
00410     ps[0] = 2.0f * p[0] / ( PixelSizeMm.X() * (S)ViewportPx[0] );
00411     ps[1] = 2.0f * p[1] / ( PixelSizeMm.Y() * (S)ViewportPx[1] );
00412     return ps;
00413 }
00414 
00416 template<class Scalar>
00417 vcg::Point2<Scalar> Camera<Scalar>::UndistortedToDistorted(vcg::Point2<Scalar>  u) const
00418 {
00419     vcg::Point2<Scalar> dis;
00420     vcg::Point2<Scalar> dc=ViewportPxTo_neg1_1(DistorCenterPx);
00421     const Scalar SQRT3 = Scalar(1.732050807568877293527446341505872366943);
00422     const Scalar CBRT = Scalar(0.33333333333333333333333);
00423     Scalar Ru,Rd,lambda,c,d,Q,R,D,S,T,sinT,cosT;
00424 
00425     if(((u[0]-dc[0])==0 && (u[1]-dc[1])==0) || k[0] == 0)
00426     {
00427         dis[0] = u[0];
00428         dis[1] = u[1];
00429         return dis;
00430     }
00431 
00432     Ru = hypot ((u[0]-dc[0]), (u[1]-dc[1]));    /* SQRT(Xu*Xu+Yu*Yu) */
00433     c = 1 / k[0];
00434     d = -c * Ru;
00435 
00436     Q = c / 3;
00437     R = -d / 2;
00438     if (R<0)
00439         D = pow(Q,3) + sqrt(-R);
00440     else
00441         D = pow(Q,3) + sqrt(R);
00442 
00443     if (D >= 0)         /* one real root */
00444     {
00445         D = sqrt(D);
00446         S = pow((R + D),CBRT);
00447         if (R>=D)
00448             T = pow((R - D),CBRT);
00449         else
00450             T = - pow(abs((int)(R - D)),CBRT); //MODIFICATO DA ME
00451         Rd = S + T;
00452 
00453         if (Rd < 0)
00454             Rd = sqrt(-1 / (3 * k[0]));
00455     }
00456     else                        /* three real roots */
00457     {
00458         D = sqrt(-D);
00459         S = pow((Scalar)(hypot (R, D)),(Scalar)CBRT);
00460         T = atan2 (D, R) / 3;
00461         //SinCos(T, sinT, cosT);
00462         sinT=sin(T);
00463         cosT=cos(T);
00464 
00465         /* the larger positive root is    2*S*cos(T)                   */
00466         /* the smaller positive root is   -S*cos(T) + SQRT(3)*S*sin(T) */
00467         /* the negative root is           -S*cos(T) - SQRT(3)*S*sin(T) */
00468         Rd = -S * cosT + SQRT3 * S * sinT;      /* use the smaller positive root */
00469     }
00470 
00471     lambda = Rd / Ru;
00472 
00473     dis[0] = u[0] * lambda;
00474     dis[1] = u[1] * lambda;
00475 
00476     return dis;
00477 }
00478 
00480 template<class S>
00481 vcg::Point2<S> Camera<S>::DistortedToUndistorted(vcg::Point2<S> d) const
00482 {
00483     vcg::Point2<S> u;
00484     vcg::Point2<S> dc=ViewportPxTo_neg1_1(DistorCenterPx);
00485     S r=sqrt(pow((d[0]-dc[0]),2)+pow((d[1]-dc[1]),2));
00486     u[0]=d[0]*(1-k[0]*r*r);
00487     u[1]=d[1]*(1-k[0]*r*r);
00488 
00489     return u;
00490 
00491 }
00492 
00493 
00494 //--- basic camera setup (GL-like)
00495 
00497 template<class S>
00498 void Camera<S>::SetPerspective( S AngleDeg, S AspectRatio, S Focal, vcg::Point2<int> Viewport)
00499 {
00500     cameraType = PERSPECTIVE;
00501     S halfsize[2];
00502 
00503     halfsize[1] = tan(math::ToRad(AngleDeg/2.0f)) * Focal;
00504     halfsize[0] = halfsize[1]*AspectRatio;
00505 
00506     SetFrustum(-halfsize[0],halfsize[0],-halfsize[1],halfsize[1],Focal,Viewport);
00507 }
00508 
00510 template<class S>
00511 void Camera<S>::SetFrustum(     S sx, S dx, S bt, S tp, S Focal, vcg::Point2<int> Viewport)
00512 {
00513     S vp[2];
00514     vp[0] = dx-sx;
00515     vp[1] = tp-bt;
00516 
00517     ViewportPx[0] = Viewport[0];
00518     if(vp[1] != -1)
00519         ViewportPx[1] = Viewport[1];                    // the user specified the viewport
00520     else
00521         ViewportPx[1] = ViewportPx[0];  // default viewport
00522 
00523     PixelSizeMm[0] = vp[0] / (S)Viewport[0];
00524     PixelSizeMm[1] = vp[1] / (S)Viewport[1];
00525 
00526     CenterPx[0] = -sx/vp[0] * (S)Viewport[0];
00527     CenterPx[1] = -bt/vp[1] * (S)Viewport[1];
00528 
00529     FocalMm =Focal;
00530 }
00531 
00532 //--- special cameras setup
00533 
00535 template<class S>
00536 void Camera<S>::SetCavalieri(S sx, S dx, S bt, S tp, S Focal, vcg::Point2<int> Viewport)
00537 {
00538     cameraType = CAVALIERI;
00539     SetFrustum(sx, dx, bt, tp, Focal,Viewport);
00540 }
00541 
00543 template<class S>
00544 void Camera<S>::SetIsometric(S sx, S dx, S bt, S tp, S Focal, vcg::Point2<int> Viewport)
00545 {
00546     cameraType = ISOMETRIC;
00547     SetFrustum(sx, dx, bt, tp, Focal,Viewport);
00548 }
00549 
00551 template<class S>
00552 void Camera<S>:: GetFrustum( S & sx, S & dx, S & bt, S & tp, S & nr)
00553 {
00554     dx = CenterPx.X()* PixelSizeMm.X();                 //scaled center
00555     sx = -( (S)ViewportPx.X() - CenterPx.X() ) * PixelSizeMm.X();
00556 
00557     bt = -CenterPx.Y()* PixelSizeMm.Y();
00558     tp = ( (S)ViewportPx.Y() - CenterPx.Y() ) * PixelSizeMm.Y();
00559 
00560     nr = FocalMm;
00561 }
00562 
00563 }
00564 #endif
00565 
00566 
00567 
00568 


shape_reconstruction
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:29:21