00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127 #ifndef __VCGLIB_CAMERA
00128 #define __VCGLIB_CAMERA
00129
00130
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
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
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
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
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]));
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)
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);
00451 Rd = S + T;
00452
00453 if (Rd < 0)
00454 Rd = sqrt(-1 / (3 * k[0]));
00455 }
00456 else
00457 {
00458 D = sqrt(-D);
00459 S = pow((Scalar)(hypot (R, D)),(Scalar)CBRT);
00460 T = atan2 (D, R) / 3;
00461
00462 sinT=sin(T);
00463 cosT=cos(T);
00464
00465
00466
00467
00468 Rd = -S * cosT + SQRT3 * S * sinT;
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
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];
00520 else
00521 ViewportPx[1] = ViewportPx[0];
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
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();
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