00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023 #ifndef __VCGLIB_MATRIX33_H
00024 #define __VCGLIB_MATRIX33_H
00025
00026 #include <stdio.h>
00027 #include <vcg/math/matrix44.h>
00028 #include <vcg/space/point3.h>
00029 #include <vector>
00030
00031 namespace vcg {
00032
00033 template<class S>
00039 class Matrix33
00040 {
00041 public:
00042 typedef S ScalarType;
00043
00045 inline Matrix33() {}
00046
00048 Matrix33( const Matrix33 & m )
00049 {
00050 for(int i=0;i<9;++i)
00051 a[i] = m.a[i];
00052 }
00053
00055 Matrix33( const S * v )
00056 {
00057 for(int i=0;i<9;++i) a[i] = v[i];
00058 }
00059
00061 Matrix33 (const Matrix44<S> & m, const int & k)
00062 {
00063 int i,j, r=0, c=0;
00064 for(i = 0; i< 4;++i)if(i!=k){c=0;
00065 for(j=0; j < 4;++j)if(j!=k)
00066 { (*this)[r][c] = m[i][j]; ++c;}
00067 ++r;
00068 }
00069 }
00070
00071 template <class EigenMatrix33Type>
00072 void ToEigenMatrix(EigenMatrix33Type & m) const {
00073 for(int i = 0; i < 3; i++)
00074 for(int j = 0; j < 3; j++)
00075 m(i,j)=(*this)[i][j];
00076 }
00077
00078 template <class EigenMatrix33Type>
00079 void FromEigenMatrix(const EigenMatrix33Type & m){
00080 for(int i = 0; i < 3; i++)
00081 for(int j = 0; j < 3; j++)
00082 (*this)[i][j]=m(i,j);
00083 }
00084
00085 static inline const Matrix33 &Identity( )
00086 {
00087 static Matrix33<S> tmp; tmp.SetIdentity();
00088 return tmp;
00089 }
00090
00092 inline unsigned int ColumnsNumber() const
00093 {
00094 return 3;
00095 };
00096
00098 inline unsigned int RowsNumber() const
00099 {
00100 return 3;
00101 };
00102
00104 Matrix33 & operator = ( const Matrix33 & m )
00105 {
00106 for(int i=0;i<9;++i)
00107 a[i] = m.a[i];
00108 return *this;
00109 }
00110
00111
00112
00114 inline S * operator [] ( const int i )
00115 {
00116 return a+i*3;
00117 }
00119 inline const S * operator [] ( const int i ) const
00120 {
00121 return a+i*3;
00122 }
00123
00124
00126 Matrix33 & operator += ( const Matrix33 &m )
00127 {
00128 for(int i=0;i<9;++i)
00129 a[i] += m.a[i];
00130 return *this;
00131 }
00132
00133
00135 Matrix33 & operator -= ( const Matrix33 &m )
00136 {
00137 for(int i=0;i<9;++i)
00138 a[i] -= m.a[i];
00139 return *this;
00140 }
00141
00143 Matrix33 & operator /= ( const S &s )
00144 {
00145 for(int i=0;i<9;++i)
00146 a[i] /= s;
00147 return *this;
00148 }
00149
00150
00152 Matrix33 operator * ( const Matrix33< S> & t ) const
00153 {
00154 Matrix33<S> r;
00155
00156 int i,j;
00157 for(i=0;i<3;++i)
00158 for(j=0;j<3;++j)
00159 r[i][j] = (*this)[i][0]*t[0][j] + (*this)[i][1]*t[1][j] + (*this)[i][2]*t[2][j];
00160
00161 return r;
00162 }
00163
00165 void operator *=( const Matrix33< S> & t )
00166 {
00167 Matrix33<S> r;
00168 int i,j;
00169 for(i=0;i<3;++i)
00170 for(j=0;j<3;++j)
00171 r[i][j] = (*this)[i][0]*t[0][j] + (*this)[i][1]*t[1][j] + (*this)[i][2]*t[2][j];
00172 for(i=0;i<9;++i) this->a[i] = r.a[i];
00173 }
00174
00176 Matrix33 & operator *= ( const S t )
00177 {
00178 for(int i=0;i<9;++i)
00179 a[i] *= t;
00180 return *this;
00181 }
00182
00184 Matrix33 operator * ( const S t ) const
00185 {
00186 Matrix33<S> r;
00187 for(int i=0;i<9;++i)
00188 r.a[i] = a[i]* t;
00189
00190 return r;
00191 }
00192
00194 Matrix33 operator - ( const Matrix33 &m ) const
00195 {
00196 Matrix33<S> r;
00197 for(int i=0;i<9;++i)
00198 r.a[i] = a[i] - m.a[i];
00199
00200 return r;
00201 }
00203 Matrix33 operator + ( const Matrix33 &m ) const
00204 {
00205 Matrix33<S> r;
00206 for(int i=0;i<9;++i)
00207 r.a[i] = a[i] + m.a[i];
00208
00209 return r;
00210 }
00215 Point3<S> operator * ( const Point3<S> & v ) const
00216 {
00217 Point3<S> t;
00218
00219 t[0] = a[0]*v[0] + a[1]*v[1] + a[2]*v[2];
00220 t[1] = a[3]*v[0] + a[4]*v[1] + a[5]*v[2];
00221 t[2] = a[6]*v[0] + a[7]*v[1] + a[8]*v[2];
00222 return t;
00223 }
00224
00225 void OuterProduct(Point3<S> const &p0, Point3<S> const &p1) {
00226 Point3<S> row;
00227 row = p1*p0[0];
00228 a[0] = row[0];a[1] = row[1];a[2] = row[2];
00229 row = p1*p0[1];
00230 a[3] = row[0]; a[4] = row[1]; a[5] = row[2];
00231 row = p1*p0[2];
00232 a[6] = row[0];a[7] = row[1];a[8] = row[2];
00233 }
00234
00235 Matrix33 & SetZero() {
00236 for(int i=0;i<9;++i) a[i] =0;
00237 return (*this);
00238 }
00239 Matrix33 & SetIdentity() {
00240 for(int i=0;i<9;++i) a[i] =0;
00241 a[0]=a[4]=a[8]=1.0;
00242 return (*this);
00243 }
00244
00245 Matrix33 & SetRotateRad(S angle, const Point3<S> & axis )
00246 {
00247 S c = cos(angle);
00248 S s = sin(angle);
00249 S q = 1-c;
00250 Point3<S> t = axis;
00251 t.Normalize();
00252 a[0] = t[0]*t[0]*q + c;
00253 a[1] = t[0]*t[1]*q - t[2]*s;
00254 a[2] = t[0]*t[2]*q + t[1]*s;
00255 a[3] = t[1]*t[0]*q + t[2]*s;
00256 a[4] = t[1]*t[1]*q + c;
00257 a[5] = t[1]*t[2]*q - t[0]*s;
00258 a[6] = t[2]*t[0]*q -t[1]*s;
00259 a[7] = t[2]*t[1]*q +t[0]*s;
00260 a[8] = t[2]*t[2]*q +c;
00261 return (*this);
00262 }
00263 Matrix33 & SetRotateDeg(S angle, const Point3<S> & axis ){
00264 return SetRotateRad(math::ToRad(angle),axis);
00265 }
00266
00268 Matrix33 & Transpose()
00269 {
00270 std::swap(a[1],a[3]);
00271 std::swap(a[2],a[6]);
00272 std::swap(a[5],a[7]);
00273 return *this;
00274 }
00275
00276
00277 Matrix33 transpose() const
00278 {
00279 Matrix33 res = *this;
00280 res.Transpose();
00281 return res;
00282 }
00283
00284 void transposeInPlace() { this->Transpose(); }
00285
00287 Matrix33 & SetDiagonal(S *v)
00288 {int i,j;
00289 for(i=0;i<3;i++)
00290 for(j=0;j<3;j++)
00291 if(i==j) (*this)[i][j] = v[i];
00292 else (*this)[i][j] = 0;
00293 return *this;
00294 }
00295
00296
00298 void SetColumn(const int n, S* v){
00299 assert( (n>=0) && (n<3) );
00300 a[n]=v[0]; a[n+3]=v[1]; a[n+6]=v[2];
00301 };
00302
00304 void SetRow(const int n, S* v){
00305 assert( (n>=0) && (n<3) );
00306 int m=n*3;
00307 a[m]=v[0]; a[m+1]=v[1]; a[m+2]=v[2];
00308 };
00309
00311 void SetColumn(const int n, const Point3<S> v){
00312 assert( (n>=0) && (n<3) );
00313 a[n]=v[0]; a[n+3]=v[1]; a[n+6]=v[2];
00314 };
00315
00317 void SetRow(const int n, const Point3<S> v){
00318 assert( (n>=0) && (n<3) );
00319 int m=n*3;
00320 a[m]=v[0]; a[m+1]=v[1]; a[m+2]=v[2];
00321 };
00322
00324 Point3<S> GetColumn(const int n) const {
00325 assert( (n>=0) && (n<3) );
00326 Point3<S> t;
00327 t[0]=a[n]; t[1]=a[n+3]; t[2]=a[n+6];
00328 return t;
00329 };
00330
00332 Point3<S> GetRow(const int n) const {
00333 assert( (n>=0) && (n<3) );
00334 Point3<S> t;
00335 int m=n*3;
00336 t[0]=a[m]; t[1]=a[m+1]; t[2]=a[m+2];
00337 return t;
00338 };
00339
00340
00341
00343 S Determinant() const
00344 {
00345 return a[0]*(a[4]*a[8]-a[5]*a[7]) -
00346 a[1]*(a[3]*a[8]-a[5]*a[6]) +
00347 a[2]*(a[3]*a[7]-a[4]*a[6]) ;
00348 }
00349
00350
00351 S Trace() const
00352 {
00353 return a[0]+a[4]+a[8];
00354 }
00355
00356
00357
00358
00359 void ExternalProduct(const Point3<S> &a, const Point3<S> &b)
00360 {
00361 for(int i=0;i<3;++i)
00362 for(int j=0;j<3;++j)
00363 (*this)[i][j] = a[i]*b[j];
00364 }
00365
00366
00367
00368 ScalarType Norm()
00369 {
00370 ScalarType SQsum=0;
00371 for(int i=0;i<3;++i)
00372 for(int j=0;j<3;++j)
00373 SQsum += a[i]*a[i];
00374 return (math::Sqrt(SQsum));
00375 }
00376
00377
00378
00379
00380
00381 template <class STLPOINTCONTAINER >
00382 void Covariance(const STLPOINTCONTAINER &points, Point3<S> &bp) {
00383 assert(!points.empty());
00384 typedef typename STLPOINTCONTAINER::const_iterator PointIte;
00385
00386 bp.SetZero();
00387 for( PointIte pi = points.begin(); pi != points.end(); ++pi) bp+= (*pi);
00388 bp/=points.size();
00389
00390 this->SetZero();
00391 vcg::Matrix33<ScalarType> A;
00392 for( PointIte pi = points.begin(); pi != points.end(); ++pi) {
00393 Point3<S> p = (*pi)-bp;
00394 A.OuterProduct(p,p);
00395 (*this)+= A;
00396 }
00397 }
00398
00399
00400
00401
00402
00403
00404
00405
00406
00407
00408
00409
00410
00411 template <class STLPOINTCONTAINER >
00412 void CrossCovariance(const STLPOINTCONTAINER &P, const STLPOINTCONTAINER &X,
00413 Point3<S> &bp, Point3<S> &bx)
00414 {
00415 SetZero();
00416 assert(P.size()==X.size());
00417 bx.SetZero();
00418 bp.SetZero();
00419 Matrix33<S> tmp;
00420 typename std::vector <Point3<S> >::const_iterator pi,xi;
00421 for(pi=P.begin(),xi=X.begin();pi!=P.end();++pi,++xi){
00422 bp+=*pi;
00423 bx+=*xi;
00424 tmp.ExternalProduct(*pi,*xi);
00425 (*this)+=tmp;
00426 }
00427 bp/=P.size();
00428 bx/=X.size();
00429 (*this)/=P.size();
00430 tmp.ExternalProduct(bp,bx);
00431 (*this)-=tmp;
00432 }
00433
00434 template <class STLPOINTCONTAINER, class STLREALCONTAINER>
00435 void WeightedCrossCovariance(const STLREALCONTAINER & weights,
00436 const STLPOINTCONTAINER &P,
00437 const STLPOINTCONTAINER &X,
00438 Point3<S> &bp,
00439 Point3<S> &bx)
00440 {
00441 SetZero();
00442 assert(P.size()==X.size());
00443 bx.SetZero();
00444 bp.SetZero();
00445 Matrix33<S> tmp;
00446 typename std::vector <Point3<S> >::const_iterator pi,xi;
00447 typename STLREALCONTAINER::const_iterator pw;
00448
00449 for(pi=P.begin(),xi=X.begin();pi!=P.end();++pi,++xi){
00450 bp+=(*pi);
00451 bx+=(*xi);
00452 }
00453 bp/=P.size();
00454 bx/=X.size();
00455
00456 for(pi=P.begin(),xi=X.begin(),pw = weights.begin();pi!=P.end();++pi,++xi,++pw){
00457
00458 tmp.ExternalProduct(((*pi)-(bp)),((*xi)-(bp)));
00459
00460 (*this)+=tmp*(*pw);
00461 }
00462 }
00463
00464 private:
00465 S a[9];
00466 };
00467
00470 template <class S>
00471 vcg::Matrix33<S> TransformationMatrix(const vcg::Point3<S> dirX,
00472 const vcg::Point3<S> dirY,
00473 const vcg::Point3<S> dirZ)
00474 {
00475 vcg::Matrix33<S> Trans;
00476
00478 Trans[0][0]=dirX[0];
00479 Trans[0][1]=dirX[1];
00480 Trans[0][2]=dirX[2];
00481 Trans[1][0]=dirY[0];
00482 Trans[1][1]=dirY[1];
00483 Trans[1][2]=dirY[2];
00484 Trans[2][0]=dirZ[0];
00485 Trans[2][1]=dirZ[1];
00486 Trans[2][2]=dirZ[2];
00487
00489 return (Trans);
00490 }
00491 template <class S>
00492 Matrix33<S> Inverse(const Matrix33<S>&m)
00493 {
00494 Eigen::Matrix3d mm,mmi;
00495 m.ToEigenMatrix(mm);
00496 mmi=mm.inverse();
00497 Matrix33<S> res;
00498 res.FromEigenMatrix(mmi);
00499 return res;
00500 }
00501
00503 template <class S>
00504 Matrix33<S> RotationMatrix(vcg::Point3<S> v0,vcg::Point3<S> v1,bool normalized=true)
00505 {
00506 typedef typename vcg::Point3<S> CoordType;
00507 Matrix33<S> rotM;
00508 const S epsilon=0.00001;
00509 if (!normalized)
00510 {
00511 v0.Normalize();
00512 v1.Normalize();
00513 }
00514 S dot=(v0*v1);
00516 if (dot>((S)1-epsilon))
00517 {
00518 rotM.SetIdentity();
00519 return rotM;
00520 }
00521
00523 CoordType axis;
00524 axis=v0^v1;
00525 axis.Normalize();
00526
00528 S u=axis.X();
00529 S v=axis.Y();
00530 S w=axis.Z();
00531 S phi=acos(dot);
00532 S rcos = cos(phi);
00533 S rsin = sin(phi);
00534
00535 rotM[0][0] = rcos + u*u*(1-rcos);
00536 rotM[1][0] = w * rsin + v*u*(1-rcos);
00537 rotM[2][0] = -v * rsin + w*u*(1-rcos);
00538 rotM[0][1] = -w * rsin + u*v*(1-rcos);
00539 rotM[1][1] = rcos + v*v*(1-rcos);
00540 rotM[2][1] = u * rsin + w*v*(1-rcos);
00541 rotM[0][2] = v * rsin + u*w*(1-rcos);
00542 rotM[1][2] = -u * rsin + v*w*(1-rcos);
00543 rotM[2][2] = rcos + w*w*(1-rcos);
00544
00545 return rotM;
00546 }
00547
00549 template <class S>
00550 Matrix33<S> RotationMatrix(const vcg::Point3<S> &axis,
00551 const float &angleRad)
00552 {
00553 vcg::Matrix44<S> matr44;
00554 vcg::Matrix33<S> matr33;
00555 matr44.SetRotateRad(angleRad,axis);
00556 for (int i=0;i<3;i++)
00557 for (int j=0;j<3;j++)
00558 matr33[i][j]=matr44[i][j];
00559 return matr33;
00560 }
00561
00565 template <class S>
00566 Matrix33<S> RandomRotation(){
00567 S x1,x2,x3;
00568 Matrix33<S> R,H,M,vv;
00569 Point3<S> v;
00570 R.SetIdentity();
00571 H.SetIdentity();
00572 x1 = rand()/S(RAND_MAX);
00573 x2 = rand()/S(RAND_MAX);
00574 x3 = rand()/S(RAND_MAX);
00575
00576 R[0][0] = cos(S(2)*M_PI*x1);
00577 R[0][1] = sin(S(2)*M_PI*x1);
00578 R[1][0] = - R[0][1];
00579 R[1][1] = R[0][0];
00580
00581 v[0] = cos(2.0 * M_PI * x2)*sqrt(x3);
00582 v[1] = sin(2.0 * M_PI * x2)*sqrt(x3);
00583 v[2] = sqrt(1-x3);
00584
00585 vv.OuterProduct(v,v);
00586 H -= vv*S(2);
00587 M = H*R*S(-1);
00588 return M;
00589 }
00590
00592 typedef Matrix33<short> Matrix33s;
00593 typedef Matrix33<int> Matrix33i;
00594 typedef Matrix33<float> Matrix33f;
00595 typedef Matrix33<double> Matrix33d;
00596
00597 }
00598
00599 #endif