point_matching.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 #ifndef _VCG_MATH_POINTMATCHING_H
00025 #define _VCG_MATH_POINTMATCHING_H
00026 
00027 #include <vcg/math/quaternion.h>
00028 #include <vcg/math/matrix44.h>
00029 
00030 #include <eigenlib/Eigen/Dense>
00031 #include <eigenlib/Eigen/Eigenvalues>
00032 #include  <iostream>
00033 
00034 namespace vcg
00035 {
00036 
00048 template <class S >
00049 void ComputeCrossCovarianceMatrix(const std::vector<Point3<S> > &spVec, Point3<S> &spBarycenter,
00050                                   const std::vector<Point3<S> > &tpVec, Point3<S> &tpBarycenter,
00051                                   Eigen::Matrix3d &m)
00052 {
00053     assert(spVec.size()==tpVec.size());
00054     m.setZero();
00055     spBarycenter.SetZero();
00056     tpBarycenter.SetZero();
00057     Eigen::Vector3d spe;
00058     Eigen::Vector3d tpe;
00059     typename std::vector <Point3<S> >::const_iterator si,ti;
00060     for(si=spVec.begin(),ti=tpVec.begin();si!=spVec.end();++si,++ti){
00061         spBarycenter+=*si;
00062         tpBarycenter+=*ti;
00063          si->ToEigenVector(spe);
00064          ti->ToEigenVector(tpe);
00065         m+=spe*tpe.transpose();
00066     }
00067     spBarycenter/=spVec.size();
00068     tpBarycenter/=tpVec.size();
00069     spBarycenter.ToEigenVector(spe);
00070     tpBarycenter.ToEigenVector(tpe);
00071     m/=spVec.size();
00072     m-=spe*tpe.transpose();
00073 }
00074 
00088 template < class  S >
00089 void ComputeRigidMatchMatrix(std::vector<Point3<S> > &Pfix,
00090                              std::vector<Point3<S> > &Pmov,
00091                              Quaternion<S>  &q,
00092                              Point3<S>  &tr)
00093 {
00094   Eigen::Matrix3d ccm;
00095   Point3<S> bfix,bmov; // baricenter of src e trg
00096 
00097   ComputeCrossCovarianceMatrix(Pmov,bmov,Pfix,bfix,ccm);
00098 
00099   Eigen::Matrix3d cyc; // the cyclic components of the cross covariance matrix.
00100   cyc=ccm-ccm.transpose();
00101 
00102   Eigen::Matrix4d  QQ;
00103   QQ.setZero();
00104   Eigen::Vector3d D(cyc(1,2),cyc(2,0),cyc(0,1));
00105 
00106   Eigen::Matrix3d RM;
00107   RM.setZero();
00108   RM(0,0)=-ccm.trace();
00109   RM(1,1)=-ccm.trace();
00110   RM(2,2)=-ccm.trace();
00111   RM += ccm + ccm.transpose();
00112 
00113   QQ(0,0) = ccm.trace();
00114   QQ.block<1,3> (0,1) = D.transpose();
00115   QQ.block<3,1> (1,0) = D;
00116   QQ.block<3,3> (1,1) = RM;
00117 
00118   Eigen::SelfAdjointEigenSolver<Eigen::Matrix4d> eig(QQ);
00119   Eigen::Vector4d eval = eig.eigenvalues();
00120   Eigen::Matrix4d evec = eig.eigenvectors();
00121 //  std::cout << "EigenVectors:" << std::endl << evec << std::endl;
00122 //  std::cout << "Eigenvalues:" << std::endl << eval << std::endl;
00123   int ind;
00124   eval.cwiseAbs().maxCoeff(&ind);
00125 
00126   q=Quaternion<S>(evec.col(ind)[0],evec.col(ind)[1],evec.col(ind)[2],evec.col(ind)[3]);
00127   Matrix44<S> Rot;
00128   q.ToMatrix(Rot);
00129   tr= (bfix - Rot*bmov);
00130 }
00131 
00132 
00146 template < class  S >
00147 void ComputeRigidMatchMatrix(std::vector<Point3<S> > &Pfix,
00148                              std::vector<Point3<S> > &Pmov,
00149                              Matrix44<S> &res)
00150 {
00151     Quaternion<S>  q;
00152     Point3<S>  tr;
00153     ComputeRigidMatchMatrix(Pfix,Pmov,q,tr);
00154 
00155     Matrix44<S> Rot;
00156     q.ToMatrix(Rot);
00157 
00158     Matrix44<S> Trn;
00159     Trn.SetTranslate(tr);
00160 
00161     res=Trn*Rot;
00162 }
00163 
00164 
00165 /*
00166 Compute a similarity matching (rigid + uniform scaling)
00167 simply create a temporary point set with the correct scaling factor
00168 */ 
00169 template <class S>
00170 void ComputeSimilarityMatchMatrix(std::vector<Point3<S> > &Pfix,
00171                                   std::vector<Point3<S> > &Pmov,
00172                                   Matrix44<S> &res)
00173 {
00174   S scalingFactor=0;
00175   for(size_t i=0;i<( Pmov.size()-1);++i)
00176   {
00177     scalingFactor += Distance(Pmov[i],Pmov[i+1])/ Distance(Pfix[i],Pfix[i+1]);
00178   }
00179   scalingFactor/=(Pmov.size()-1);
00180 
00181   std::vector<Point3<S> > Pnew(Pmov.size());
00182   for(size_t i=0;i<Pmov.size();++i)
00183     Pnew[i]=Pmov[i]/scalingFactor;
00184 
00185   ComputeRigidMatchMatrix(Pfix,Pnew,res);
00186 
00187   Matrix44<S> scaleM; scaleM.SetDiagonal(1.0/scalingFactor);
00188   res = res * scaleM;
00189 }
00190 
00191 } // end namespace
00192 
00193 #endif


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