00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #ifndef __VCGLIB_FITTING3
00025 #define __VCGLIB_FITTING3
00026
00027 #include <vector>
00028 #include <vcg/space/plane3.h>
00029 #include <vcg/math/matrix44.h>
00030 #include <vcg/math/matrix33.h>
00031
00032 #include <eigenlib/Eigen/Core>
00033 #include <eigenlib/Eigen/Eigenvalues>
00034
00035 namespace vcg {
00036
00041 template <class S >
00042 void ComputeCovarianceMatrix(const std::vector<Point3<S> > &pointVec, Point3<S> &barycenter, Eigen::Matrix<S,3,3> &m)
00043 {
00044
00045 barycenter.SetZero();
00046 typename std::vector< Point3<S> >::const_iterator pit;
00047 for( pit = pointVec.begin(); pit != pointVec.end(); ++pit) barycenter+= (*pit);
00048 barycenter/=pointVec.size();
00049
00050
00051 m.setZero();
00052 Eigen::Matrix<S,3,1> p;
00053 for(pit = pointVec.begin(); pit != pointVec.end(); ++pit) {
00054 ((*pit)-barycenter).ToEigenVector(p);
00055 m+= p*p.transpose();
00056 }
00057 }
00058
00064 template <class S>
00065 void FitPlaneToPointSet(const std::vector< Point3<S> > & pointVec, Plane3<S> & plane)
00066 {
00067 Eigen::Matrix<S,3,3> covMat = Eigen::Matrix<S,3,3>::Zero();
00068 Point3<S> b;
00069 ComputeCovarianceMatrix(pointVec,b,covMat);
00070
00071 Eigen::SelfAdjointEigenSolver<Eigen::Matrix<S,3,3> > eig(covMat);
00072 Eigen::Matrix<S,3,1> eval = eig.eigenvalues();
00073 Eigen::Matrix<S,3,3> evec = eig.eigenvectors();
00074 eval = eval.cwiseAbs();
00075 int minInd;
00076 eval.minCoeff(&minInd);
00077 Point3<S> d;
00078 d[0] = evec(0,minInd);
00079 d[1] = evec(1,minInd);
00080 d[2] = evec(2,minInd);
00081
00082 plane.Init(b,d);
00083 }
00084
00090 template <class S >
00091 void ComputeWeightedCovarianceMatrix(const std::vector<Point3<S> > &pointVec, const std::vector<S> &weightVec, Point3<S> &bp, Eigen::Matrix<S,3,3> &m)
00092 {
00093 assert(pointVec.size() == weightVec.size());
00094
00095 bp.SetZero();
00096 S wSum=0;
00097 typename std::vector< Point3<S> >::const_iterator pit;
00098 typename std::vector< S>::const_iterator wit;
00099 for( pit = pointVec.begin(),wit=weightVec.begin(); pit != pointVec.end(); ++pit,++wit)
00100 {
00101 bp+= (*pit)*(*wit);
00102 wSum+=*wit;
00103 }
00104 bp /=wSum;
00105
00106
00107
00108 m.setZero();
00109 Eigen::Matrix<S,3,3> A;
00110 Eigen::Matrix<S,3,1> p;
00111 for( pit = pointVec.begin(),wit=weightVec.begin(); pit != pointVec.end(); ++pit,++wit)
00112 {
00113 (((*pit)-bp)*(*wit)).ToEigenVector(p);
00114 m+= p*p.transpose();
00115 }
00116 m/=wSum;
00117 }
00123 template <class S>
00124 void WeightedFitPlaneToPointSet(const std::vector< Point3<S> > & pointVec, const std::vector<S> &weightVec, Plane3<S> & plane)
00125 {
00126 Eigen::Matrix<S,3,3> covMat = Eigen::Matrix<S,3,3>::Zero();
00127 Point3<S> b;
00128 ComputeWeightedCovarianceMatrix(pointVec,weightVec, b,covMat);
00129
00130 Eigen::SelfAdjointEigenSolver<Eigen::Matrix<S,3,3> > eig(covMat);
00131 Eigen::Matrix<S,3,1> eval = eig.eigenvalues();
00132 Eigen::Matrix<S,3,3> evec = eig.eigenvectors();
00133 eval = eval.cwiseAbs();
00134 int minInd;
00135 eval.minCoeff(&minInd);
00136 Point3<S> d;
00137 d[0] = evec(0,minInd);
00138 d[1] = evec(1,minInd);
00139 d[2] = evec(2,minInd);
00140
00141 plane.Init(b,d);
00142 }
00143
00144 }
00145
00146 #endif