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 #ifndef VCGLIB_UPDATE_CURVATURE_FITTING
00028 #define VCGLIB_UPDATE_CURVATURE_FITTING
00029
00030 #include <vcg/space/index/grid_static_ptr.h>
00031 #include <vcg/math/base.h>
00032 #include <vcg/math/matrix.h>
00033 #include <vcg/simplex/face/topology.h>
00034 #include <vcg/simplex/face/pos.h>
00035 #include <vcg/simplex/face/jumping_pos.h>
00036 #include <vcg/container/simple_temporary_data.h>
00037 #include <vcg/complex/trimesh/update/normal.h>
00038 #include <vcg/complex/trimesh/point_sampling.h>
00039 #include <vcg/complex/trimesh/append.h>
00040 #include <vcg/complex/intersection.h>
00041 #include <vcg/complex/trimesh/inertia.h>
00042 #include <vcg/math/matrix33.h>
00043
00044 #include <vcg/Eigen/Core>
00045 #include <vcg/Eigen/QR>
00046 #include <vcg/Eigen/LU>
00047
00048
00049
00050 namespace vcg {
00051 namespace tri {
00052
00054
00056
00058
00062 template <class MeshType>
00063 class UpdateCurvatureFitting
00064 {
00065
00066 public:
00067 typedef typename MeshType::FaceType FaceType;
00068 typedef typename MeshType::FacePointer FacePointer;
00069 typedef typename MeshType::FaceIterator FaceIterator;
00070 typedef typename MeshType::VertexIterator VertexIterator;
00071 typedef typename MeshType::VertContainer VertContainer;
00072 typedef typename MeshType::VertexType VertexType;
00073 typedef typename MeshType::VertexPointer VertexPointer;
00074 typedef typename MeshType::VertexPointer VertexTypeP;
00075 typedef vcg::face::VFIterator<FaceType> VFIteratorType;
00076 typedef typename MeshType::CoordType CoordType;
00077 typedef typename CoordType::ScalarType ScalarType;
00078
00079 class Quadric
00080 {
00081 public:
00082
00083 Quadric(double av, double bv, double cv, double dv, double ev)
00084 {
00085 a() = av;
00086 b() = bv;
00087 c() = cv;
00088 d() = dv;
00089 e() = ev;
00090 }
00091
00092 double& a() { return data[0];}
00093 double& b() { return data[1];}
00094 double& c() { return data[2];}
00095 double& d() { return data[3];}
00096 double& e() { return data[4];}
00097
00098 double data[5];
00099
00100 double evaluate(double u, double v)
00101 {
00102 return a*u*u + b*u*v + c*v*v + d*u + e*v;
00103 }
00104
00105 double du(double u, double v)
00106 {
00107 return 2.0*a()*u + b()*v + d();
00108 }
00109
00110 double dv(double u, double v)
00111 {
00112 return 2.0*c()*v + b()*u + e();
00113 }
00114
00115 double duv(double u, double v)
00116 {
00117 return b();
00118 }
00119
00120 double duu(double u, double v)
00121 {
00122 return 2.0*a();
00123 }
00124
00125 double dvv(double u, double v)
00126 {
00127 return 2.0*c();
00128 }
00129
00130 static Quadric fit(std::vector<CoordType> VV)
00131 {
00132 assert(VV.size() >= 5);
00133 Eigen::MatrixXf A(VV.size(),5);
00134 Eigen::MatrixXf b(VV.size(),1);
00135 Eigen::MatrixXf sol(VV.size(),1);
00136
00137 for(unsigned int c=0; c < VV.size(); ++c)
00138 {
00139 double u = VV[c].X();
00140 double v = VV[c].Y();
00141 double n = VV[c].Z();
00142
00143 A(c,0) = u*u;
00144 A(c,1) = u*v;
00145 A(c,2) = v*v;
00146 A(c,3) = u;
00147 A(c,4) = v;
00148
00149 b[c] = n;
00150 }
00151
00152 sol = ((A.transpose()*A).inverse()*A.transpose())*b;
00153 return Quadric(sol[0],sol[1],sol[2],sol[3],sol[4]);
00154 }
00155 };
00156
00157 static CoordType project(VertexType* v, VertexType* vp)
00158 {
00159 return vp->P() - (v->N() * ((vp->P() - v->P()) * v->N()));
00160 }
00161
00162
00163 static std::vector<CoordType> computeReferenceFrames(VertexTypeP vi)
00164 {
00165 vcg::face::VFIterator<FaceType> vfi(vi);
00166
00167 int i = (vfi.I()+1)%3;
00168 VertexTypeP vp = vfi.F()->V(i);
00169
00170 CoordType x = (project(&*vi,vp) - vi->P()).Normalize();
00171
00172 assert(fabs(x * vi->N()) < 0.1);
00173
00174 std::vector<CoordType> res(3);
00175
00176 res[0] = x;
00177 res[1] = (vi->N() ^ res[0]).Normalize();
00178 res[2] = (vi->N())/(vi->N()).Norm();
00179
00180 return res;
00181 }
00182
00183 static std::set<CoordType> getSecondRing(VertexTypeP v)
00184 {
00185 std::set<VertexTypeP> ris;
00186 std::set<CoordType> coords;
00187
00188 vcg::face::VFIterator<FaceType> vvi(v);
00189 for(;!vvi.End();++vvi)
00190 {
00191 vcg::face::VFIterator<FaceType> vvi2(vvi.F()->V((vvi.I()+1)%3));
00192 for(;!vvi2.End();++vvi2)
00193 {
00194 ris.insert(vvi2.F()->V((vvi2.I()+1)%3));
00195 }
00196 }
00197 typename std::set<VertexTypeP>::iterator it;
00198 for(it = ris.begin(); it != ris.end(); ++it)
00199 coords.insert((*it)->P());
00200
00201 return coords;
00202 }
00203
00204 static Quadric fitQuadric(VertexTypeP v, std::vector<CoordType>& ref)
00205 {
00206 std::set<CoordType> ring = getSecondRing(v);
00207 if (ring.size() < 5)
00208 return Quadric(1,1,1,1,1);
00209 std::vector<CoordType> points;
00210
00211 typename std::set<CoordType>::iterator b = ring.begin();
00212 typename std::set<CoordType>::iterator e = ring.end();
00213
00214 while(b != e)
00215 {
00216
00217 CoordType vTang = *b - v->P();
00218
00219 double x = vTang * ref[0];
00220 double y = vTang * ref[1];
00221 double z = vTang * ref[2];
00222 points.push_back(CoordType(x,y,z));
00223 ++b;
00224 }
00225 return Quadric::fit(points);
00226 }
00227
00228
00229 static void computeCurvature(MeshType & m)
00230 {
00231
00232 assert(tri::HasPerVertexVFAdjacency(m) && tri::HasPerFaceVFAdjacency(m) );
00233
00234 vcg::tri::UpdateTopology<MeshType>::VertexFace(m);
00235
00236 vcg::tri::UpdateNormals<MeshType>::PerVertexAngleWeighted(m);
00237 vcg::tri::UpdateNormals<MeshType>::NormalizeVertex(m);
00238
00239
00240 VertexIterator vi;
00241 for(vi = m.vert.begin(); vi!=m.vert.end(); ++vi )
00242 {
00243 std::vector<CoordType> ref = computeReferenceFrames(&*vi);
00244
00245 Quadric q = fitQuadric(&*vi,ref);
00246 double a = q.a();
00247 double b = q.b();
00248 double c = q.c();
00249 double d = q.d();
00250 double e = q.e();
00251
00252 double E = 1.0 + d*d;
00253 double F = d*e;
00254 double G = 1.0 + e*e;
00255
00256 CoordType n = CoordType(-d,-e,1.0).Normalize();
00257
00258 vi->N() = ref[0] * n[0] + ref[1] * n[1] + ref[2] * n[2];
00259
00260 double L = 2.0 * a * n.Z();
00261 double M = b * n.Z();
00262 double N = 2 * c * n.Z();
00263
00264
00265 Eigen::Matrix2d m;
00266 m << L*G - M*F, M*E-L*F, M*E-L*F, N*E-M*F;
00267 m = m / (E*G-F*F);
00268 Eigen::SelfAdjointEigenSolver<Eigen::Matrix2d> eig(m);
00269
00270 Eigen::Vector2d c_val = eig.eigenvalues();
00271 Eigen::Matrix2d c_vec = eig.eigenvectors();
00272
00273 c_val = -c_val;
00274
00275 CoordType v1, v2;
00276 v1[0] = c_vec[0];
00277 v1[1] = c_vec[1];
00278 v1[2] = 0;
00279
00280 v2[0] = c_vec[2];
00281 v2[1] = c_vec[3];
00282 v2[2] = 0;
00283
00284 v1 = v1.Normalize();
00285 v2 = v2.Normalize();
00286
00287 v1 = v1 * c_val[0];
00288 v2 = v2 * c_val[1];
00289
00290 CoordType v1global = ref[0] * v1[0] + ref[1] * v1[1] + ref[2] * v1[2];
00291 CoordType v2global = ref[0] * v2[0] + ref[1] * v2[1] + ref[2] * v2[2];
00292
00293 v1global.Normalize();
00294 v2global.Normalize();
00295
00296 if (c_val[0] > c_val[1])
00297 {
00298 (*vi).PD1() = v1global;
00299 (*vi).PD2() = v2global;
00300 (*vi).K1() = c_val[0];
00301 (*vi).K2() = c_val[1];
00302 }
00303 else
00304 {
00305 (*vi).PD1() = v2global;
00306 (*vi).PD2() = v1global;
00307 (*vi).K1() = c_val[1];
00308 (*vi).K2() = c_val[0];
00309 }
00310
00311 }
00312 }
00313 };
00314
00315 }
00316 }
00317 #endif