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 Revision 1.14 2006/12/18 16:02:57 matteodelle 00027 minor eroor correction on variable names 00028 00029 Revision 1.13 2006/12/18 14:28:07 matteodelle 00030 *** empty log message *** 00031 00032 Revision 1.12 2006/12/18 09:46:39 callieri 00033 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. 00034 00035 Revision 1.11 2006/01/10 12:22:34 spinelli 00036 add namespace vcg:: 00037 00038 Revision 1.10 2005/10/24 14:42:57 spinelli 00039 add namespace vcg:: to GetFrustum(...) 00040 00041 Revision 1.9 2005/06/29 15:02:29 spinelli 00042 aggiunto: 00043 - static void CavalieriProj( .. ) 00044 - static void IsometricProj( .. ) 00045 00046 modificato: 00047 - static void TransformGL( .. ) 00048 - static void SetSubView( .. ) 00049 00050 Revision 1.8 2005/02/22 10:57:05 tommyfranken 00051 corrected some syntax errors in GetFrustum 00052 00053 Revision 1.7 2005/02/21 18:11:47 ganovelli 00054 GetFrustum moved from gl/camera to math/camera.h 00055 00056 Revision 1.6 2004/12/16 14:41:36 ricciodimare 00057 *** empty log message *** 00058 00059 Revision 1.5 2004/12/16 11:08:35 ricciodimare 00060 Cambiato il nome del costruttore era rimasto quello vecchio... e tolti alcune righe di codice commentate 00061 00062 Revision 1.4 2004/12/15 18:45:06 tommyfranken 00063 *** empty log message *** 00064 00065 Revision 1.3 2004/11/03 09:38:21 ganovelli 00066 added SetSubView, some comment and put the class back(!) 00067 00068 Revision 1.2 2004/10/05 19:04:44 ganovelli 00069 changed from classes to functions 00070 00071 Revision 1.1 2004/09/15 22:59:13 ganovelli 00072 creation 00073 00074 ****************************************************************************/ 00075 00076 00077 #ifndef __GL_CAMERA 00078 #define __GL_CAMERA 00079 // VCG 00080 #include <vcg/math/camera.h> 00081 00082 // opengl 00083 #include <GL/glew.h> 00084 00085 template <class CameraType> 00086 struct GlCamera{ 00087 00088 typedef typename CameraType::ScalarType ScalarType; 00089 typedef typename CameraType::ScalarType S; 00090 00091 00093 static vcg::Matrix44<ScalarType> 00094 MatrixGL(vcg::Camera<S> & cam, vcg::Matrix44<S> &m) 00095 { 00096 glPushAttrib(GL_TRANSFORM_BIT); 00097 glMatrixMode(GL_PROJECTION); 00098 glPushMatrix(); 00099 glLoadIdentity(); 00100 TransformGL(cam); 00101 glGetv(GL_PROJECTION_MATRIX,&m[0][0]); 00102 glPopMatrix(); 00103 glPopAttrib(); 00104 return m; 00105 } 00106 00108 static void SetGLCavalieriProj(float x1, float x2, float y1, float y2, float z1, float z2) 00109 { 00110 GLfloat cavalieri[16]; 00111 00112 cavalieri[0] = 2.0f/(x2-x1); cavalieri[4] = 0; 00113 cavalieri[8] = (0.707106f * -2.0f)/(x2-x1); cavalieri[12] = (x2+x1)/(x2-x1); 00114 cavalieri[1] = 0; cavalieri[5] = 2.0/(y2-y1); 00115 cavalieri[9] = (0.707106f * -2.0f)/(y2-y1); cavalieri[13] = (y2+y1)/(y2-y1); 00116 cavalieri[2] = 0; cavalieri[6] = 0; 00117 cavalieri[10] = -2.0f/(z2-z1); cavalieri[14] = (z2+z1)/(z2-z1); 00118 cavalieri[3] = 0; cavalieri[7] = 0; 00119 cavalieri[11] = 0; cavalieri[15] = 1.0f; 00120 00121 glLoadMatrixf(cavalieri); 00122 } 00123 00125 static void SetGLIsometricProj(float x1, float x2, float y1, float y2, float z1, float z2) 00126 { 00127 GLfloat isometric[16]; 00128 00129 isometric[0] = 1.6f/(x2-x1); isometric[4] = 0; 00130 isometric[8] = -1.6f/(x2-x1); isometric[12] = (x2+x1)/(x2-x1); 00131 isometric[1] = -1.0f/(y2-y1); isometric[5] = 2.0f/(y2-y1); 00132 isometric[9] = -1.0f/(y2-y1); isometric[13] = (y2+y1)/(y2-y1); 00133 isometric[2] = 0; isometric[6] = 0; 00134 isometric[10] = -2.0f/(z2-z1); isometric[14] = (z2+z1)/(z2-z1); 00135 isometric[3] = 0; isometric[7] = 0; 00136 isometric[11] = 0; isometric[15] = 1.0f; 00137 00138 glLoadMatrixf(isometric); 00139 } 00140 00142 static void GetFrustum(vcg::Camera<S> & intrinsics, S & sx,S & dx,S & bt,S & tp,S & f) 00143 { 00144 intrinsics.GetFrustum(sx,dx,bt,tp,f); 00145 } 00146 00148 static void TransformGL(vcg::Camera<S> & camera, S nearDist, S farDist ) 00149 { 00150 S sx,dx,bt,tp,nr; 00151 camera.GetFrustum(sx,dx,bt,tp,nr); 00152 00153 if(camera.cameraType == vcg::PERSPECTIVE) { 00154 S ratio = nearDist/nr; 00155 sx *= ratio; 00156 dx *= ratio; 00157 bt *= ratio; 00158 tp *= ratio; 00159 } 00160 00161 assert(glGetError()==0); 00162 00163 switch(camera.cameraType) 00164 { 00165 case vcg::PERSPECTIVE: glFrustum(sx,dx,bt,tp,nearDist,farDist); break; 00166 case vcg::ORTHO: glOrtho(sx,dx,bt,tp,nearDist,farDist); break; 00167 case vcg::ISOMETRIC: SetGLIsometricProj(sx,dx,bt,tp,nearDist,farDist); break; 00168 case vcg::CAVALIERI: SetGLCavalieriProj(sx,dx,bt,tp,nearDist,farDist); break; 00169 } 00170 00171 assert(glGetError()==0); 00172 }; 00173 00174 00175 static void GetViewSize(vcg::Camera<S> & camera, S &width, S &height) { 00176 S sx,dx,bt,tp,nr,fr; 00177 GetFrustum(camera,sx,dx,bt,tp,nr,fr); 00178 width = dx-sx; //right - left = width 00179 height = tp-bt; //top - bottom = height 00180 }; 00181 00182 00183 static void SetSubView(vcg::Camera<S> & camera,vcg::Point2<S> p0,S nearDist, S farDist,vcg::Point2<S> p1){ 00184 //typedef typename CameraType::ScalarType S; 00185 S sx,dx,bt,tp,f; 00186 GetFrustum(camera,sx,dx,bt,tp,f); 00187 S width = dx-sx; //right - left = width 00188 S height = tp-bt; //top - bottom = height 00189 /*glFrustum( 00190 width* p0[0]+ sx, width* p1[0]+ sx, 00191 height* p0[1]+ bt, height* p1[1]+ bt, 00192 nr,fr);*/ 00193 00194 00195 00196 switch(camera.cameraType) 00197 { 00198 case vcg::PERSPECTIVE: glFrustum( width* p0[0]+ sx, width* p1[0]+ sx, height* p0[1]+ bt, height* p1[1]+bt,nearDist,farDist); break; 00199 case vcg::ORTHO: glOrtho(width* p0[0]+sx, width* p1[0]+sx, height* p0[1]+ bt, height* p1[1]+bt,nearDist,farDist); break; 00200 //case vcg::ISOMETRIC: IsometricProj(dx-width* p1[0], dx-width* p0[0], tp-height* p1[1], tp-height* p0[1],nearDist,farDist); break; 00201 //case vcg::CAVALIERI: CavalieriProj(dx-width* p1[0], dx-width* p0[0], tp-height* p1[1], tp-height* p0[1],nearDist,farDist); break; 00202 } 00203 00204 00205 assert(glGetError()==0); 00206 }; 00207 }; 00208 #endif 00209 00210 00211 00212 00213 00214 00215 //private: 00216 // 00217 // static inline S SQRT( S x) { return sqrt(fabs(x)); } 00218 // static inline S CBRT ( S x ) 00219 // { 00220 // if (x == 0) return 0; 00221 // else if (x > 0) return pow (x, 1.0 / 3.0); 00222 // else return -pow (-x, 1.0 / 3.0); 00223 // } 00224 // static inline void SINCOS( S x, S & s, S & c) 00225 // { 00226 // s=sin(x); 00227 // c=cos(x); 00228 // } 00229 // static inline void SINCOSd( double x, double & s, double & c) 00230 // { 00231 // s=sin(x); 00232 // c=cos(x); 00233 // } 00234 // static inline S CUB( S x ) { return x*x*x; } 00235 // static inline S SQR( S x ) { return x*x; } 00236 // 00237 //public: 00238 // void undistorted_to_distorted_sensor_coord (S Xu, S Yu, S & Xd, S & Yd) const 00239 // { 00240 // const S SQRT3 = S(1.732050807568877293527446341505872366943); 00241 // S Ru,Rd,lambda,c,d,Q,R,D,S,T,sinT,cosT; 00242 // 00243 // if((Xu==0 && Yu==0) || k[0] == 0) 00244 // { 00245 // Xd = Xu; 00246 // Yd = Yu; 00247 // return; 00248 // } 00249 // 00250 // Ru = hypot (Xu, Yu); /* SQRT(Xu*Xu+Yu*Yu) */ 00251 // c = 1 / k[0]; 00252 // d = -c * Ru; 00253 // 00254 // Q = c / 3; 00255 // R = -d / 2; 00256 // D = CUB (Q) + SQR (R); 00257 // 00258 // if (D >= 0) /* one real root */ 00259 // { 00260 // D = SQRT (D); 00261 // S = CBRT (R + D); 00262 // T = CBRT (R - D); 00263 // Rd = S + T; 00264 // 00265 // if (Rd < 0) 00266 // Rd = SQRT (-1 / (3 * k[0])); 00267 // } 00268 // else /* three real roots */ 00269 // { 00270 // D = SQRT (-D); 00271 // S = CBRT (hypot (R, D)); 00272 // T = atan2 (D, R) / 3; 00273 // SINCOS (T, sinT, cosT); 00274 // 00275 // /* the larger positive root is 2*S*cos(T) */ 00276 // /* the smaller positive root is -S*cos(T) + SQRT(3)*S*sin(T) */ 00277 // /* the negative root is -S*cos(T) - SQRT(3)*S*sin(T) */ 00278 // Rd = -S * cosT + SQRT3 * S * sinT; /* use the smaller positive root */ 00279 // } 00280 // 00281 // lambda = Rd / Ru; 00282 // 00283 // Xd = Xu * lambda; 00284 // Yd = Yu * lambda; 00285 // } 00286 // 00287 // 00288 //void correction(double k, float i, float j, float &disi, float &disj) 00289 //{ 00290 // // (i,j) punto nell'immagine distorta 00291 // // (disi,disj) punto nell'immagine corretta (undistorted) 00292 // float hyp; 00293 // float I,J,ni,nj; 00294 // float ratio = 1; 00295 // 00296 // ni = i-viewport[0]/2; 00297 // nj = j-viewport[1]/2; 00298 // hyp = ni*ni + nj*nj; 00299 // 00300 // I = ni * (1+ k * hyp); 00301 // J = nj * (1+ k * hyp); 00302 // 00303 // disi = (I*ratio+viewport[0]/2); 00304 // disj = (J*ratio+viewport[1]/2); 00305 //} 00306 // 00307 // 00308 // 00309 //void distorsion( float k ,float i, float j,double & disi, double &disj) 00310 //{ 00311 // // (i,j) punto nell'immagine corretta (undistorted) 00312 // // (disi,disj) punto nell'immagine distorta 00313 // float hyp; 00314 // int _I,_J; 00315 // float I,J,ni,nj; 00316 // I = i-viewport[0]/2; 00317 // J = j-viewport[1]/2; 00318 // hyp = sqrt(I*I + J*J); 00319 // if((k==0.0) || (hyp <0.001)) 00320 // { 00321 // disi = i; 00322 // disj = j; 00323 // } 00324 // else 00325 // { 00326 // undistorted_to_distorted_sensor_coord (I, J, disi, disj); 00327 // disi += viewport[0]/2; 00328 // disj += viewport[1]/2; 00329 // 00330 // 00335 // float ratio=1; 00336 // 00337 // 00338 // 00339 // //----------- Maple 00340 // // float t0,t1,t2,sol; 00341 // 00342 // //t0 = 1/k*pow((108.0*hyp+12.0*sqrt(3.0)*sqrt((4.0+27.0*hyp*hyp*k)/k))*k*k,0.3333333333333333)/6.0-2.0/pow((108.0*hyp+12.0*sqrt(3.0)*sqrt((4.0+27.0*hyp*hyp*k)/k))*k*k,0.3333333333333333); 00343 // 00344 // 00345 // //t1 = -1/k*pow((108.0*hyp+12.0*sqrt(3.0)*sqrt((4.0+27.0*hyp*hyp*k)/k))*k*k,0.3333333333333333)/12.0+1/pow((108.0*hyp+12.0*sqrt(3.0)*sqrt((4.0+27.0*hyp* 00346 // //hyp*k)/k))*k*k,0.3333333333333333)+sqrt(-1.0)*sqrt(3.0)*(1/k*pow((108.0*hyp+ 00347 // //12.0*sqrt(3.0)*sqrt((4.0+27.0*hyp*hyp*k)/k))*k*k,0.3333333333333333)/6.0+2.0/ 00348 // //pow((108.0*hyp+12.0*sqrt(3.0)*sqrt((4.0+27.0*hyp*hyp*k)/k))*k*k, 00349 // //0.3333333333333333))/2.0; 00350 // 00351 // //t2 = -1/k*pow((108.0*hyp+12.0*sqrt(3.0)*sqrt((4.0+27.0*hyp*hyp*k)/k))*k*k,0.3333333333333333)/12.0+1/pow((108.0*hyp+12.0*sqrt(3.0)*sqrt((4.0+27.0*hyp* 00352 // //hyp*k)/k))*k*k,0.3333333333333333)-sqrt(-1.0)*sqrt(3.0)*(1/k*pow((108.0*hyp+ 00353 // //12.0*sqrt(3.0)*sqrt((4.0+27.0*hyp*hyp*k)/k))*k*k,0.3333333333333333)/6.0+2.0/ 00354 // //pow((108.0*hyp+12.0*sqrt(3.0)*sqrt((4.0+27.0*hyp*hyp*k)/k))*k*k, 00355 // //0.3333333333333333))/2.0; 00356 // 00357 // //sol = (t0>t1)?t0:t1; 00358 // //sol = (sol<t2)?t2:sol; 00359 // //sol = t0; 00360 // //ni = sol*I/hyp; 00361 // //nj = sol*J/hyp; 00362 // ////----------- 00363 // 00364 // //disi = (ni*ratio+viewport[0]/2); 00365 // //disj = (nj*ratio+viewport[1]/2); 00366 // } 00367 //} 00368 // void ResizeGridMap(const int & si,const int & sj ){ 00369 // int j; 00370 // gridMap.resize(sj+1); 00371 // for(j=0; j < sj+1; j++) 00372 // gridMap[j].resize(si+1); 00373 // } 00374 // void UpdateGridMap(){ 00375 // int sj = gridMap.size(); 00376 // int si = gridMap[0].size(); 00377 // int i,j; 00378 // for(j=0; j < sj; j++) 00379 // for(i=0; i < gridMap[0].size(); i++) 00380 // // gridMap[i][j] = Point2<scalar> (i/(double)(si-1),j/(double)(sj-1)); 00381 // { 00382 // double disi,disj; 00383 // distorsion( k[0] ,(i/(double)(si-1))*viewport[0], (j/(double)(sj-1))*viewport[1],disi,disj); 00384 // gridMap[i][j] = Point2<scalar> (disi/viewport[0],disj/viewport[1]); 00385 // } 00386 // } 00387 // 00388 // inline Camera() 00389 // { 00390 // k[0]=k[1]=k[2]=k[3]=0.0; 00391 // valid = false; 00392 // ortho = false; 00393 // ResizeGridMap(100,100);// da spostare altrove 00394 // } 00395 // 00396 // inline bool IsValid() 00397 // { 00398 // return valid; 00399 // } 00400 // 00401 // inline bool IsOrtho() const 00402 // { 00403 // return ortho; 00404 // } 00405 // 00406 // inline void SetInvalid() 00407 // { 00408 // valid = false; 00409 // } 00410 // 00411 // inline void SetOrtho(bool isOrtho=true) 00412 // { 00413 // ortho = isOrtho; 00414 // } 00415 // 00416 // // Genera una camera standard 00417 // void Standard() 00418 // { 00419 // valid = true; 00420 // ortho = false; 00421 // view_p = vectorial(0,0,0); 00422 // x_axis = vectorial(1,0,0); 00423 // y_axis = vectorial(0,1,0); 00424 // z_axis = vectorial(0,0,1); 00425 // f = 25.75; 00426 // s = Point2<S>(0.0074,0.0074); 00427 // c = Point2<S>(320,240); 00428 // viewport[0] = 640; 00429 // viewport[1] = 480; 00430 // k[0] = 0; 00431 // k[1] = 0; 00432 // k[2] = 0; 00433 // k[3] = 0; 00434 // } 00435 // 00436 // // Trasla la camera (world coordinate) 00437 // inline void Translate( const vectorial & t ) 00438 // { 00439 // view_p += t; 00440 // } 00441 // 00442 // // Trasla la camera (camera coordinate) 00443 // inline void Move( const vectorial & t ) 00444 // { 00445 // view_p+= x_axis * t[0]+y_axis * t[1] + z_axis * t[2]; 00446 // } 00447 // 00448 // // scala la camera 00449 // inline void Scale(const scalar & sc){ 00450 // view_p *=sc; 00451 // s[0]*=sc; 00452 // s[1]*=sc; 00453 // f*=sc; 00454 // //printf("sc\n"); 00455 // } 00456 // 00457 // 00458 // 00459 // // NOTA funziona solo se l'ultima colonna di m e' 0,0,0,1 00460 // void Apply( const Matrix44<S> & m ) 00461 // { 00462 // // Passo 1: calcolo pseudo inversa di m 00463 // S s11,s12,s13; 00464 // S s21,s22,s23; 00465 // S s31,s32,s33; 00466 // S s41,s42,s43; 00467 // 00468 // { 00469 // S t4 = m[0][0]*m[1][1]; 00470 // S t6 = m[0][0]*m[2][1]; 00471 // S t8 = m[1][0]*m[0][1]; 00472 // S t10 = m[1][0]*m[2][1]; 00473 // S t12 = m[2][0]*m[0][1]; 00474 // S t14 = m[2][0]*m[1][1]; 00475 // S t17 = 1/(t4*m[2][2]-t6*m[1][2]-t8*m[2][2]+t10*m[0][2]+t12*m[1][2]-t14*m[0][2]); 00476 // S t27 = m[1][0]*m[2][2]; 00477 // S t28 = m[2][0]*m[1][2]; 00478 // S t31 = m[0][0]*m[2][2]; 00479 // S t32 = m[2][0]*m[0][2]; 00480 // S t35 = m[0][0]*m[1][2]; 00481 // S t36 = m[1][0]*m[0][2]; 00482 // S t49 = m[3][0]*m[1][1]; 00483 // S t51 = m[3][0]*m[2][1]; 00484 // S t59 = m[3][0]*m[0][1]; 00485 // s11 = -(-m[1][1]*m[2][2]+m[2][1]*m[1][2])*t17; 00486 // s12 = -( m[0][1]*m[2][2]-m[2][1]*m[0][2])*t17; 00487 // s13 = ( m[0][1]*m[1][2]-m[1][1]*m[0][2])*t17; 00488 // s21 = (-t27+t28)*t17; 00489 // s22 = -(-t31+t32)*t17; 00490 // s23 = -( t35-t36)*t17; 00491 // s31 = -(-t10+t14)*t17; 00492 // s32 = (-t6 +t12)*t17; 00493 // s33 = ( t4 -t8 )*t17; 00494 // s41 = -(t10*m[3][2]-t27*m[3][1]-t14*m[3][2]+t28*m[3][1]+t49*m[2][2]-t51*m[1][2])*t17; 00495 // s42 = -(-t6*m[3][2]+t31*m[3][1]+t12*m[3][2]-t32*m[3][1]-t59*m[2][2]+t51*m[0][2])*t17; 00496 // s43 = (-t4*m[3][2]+t35*m[3][1]+t8 *m[3][2]-t36*m[3][1]-t59*m[1][2]+t49*m[0][2])*t17; 00497 // 1.0; 00498 // } 00499 // 00500 // //Matrix44<S> t2 = tt*m; 00501 // //print(t2); 00502 // // Fase 2: Calcolo nuovo punto di vista 00503 // { 00504 // S t1 = view_p[2]*s31; 00505 // S t3 = view_p[2]*s21; 00506 // S t5 = s43*s21; 00507 // S t7 = s43*s31; 00508 // S t9 = view_p[1]*s31; 00509 // S t11 = view_p[1]*s21; 00510 // S t13 = s42*s31; 00511 // S t15 = s42*s21; 00512 // S t17 = view_p[0]*s32; 00513 // S t19 = view_p[0]*s22; 00514 // S t21 = s41*s32; 00515 // S t23 = s41*s22; 00516 // S t25 = -t1*s22+t3*s32-t5*s32+t7*s22+t9*s23-t11*s33-t13*s23+t15*s33-t17*s23+t19*s33+t21*s23-t23*s33; 00517 // S t39 = 1/(s11*s22*s33-s11*s32*s23-s21*s12*s33+s21*s32*s13+s31*s12*s23-s31*s22*s13); 00518 // S t41 = view_p[0]*s12; 00519 // S t45 = s41*s12; 00520 // S t47 = view_p[2]*s11; 00521 // S t50 = s43*s11; 00522 // S t53 = view_p[1]*s11; 00523 // S t56 = s42*s11; 00524 // S t59 = t41*s33-t17*s13+t21*s13-t45*s33+t47*s32-t1*s12-t50*s32+t7*s12-t53*s33+t9*s13+t56*s33-t13*s13; 00525 // S t73 = t15*s13-t56*s23+t19*s13-t41*s23-t23*s13+t45*s23-t11*s13+t53*s23+t3*s12-t47*s22-t5*s12+t50*s22; 00526 // 00527 // view_p[0] = t25*t39; 00528 // view_p[1] = -t59*t39; 00529 // view_p[2] = -t73*t39; 00530 // } 00531 // 00532 // // Fase 3: Calcol nuovo sistema di riferimento 00533 // { 00534 // S A00 = s11*x_axis[0]+s12*x_axis[1]+s13*x_axis[2]; 00535 // S A01 = s11*y_axis[0]+s12*y_axis[1]+s13*y_axis[2]; 00536 // S A02 = s11*z_axis[0]+s12*z_axis[1]+s13*z_axis[2]; 00537 // // S A03 = 0.0; 00538 // S A10 = s21*x_axis[0]+s22*x_axis[1]+s23*x_axis[2]; 00539 // S A11 = s21*y_axis[0]+s22*y_axis[1]+s23*y_axis[2]; 00540 // S A12 = s21*z_axis[0]+s22*z_axis[1]+s23*z_axis[2]; 00541 // // S A13 = 0.0; 00542 // S A20 = s31*x_axis[0]+s32*x_axis[1]+s33*x_axis[2]; 00543 // S A21 = s31*y_axis[0]+s32*y_axis[1]+s33*y_axis[2]; 00544 // S A22 = s31*z_axis[0]+s32*z_axis[1]+s33*z_axis[2]; 00545 // 00546 // x_axis[0] = A00; x_axis[1] = A10; x_axis[2] = A20; 00547 // y_axis[0] = A01; y_axis[1] = A11; y_axis[2] = A21; 00548 // z_axis[0] = A02; z_axis[1] = A12; z_axis[2] = A22; 00549 // // S A1[2][3] = 0.0; 00550 // // S A1[3][0] = 0.0; 00551 // // S A1[3][1] = 0.0; 00552 // // S A1[3][2] = 0.0; 00553 // // S A1[3][3] = 1.0; 00554 // } 00555 // } 00556 // 00557 // /* 00558 // // Applica una trasformazione 00559 // void Apply( const Matrix44<S> & m ) 00560 // { 00561 // Point3<S> tx = view_p+x_axis; 00562 // Point3<S> ty = view_p+y_axis; 00563 // Point3<S> tz = view_p+z_axis; 00564 // 00565 // view_p = m.Apply(view_p); 00566 // 00567 // x_axis = m.Apply(tx) - view_p; 00568 // y_axis = m.Apply(ty) - view_p; 00569 // z_axis = m.Apply(tz) - view_p; 00570 // } 00571 // 00572 // // Applica una trasformazione ma bene! 00573 // void Stable_Apply( const Matrix44<S> & m ) 00574 // { 00575 // Point3<S> tx = view_p+x_axis; 00576 // Point3<S> ty = view_p+y_axis; 00577 // Point3<S> tz = view_p+z_axis; 00578 // 00579 // view_p = m.Stable_Apply(view_p); 00580 // 00581 // x_axis = m.Stable_Apply(tx) - view_p; 00582 // y_axis = m.Stable_Apply(ty) - view_p; 00583 // z_axis = m.Stable_Apply(tz) - view_p; 00584 // } 00585 // 00586 // */ 00587 // 00588 // void Project( const vectorial & p, Point2<S> & q ) const 00589 // { 00590 // vectorial dp = p - view_p; 00591 // S dx = dp*x_axis; 00592 // S dy = dp*y_axis; 00593 // S dz = dp*z_axis; 00594 // 00595 // S tx = dx; 00596 // S ty = -dy; 00597 // S qx,qy; 00598 // 00599 // // nota: per le camere ortogonali viewportM vale 1 00600 // if(!IsOrtho()) 00601 // { 00602 // tx *= f/dz; 00603 // ty *= f/dz; 00604 // 00605 // undistorted_to_distorted_sensor_coord(tx,ty,qx,qy); 00606 // 00607 // q[0] = qx/s[0]+c[0]; 00608 // q[1] = qy/s[1]+c[1]; 00609 // } 00610 // else 00611 // { 00612 // q[0] = tx/(s[0]*viewportM)+c[0]; 00613 // q[1] = ty/(s[1]*viewportM)+c[1]; 00614 // } 00615 // } 00616 // 00617 //#if 1 00618 // void Show( FILE * fp ) 00619 // { 00620 // if(valid) 00621 // fprintf(fp, 00622 // "posiz.: %g %g %g\n" 00623 // "x axis: %g %g %g\n" 00624 // "y axis: %g %g %g\n" 00625 // "z axis: %g %g %g\n" 00626 // "focal : %g scale: %g %g center: %g %g\n" 00627 // "viewp.: %d %d distorsion: %g %g %g %g\n" 00628 // ,view_p[0],view_p[1],view_p[2] 00629 // ,x_axis[0],x_axis[1],x_axis[2] 00630 // ,y_axis[0],y_axis[1],y_axis[2] 00631 // ,z_axis[0],z_axis[1],z_axis[2] 00632 // ,f,s[0],s[1],c[0],c[1] 00633 // ,viewport[0],viewport[1],k[0],k[1],k[2],k[3] 00634 // ); 00635 // else 00636 // fprintf(fp,"Invalid\n"); 00637 // } 00638 //#endif 00639 // 00640 // // Legge una camera in descrizione tsai binario 00641 // static void load_tsai_bin (FILE *fp, tsai_camera_parameters *cp, tsai_calibration_constants *cc) 00642 // { 00643 // double sa, 00644 // ca, 00645 // sb, 00646 // cb, 00647 // sg, 00648 // cg; 00649 // 00650 // fread(&(cp->Ncx),sizeof(double),1,fp); 00651 // fread(&(cp->Nfx),sizeof(double),1,fp); 00652 // fread(&(cp->dx),sizeof(double),1,fp); 00653 // fread(&(cp->dy),sizeof(double),1,fp); 00654 // fread(&(cp->dpx),sizeof(double),1,fp); 00655 // fread(&(cp->dpy),sizeof(double),1,fp); 00656 // fread(&(cp->Cx),sizeof(double),1,fp); 00657 // fread(&(cp->Cy),sizeof(double),1,fp); 00658 // fread(&(cp->sx),sizeof(double),1,fp); 00659 // 00660 // fread(&(cc->f),sizeof(double),1,fp); 00661 // fread(&(cc->kappa1),sizeof(double),1,fp); 00662 // fread(&(cc->Tx),sizeof(double),1,fp); 00663 // fread(&(cc->Ty),sizeof(double),1,fp); 00664 // fread(&(cc->Tz),sizeof(double),1,fp); 00665 // fread(&(cc->Rx),sizeof(double),1,fp); 00666 // fread(&(cc->Ry),sizeof(double),1,fp); 00667 // fread(&(cc->Rz),sizeof(double),1,fp); 00668 // 00669 // 00670 // SINCOSd (cc->Rx, sa, ca); 00671 // SINCOSd (cc->Ry, sb, cb); 00672 // SINCOSd (cc->Rz, sg, cg); 00673 // 00674 // cc->r1 = cb * cg; 00675 // cc->r2 = cg * sa * sb - ca * sg; 00676 // cc->r3 = sa * sg + ca * cg * sb; 00677 // cc->r4 = cb * sg; 00678 // cc->r5 = sa * sb * sg + ca * cg; 00679 // cc->r6 = ca * sb * sg - cg * sa; 00680 // cc->r7 = -sb; 00681 // cc->r8 = cb * sa; 00682 // cc->r9 = ca * cb; 00683 // 00684 // fread(&(cc->p1),sizeof(double),1,fp); 00685 // fread(&(cc->p2),sizeof(double),1,fp); 00686 // } 00687 // 00688 // void load_tsai (FILE *fp, tsai_camera_parameters *cp, tsai_calibration_constants *cc) 00689 // { 00690 // double sa, 00691 // ca, 00692 // sb, 00693 // cb, 00694 // sg, 00695 // cg; 00696 // 00697 // fscanf (fp, "%lf", &(cp->Ncx)); 00698 // fscanf (fp, "%lf", &(cp->Nfx)); 00699 // fscanf (fp, "%lf", &(cp->dx)); 00700 // fscanf (fp, "%lf", &(cp->dy)); 00701 // fscanf (fp, "%lf", &(cp->dpx)); 00702 // fscanf (fp, "%lf", &(cp->dpy)); 00703 // fscanf (fp, "%lf", &(cp->Cx)); 00704 // fscanf (fp, "%lf", &(cp->Cy)); 00705 // fscanf (fp, "%lf", &(cp->sx)); 00706 // 00707 // fscanf (fp, "%lf", &(cc->f)); 00708 // fscanf (fp, "%lf", &(cc->kappa1)); 00709 // fscanf (fp, "%lf", &(cc->Tx)); 00710 // fscanf (fp, "%lf", &(cc->Ty)); 00711 // fscanf (fp, "%lf", &(cc->Tz)); 00712 // fscanf (fp, "%lf", &(cc->Rx)); 00713 // fscanf (fp, "%lf", &(cc->Ry)); 00714 // fscanf (fp, "%lf", &(cc->Rz)); 00715 // 00716 // SINCOSd (cc->Rx, sa, ca); 00717 // SINCOSd (cc->Ry, sb, cb); 00718 // SINCOSd (cc->Rz, sg, cg); 00719 // 00720 // cc->r1 = cb * cg; 00721 // cc->r2 = cg * sa * sb - ca * sg; 00722 // cc->r3 = sa * sg + ca * cg * sb; 00723 // cc->r4 = cb * sg; 00724 // cc->r5 = sa * sb * sg + ca * cg; 00725 // cc->r6 = ca * sb * sg - cg * sa; 00726 // cc->r7 = -sb; 00727 // cc->r8 = cb * sa; 00728 // cc->r9 = ca * cb; 00729 // 00730 // fscanf (fp, "%lf", &(cc->p1)); 00731 // fscanf (fp, "%lf", &(cc->p2)); 00732 // } 00733 // 00734 // // Importa una camera dal formato tsai 00735 // void import( const tsai_camera_parameters & cp, 00736 // const tsai_calibration_constants & cc, 00737 // const int image_viewport[2] 00738 // ) 00739 // { 00740 // assert(!IsOrtho()); 00741 // valid = true; 00742 // x_axis[0] = cc.r1; x_axis[1] = cc.r2; x_axis[2] = cc.r3; 00743 // y_axis[0] = cc.r4; y_axis[1] = cc.r5; y_axis[2] = cc.r6; 00744 // z_axis[0] = cc.r7; z_axis[1] = cc.r8; z_axis[2] = cc.r9; 00745 // 00746 // view_p[0] = - (cc.Tx * x_axis[0] + cc.Ty * y_axis[0] + cc.Tz * z_axis[0]); 00747 // view_p[1] = - (cc.Tx * x_axis[1] + cc.Ty * y_axis[1] + cc.Tz * z_axis[1]); 00748 // view_p[2] = - (cc.Tx * x_axis[2] + cc.Ty * y_axis[2] + cc.Tz * z_axis[2]); 00749 // 00750 // s[0] = cp.dpx/cp.sx; 00751 // s[1] = cp.dpy; 00752 // c[0] = cp.Cx; 00753 // c[1] = cp.Cy; 00754 // 00755 // f = cc.f; 00756 // viewport[0] = image_viewport[0]; 00757 // viewport[1] = image_viewport[1]; 00758 // 00759 // k[0] = cc.kappa1; 00760 // k[1] = cc.kappa1; 00761 // k[2] = 0; 00762 // k[2] = 0; 00763 // } 00764 // 00765 // // Esporta una camera in formato tsai 00766 // void export( tsai_camera_parameters & cp, 00767 // tsai_calibration_constants & cc, 00768 // int image_viewport[2] 00769 // ) 00770 // { 00771 // assert(!IsOrtho()); 00772 // cc.r1 = x_axis[0]; cc.r2 = x_axis[1]; cc.r3= x_axis[2] ; 00773 // cc.r4 = y_axis[0]; cc.r5 = y_axis[1]; cc.r6= y_axis[2] ; 00774 // cc.r7 = z_axis[0]; cc.r8 = z_axis[1]; cc.r9= z_axis[2] ; 00775 // 00776 // cc.Tx = - (view_p[0] * x_axis[0] + view_p[1] * x_axis[1] + view_p[2] * x_axis[2]); 00777 // cc.Ty = - (view_p[0] * y_axis[0] + view_p[1] * y_axis[1] + view_p[2] * y_axis[2]); 00778 // cc.Tz = - (view_p[0] * z_axis[0] + view_p[1] * z_axis[1] + view_p[2] * z_axis[2]); 00779 // 00780 // cp.dpx = s[0]; 00781 // cp.dpy = s[1]; 00782 // 00783 // cp.Cx= c[0] ; 00784 // cp.Cy= c[1] ; 00785 // cp.sx= 1; 00786 // 00787 // cc.f= f ; 00788 // 00789 // image_viewport[0] = viewport[0]; 00790 // image_viewport[1] = viewport[1]; 00791 // 00792 // cc.kappa1= k[0] ; 00793 // cc.kappa1= k[1] ; 00794 // } 00795 // 00796 // 00797 // void Save(FILE * out) 00798 // { 00799 // fprintf(out,"VIEW_POINT %f %f %f\n", view_p[0],view_p[1],view_p[2]); 00800 // fprintf(out,"X_AXIS %f %f %f\n", x_axis[0],x_axis[1],x_axis[2]); 00801 // fprintf(out,"Y_AXIS %f %f %f\n", y_axis[0],y_axis[1],y_axis[2]); 00802 // fprintf(out,"Z_AXIS %f %f %f\n", z_axis[0],z_axis[1],z_axis[2]); 00803 // fprintf(out,"FOCUS_LENGHT %f \n", f); 00804 // fprintf(out,"SCALE %f %f \n", s[0], s[1]); 00805 // fprintf(out,"VIEWPORT %d %d \n", viewport[0], viewport[1]); 00806 // fprintf(out,"VIEWPORTM %f\n", viewportM); 00807 // fprintf(out,"RADIAL_DISTORSION %.10g %.10g \n", k[0],k[1]); 00808 // fprintf(out,"CENTER %f %f \n", c[0], c[1]); 00809 // fprintf(out,"IS_VALID %d\n", IsValid()); 00810 // fprintf(out,"END_CAMERA\n"); 00811 // } 00812 // 00813 // void Load(FILE * in) 00814 // { 00815 // char row[255]; 00816 // Standard(); 00817 // while(!feof(in)) 00818 // { 00819 // fscanf(in,"%s",row); 00820 // if(strcmp(row,"VIEW_POINT")==0) 00821 // fscanf(in,"%lg %lg %lg",&view_p[0],&view_p[1],&view_p[2]); 00822 // else 00823 // if(strcmp(row,"X_AXIS")==0) 00824 // fscanf(in,"%lg %lg %lg",& x_axis[0],&x_axis[1],&x_axis[2]); 00825 // else 00826 // if(strcmp(row,"Y_AXIS")==0) 00827 // fscanf(in,"%lg %lg %lg",& y_axis[0],&y_axis[1],&y_axis[2]); 00828 // else 00829 // if(strcmp(row,"Z_AXIS")==0) 00830 // fscanf(in,"%lg %lg %lg",& z_axis[0],&z_axis[1],&z_axis[2]); 00831 // else 00832 // if(strcmp(row,"FOCUS_LENGHT")==0) 00833 // fscanf(in,"%lg",&f); 00834 // else 00835 // if(strcmp(row,"SCALE")==0) 00836 // fscanf(in,"%lg %lg",&s[0],&s[1]); 00837 // else 00838 // if(strcmp(row,"VIEWPORT")==0) 00839 // fscanf(in,"%d %d", &viewport[0],&viewport[1]); 00840 // else 00841 // if(strcmp(row,"VIEWPORTM")==0) 00842 // fscanf(in,"%f", &viewportM); 00843 // else 00844 // if(strcmp(row,"CENTER")==0) 00845 // fscanf(in,"%lg %lg", &c[0],&c[1]); 00846 // else 00847 // if(strcmp(row,"RADIAL_DISTORSION")==0) 00848 // fscanf(in,"%lg %lg", &k[0],&k[1]); 00849 // else 00850 // if(strcmp(row,"IS_VALID")==0) 00851 // fscanf(in,"%d",&valid); 00852 // if(strcmp(row,"END_CAMERA")==0) 00853 // break; 00854 // } 00855 // } 00856 // 00857 //#ifdef __GL_H__ 00858 // 00862 //void SetGL(const Box3<scalar> &bb,scalar subx0=0, scalar subx1=1,scalar suby0=0,scalar suby1=1) 00863 //{ 00864 // scalar _,__; 00865 // SetGL(_,__,bb,subx0, subx1, suby0, suby1); 00866 // 00867 //} 00868 // 00869 //void SetGL(scalar &znear, scalar &zfar,const Box3<scalar> &bb,scalar subx0=0, 00870 // scalar subx1=1,scalar suby0=0,scalar suby1=1) 00871 //{ 00872 // glMatrixMode(GL_PROJECTION); 00873 // glLoadIdentity(); 00874 // scalar left,right; 00875 // scalar bottom, top; 00876 // scalar w,h; 00877 // 00878 // // La lunghezza focale <f> e' la distanza del piano immagine dal centro di proiezione. 00879 // // il che mappa direttamente nella chiamata glFrustum che prende in ingresso 00880 // // le coordinate del piano immagine posto a znear. 00881 // 00882 // float imleft =-c[0]*s[0]; 00883 // float imright =(viewport[0]-c[0])*s[0]; 00884 // float imbottom =-c[1]*s[1]; 00885 // float imtop =(viewport[1]-c[1])*s[1]; 00886 // znear = Distance(view_p, bb.Center())-bb.Diag(); 00887 // zfar = Distance(view_p, bb.Center())+bb.Diag(); 00888 // 00889 // w=imright-imleft; 00890 // h=imtop-imbottom; 00891 // 00892 // // Quindi il frustum giusto sarebbe questo, 00893 // // glFrustum(imleft, imright, imbottom, imtop, f, zfar); 00894 // // ma per amor di opengl conviene spostare il near plane fino ad essere vicino all'oggetto da inquadrare. 00895 // // Cambiare f significa amplificare in maniera proporzionale anche i left right ecc. 00896 // 00897 // // 8/5/02 Nota che il near plane va spostato verso l'oggetto solo se quello calcolato sopra e' maggiore di 'f' 00898 // // nota che potrebbe anche succedere che znear <0 (viewpoint vicino ad un oggetto con il bb allungato); 00899 // if(znear<f) znear=f; 00900 // 00901 // float nof = znear/f; 00902 // if(subx0==0 && subx1 == 1 && suby0==0 && suby1 == 1) 00903 // { 00904 // if(!IsOrtho()) 00905 // glFrustum(imleft*nof, imright*nof, imbottom*nof, imtop*nof, znear, zfar); 00906 // else 00907 // glOrtho(imleft*viewportM, imright*viewportM, imbottom*viewportM, imtop*viewportM, znear, zfar); 00908 // } 00909 // else {// nel caso si voglia fare subboxing 00910 // left = imleft+w*subx0; 00911 // right = imleft+w*subx1; 00912 // bottom = imbottom +h*suby0; 00913 // top = imbottom +h*suby1; 00914 // { 00915 // if(!IsOrtho()) 00916 // glFrustum(left*nof, right*nof, bottom*nof, top*nof, znear, zfar); 00917 // else 00918 // glOrtho(left*viewportM, right*viewportM, bottom*viewportM, top*viewportM, znear, zfar); 00919 // } 00920 // } 00921 // 00922 // glMatrixMode(GL_MODELVIEW); 00923 // glLoadIdentity(); 00924 // scalar l=max(scalar(1.0),view_p.Norm()); 00925 // gluLookAt(view_p[0], view_p[1], view_p[2], 00926 // view_p[0] + (z_axis[0]*l), 00927 // view_p[1] + (z_axis[1]*l), 00928 // view_p[2] + (z_axis[2]*l), 00929 // y_axis[0],y_axis[1],y_axis[2]); 00930 //} 00933 //void Jitter(Point3<scalar> c, scalar RadAngle) 00934 //{ 00935 // Point3<scalar> rnd(1.0 - 2.0*scalar(rand())/RAND_MAX, 00936 // 1.0 - 2.0*scalar(rand())/RAND_MAX, 00937 // 1.0 - 2.0*scalar(rand())/RAND_MAX); 00938 // rnd.Normalize(); 00939 // Matrix44<scalar> m,t0,t1,tr; 00940 // Point3<scalar> axis = rnd ^ (view_p-c).Normalize(); 00941 // scalar RadRandAngle=RadAngle*(1.0 - 2.0*scalar(rand())/RAND_MAX); 00942 // t0.Translate(c); 00943 // t1.Translate(-c); 00944 // m.Rotate(ToDeg(RadRandAngle),axis); 00945 // tr=t1*m*t0; 00946 // Apply(tr); 00947 //} 00948 // 00949 // 00950 // 00951 // 00952 //void glTexGen(int offx =0, // angolo basso sinistra della 00953 // int offy=0, // subtexture per la quale si vogliono settare le coordinate 00954 // int sx=1, // Dimensioni in Texel 00955 // int sy=1, 00956 // int Tx=1, // Dimensioni della texture 00957 // int Ty=1) 00958 //{ 00959 // // prendi la rototraslazione che 00960 // // trasforma la coordinata nel 00961 // // sistema di coordinate della camera 00962 // Matrix44d M; 00963 // M[0][0] = x_axis[0]; 00964 // M[0][1] = x_axis[1]; 00965 // M[0][2] = x_axis[2]; 00966 // M[0][3] = -view_p* x_axis ; 00967 // 00968 // M[1][0] = y_axis[0]; 00969 // M[1][1] = y_axis[1]; 00970 // M[1][2] = y_axis[2]; 00971 // M[1][3] = -view_p* y_axis; 00972 // 00973 // M[2][0] = z_axis[0]; 00974 // M[2][1] = z_axis[1]; 00975 // M[2][2] = z_axis[2]; 00976 // M[2][3] = -view_p* z_axis; 00977 // 00978 // M[3][0] = 0.0; 00979 // M[3][1] = 0.0; 00980 // M[3][2] = 0.0; 00981 // M[3][3] = 1.0; 00982 // 00983 // // prendi la matrice di proiezione 00984 // Matrix44d P; 00985 // P.SetZero(); 00986 // 00987 // if(!IsOrtho())// prospettica 00988 // { 00989 // 00990 // P[0][0] = sx/(s[0]*viewport[0]*Tx); 00991 // P[0][2] = (1/f)*(offx+0.5*sx)/Tx; 00992 // 00993 // P[1][1] = sy/(s[1]* viewport[1]*Ty); 00994 // P[1][2] = (1/f)*(offy+0.5*sy)/Ty; 00995 // 00996 // P[2][2] = 1; 00997 // P[3][2] = 1/f; 00998 // } 00999 // else // ortogonale 01000 // { 01001 // P[0][0] = sx/(s[0]*viewport[0]*viewportM*Tx); 01002 // P[0][3] = (offx+0.5*sx)/Tx; // l'effetto e' una traslazione di +1/2 01003 // 01004 // P[1][1] = sy/(s[1]* viewport[1]*viewportM*Ty); 01005 // P[1][3] = (offy+0.5*sy)/Ty; // l'effetto e' una traslazione di +1/2 01006 // 01007 // P[2][2] = 1; 01008 // P[3][3] = 1; 01009 // } 01010 // // componi 01011 // Matrix44d PM = P*M; 01012 // 01013 // glTexGend(GL_S, GL_TEXTURE_GEN_MODE, GL_OBJECT_LINEAR); 01014 // glTexGend(GL_T, GL_TEXTURE_GEN_MODE, GL_OBJECT_LINEAR); 01015 // glTexGend(GL_Q, GL_TEXTURE_GEN_MODE, GL_OBJECT_LINEAR); 01016 // 01017 // glTexGendv(GL_S,GL_OBJECT_PLANE,&PM[0][0]); 01018 // glTexGendv(GL_T,GL_OBJECT_PLANE,&PM[1][0]); 01019 // glTexGendv(GL_Q,GL_OBJECT_PLANE,&PM[3][0]); 01020 // 01021 // glEnable(GL_TEXTURE_GEN_S); 01022 // glEnable(GL_TEXTURE_GEN_T); 01023 // glDisable(GL_TEXTURE_GEN_R); 01024 // glEnable(GL_TEXTURE_GEN_Q); 01025 //} 01026 // 01029 //void glTexGen_NV(int sx, // Texture Size 01030 // int sy) 01031 //{ 01032 // // prendi la rototraslazione che 01033 // // trasforma la coordinata nel 01034 // // sistema di coordinate della camera 01035 // Matrix44d M; 01036 // M[0][0] = x_axis[0]; 01037 // M[0][1] = x_axis[1]; 01038 // M[0][2] = x_axis[2]; 01039 // M[0][3] = -view_p* x_axis ; 01040 // 01041 // M[1][0] = y_axis[0]; 01042 // M[1][1] = y_axis[1]; 01043 // M[1][2] = y_axis[2]; 01044 // M[1][3] = -view_p* y_axis; 01045 // 01046 // M[2][0] = z_axis[0]; 01047 // M[2][1] = z_axis[1]; 01048 // M[2][2] = z_axis[2]; 01049 // M[2][3] = -view_p* z_axis; 01050 // 01051 // M[3][0] = 0.0; 01052 // M[3][1] = 0.0; 01053 // M[3][2] = 0.0; 01054 // M[3][3] = 1.0; 01055 // 01056 // // prendi la matrice di proiezione 01057 // Matrix44d P; 01058 // P.SetZero(); 01059 // 01060 // if(!IsOrtho())// prospettica 01061 // { 01062 // 01063 // P[0][0] = sx/(s[0]*viewport[0]); 01064 // P[0][2] = sx*(1/f)*( 0.5); 01065 // 01066 // P[1][1] = sy/(s[1]* viewport[1] ); 01067 // P[1][2] = sy*(1/f)*( 0.5); 01068 // 01069 // P[2][2] = 1; 01070 // P[3][2] = 1/f; 01071 // } 01072 // else // ortogonale 01073 // { 01074 // P[0][0] = sx/(s[0]*viewport[0]*viewportM); 01075 // P[0][3] = sx* 0.5 ; // l'effetto e' una traslazione di +1/2 01076 // 01077 // P[1][1] = sy/(s[1]* viewport[1]*viewportM); 01078 // P[1][3] = sy* 0.5 ; // l'effetto e' una traslazione di +1/2 01079 // 01080 // P[2][2] = 1; 01081 // P[3][3] = 1; 01082 // } 01083 // // componi 01084 // Matrix44d PM = P*M; 01085 // 01086 // glTexGend(GL_S, GL_TEXTURE_GEN_MODE, GL_OBJECT_LINEAR); 01087 // glTexGend(GL_T, GL_TEXTURE_GEN_MODE, GL_OBJECT_LINEAR); 01088 // glTexGend(GL_Q, GL_TEXTURE_GEN_MODE, GL_OBJECT_LINEAR); 01089 // 01090 // glTexGendv(GL_S,GL_OBJECT_PLANE,&PM[0][0]); 01091 // glTexGendv(GL_T,GL_OBJECT_PLANE,&PM[1][0]); 01092 // glTexGendv(GL_Q,GL_OBJECT_PLANE,&PM[3][0]); 01093 // 01094 // glEnable(GL_TEXTURE_GEN_S); 01095 // glEnable(GL_TEXTURE_GEN_T); 01096 // glDisable(GL_TEXTURE_GEN_R); 01097 // glEnable(GL_TEXTURE_GEN_Q); 01099 // 01100 //} 01101 //#endif // __GL_H__ 01102 // 01103 //}; 01104 //} // End namespace vcg