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/simplex/face/topology.h>
00032 #include <vcg/simplex/face/pos.h>
00033 #include <vcg/simplex/face/jumping_pos.h>
00034 #include <vcg/container/simple_temporary_data.h>
00035 #include <vcg/complex/algorithms/update/normal.h>
00036 #include <vcg/complex/algorithms/point_sampling.h>
00037 #include <vcg/complex/algorithms/intersection.h>
00038 #include <vcg/complex/algorithms/inertia.h>
00039 #include <vcg/complex/algorithms/nring.h>
00040
00041 #include <eigenlib/Eigen/Core>
00042 #include <eigenlib/Eigen/QR>
00043 #include <eigenlib/Eigen/LU>
00044 #include <eigenlib/Eigen/SVD>
00045 #include <eigenlib/Eigen/Eigenvalues>
00046
00047
00048 namespace vcg {
00049 namespace tri {
00050
00052
00054
00056
00060 template <class MeshType>
00061 class UpdateCurvatureFitting
00062 {
00063
00064 public:
00065 typedef typename MeshType::FaceType FaceType;
00066 typedef typename MeshType::FacePointer FacePointer;
00067 typedef typename MeshType::FaceIterator FaceIterator;
00068 typedef typename MeshType::VertexIterator VertexIterator;
00069 typedef typename MeshType::VertContainer VertContainer;
00070 typedef typename MeshType::VertexType VertexType;
00071 typedef typename MeshType::VertexPointer VertexPointer;
00072 typedef typename MeshType::VertexPointer VertexTypeP;
00073 typedef vcg::face::VFIterator<FaceType> VFIteratorType;
00074 typedef typename MeshType::CoordType CoordType;
00075 typedef typename CoordType::ScalarType ScalarType;
00076
00077 class Quadric
00078 {
00079 public:
00080
00081 Quadric(double av, double bv, double cv, double dv, double ev)
00082 {
00083 a() = av;
00084 b() = bv;
00085 c() = cv;
00086 d() = dv;
00087 e() = ev;
00088 }
00089
00090 double& a() { return data[0];}
00091 double& b() { return data[1];}
00092 double& c() { return data[2];}
00093 double& d() { return data[3];}
00094 double& e() { return data[4];}
00095
00096 double data[5];
00097
00098 double evaluate(double u, double v)
00099 {
00100 return a()*u*u + b()*u*v + c()*v*v + d()*u + e()*v;
00101 }
00102
00103 double du(double u, double v)
00104 {
00105 return 2.0*a()*u + b()*v + d();
00106 }
00107
00108 double dv(double u, double v)
00109 {
00110 return 2.0*c()*v + b()*u + e();
00111 }
00112
00113 double duv(double , double )
00114 {
00115 return b();
00116 }
00117
00118 double duu(double , double )
00119 {
00120 return 2.0*a();
00121 }
00122
00123 double dvv(double , double )
00124 {
00125 return 2.0*c();
00126 }
00127
00128 static Quadric fit(std::vector<CoordType> VV)
00129 {
00130 assert(VV.size() >= 5);
00131 Eigen::MatrixXf A(VV.size(),5);
00132 Eigen::MatrixXf b(VV.size(),1);
00133 Eigen::MatrixXf sol(VV.size(),1);
00134
00135 for(unsigned int c=0; c < VV.size(); ++c)
00136 {
00137 double u = VV[c].X();
00138 double v = VV[c].Y();
00139 double n = VV[c].Z();
00140
00141 A(c,0) = u*u;
00142 A(c,1) = u*v;
00143 A(c,2) = v*v;
00144 A(c,3) = u;
00145 A(c,4) = v;
00146
00147 b(c,0) = n;
00148 }
00149
00150 sol = ((A.transpose()*A).inverse()*A.transpose())*b;
00151 return Quadric(sol(0,0),sol(1,0),sol(2,0),sol(3,0),sol(4,0));
00152 }
00153 };
00154
00155 static CoordType project(VertexType* v, VertexType* vp)
00156 {
00157 return vp->P() - (v->N() * ((vp->P() - v->P()) * v->N()));
00158 }
00159
00160
00161 static std::vector<CoordType> computeReferenceFrames(VertexTypeP vi)
00162 {
00163 vcg::face::VFIterator<FaceType> vfi(vi);
00164
00165 int i = (vfi.I()+1)%3;
00166 VertexTypeP vp = vfi.F()->V(i);
00167
00168 CoordType x = (project(&*vi,vp) - vi->P()).Normalize();
00169
00170
00171 std::vector<CoordType> res(3);
00172
00173 res[0] = x;
00174 res[1] = (vi->N() ^ res[0]).Normalize();
00175 res[2] = (vi->N())/(vi->N()).Norm();
00176
00177 return res;
00178 }
00179
00180 static std::set<CoordType> getSecondRing(VertexTypeP v)
00181 {
00182 std::set<VertexTypeP> ris;
00183 std::set<CoordType> coords;
00184
00185 vcg::face::VFIterator<FaceType> vvi(v);
00186 for(;!vvi.End();++vvi)
00187 {
00188 vcg::face::VFIterator<FaceType> vvi2(vvi.F()->V((vvi.I()+1)%3));
00189 for(;!vvi2.End();++vvi2)
00190 {
00191 ris.insert(vvi2.F()->V((vvi2.I()+1)%3));
00192 }
00193 }
00194 typename std::set<VertexTypeP>::iterator it;
00195 for(it = ris.begin(); it != ris.end(); ++it)
00196 coords.insert((*it)->P());
00197
00198 return coords;
00199 }
00200
00201 static Quadric fitQuadric(VertexTypeP v, std::vector<CoordType>& ref)
00202 {
00203 std::set<CoordType> ring = getSecondRing(v);
00204 if (ring.size() < 5)
00205 return Quadric(1,1,1,1,1);
00206 std::vector<CoordType> points;
00207
00208 typename std::set<CoordType>::iterator b = ring.begin();
00209 typename std::set<CoordType>::iterator e = ring.end();
00210
00211 while(b != e)
00212 {
00213
00214 CoordType vTang = *b - v->P();
00215
00216 double x = vTang * ref[0];
00217 double y = vTang * ref[1];
00218 double z = vTang * ref[2];
00219 points.push_back(CoordType(x,y,z));
00220 ++b;
00221 }
00222 return Quadric::fit(points);
00223 }
00224
00225
00226 static void computeCurvature(MeshType & m)
00227 {
00228 Allocator<MeshType>::CompactVertexVector(m);
00229 tri::RequireCompactness(m);
00230 tri::RequireVFAdjacency(m);
00231
00232 vcg::tri::UpdateTopology<MeshType>::VertexFace(m);
00233
00234 vcg::tri::UpdateNormal<MeshType>::PerVertexAngleWeighted(m);
00235 vcg::tri::UpdateNormal<MeshType>::NormalizePerVertex(m);
00236
00237
00238 VertexIterator vi;
00239 for(vi = m.vert.begin(); vi!=m.vert.end(); ++vi )
00240 {
00241 std::vector<CoordType> ref = computeReferenceFrames(&*vi);
00242
00243 Quadric q = fitQuadric(&*vi,ref);
00244 double a = q.a();
00245 double b = q.b();
00246 double c = q.c();
00247 double d = q.d();
00248 double e = q.e();
00249
00250 double E = 1.0 + d*d;
00251 double F = d*e;
00252 double G = 1.0 + e*e;
00253
00254 CoordType n = CoordType(-d,-e,1.0).Normalize();
00255
00256 vi->N() = ref[0] * n[0] + ref[1] * n[1] + ref[2] * n[2];
00257
00258 double L = 2.0 * a * n.Z();
00259 double M = b * n.Z();
00260 double N = 2 * c * n.Z();
00261
00262
00263 Eigen::Matrix2d m;
00264 m << L*G - M*F, M*E-L*F, M*E-L*F, N*E-M*F;
00265 m = m / (E*G-F*F);
00266 Eigen::SelfAdjointEigenSolver<Eigen::Matrix2d> eig(m);
00267
00268 Eigen::Vector2d c_val = eig.eigenvalues();
00269 Eigen::Matrix2d c_vec = eig.eigenvectors();
00270
00271 c_val = -c_val;
00272
00273 CoordType v1, v2;
00274 v1[0] = c_vec(0,0);
00275 v1[1] = c_vec(0,1);
00276 v1[2] = 0;
00277
00278 v2[0] = c_vec(1,0);
00279 v2[1] = c_vec(1,1);
00280 v2[2] = 0;
00281
00282 v1 = v1.Normalize();
00283 v2 = v2.Normalize();
00284
00285 v1 = v1 * c_val[0];
00286 v2 = v2 * c_val[1];
00287
00288 CoordType v1global = ref[0] * v1[0] + ref[1] * v1[1] + ref[2] * v1[2];
00289 CoordType v2global = ref[0] * v2[0] + ref[1] * v2[1] + ref[2] * v2[2];
00290
00291 v1global.Normalize();
00292 v2global.Normalize();
00293
00294 if (c_val[0] > c_val[1])
00295 {
00296 (*vi).PD1().Import(v1global);
00297 (*vi).PD2().Import(v2global);
00298 (*vi).K1() = c_val[0];
00299 (*vi).K2() = c_val[1];
00300 }
00301 else
00302 {
00303 (*vi).PD1().Import(v2global);
00304 (*vi).PD2().Import(v1global);
00305 (*vi).K1() = c_val[1];
00306 (*vi).K2() = c_val[0];
00307 }
00308
00309 }
00310 }
00311
00312
00313
00314 class QuadricLocal
00315 {
00316 public:
00317
00318 QuadricLocal ()
00319 {
00320 a() = b() = c() = d() = e() = 1.0;
00321 }
00322
00323 QuadricLocal (double av, double bv, double cv, double dv, double ev)
00324 {
00325 a() = av;
00326 b() = bv;
00327 c() = cv;
00328 d() = dv;
00329 e() = ev;
00330 }
00331
00332 double& a() { return data[0];}
00333 double& b() { return data[1];}
00334 double& c() { return data[2];}
00335 double& d() { return data[3];}
00336 double& e() { return data[4];}
00337
00338 double data[5];
00339
00340 double evaluate(double u, double v)
00341 {
00342 return a()*u*u + b()*u*v + c()*v*v + d()*u + e()*v;
00343 }
00344
00345 double du(double u, double v)
00346 {
00347 return 2.0*a()*u + b()*v + d();
00348 }
00349
00350 double dv(double u, double v)
00351 {
00352 return 2.0*c()*v + b()*u + e();
00353 }
00354
00355 double duv(double , double )
00356 {
00357 return b();
00358 }
00359
00360 double duu(double , double )
00361 {
00362 return 2.0*a();
00363 }
00364
00365 double dvv(double , double )
00366 {
00367 return 2.0*c();
00368 }
00369
00370
00371 static QuadricLocal fit(std::vector<CoordType> &VV, bool svdRes, bool detCheck)
00372 {
00373 assert(VV.size() >= 5);
00374 Eigen::MatrixXd A(VV.size(),5);
00375 Eigen::MatrixXd b(VV.size(),1);
00376 Eigen::MatrixXd sol(5,1);
00377
00378 for(unsigned int c=0; c < VV.size(); ++c)
00379 {
00380 double u = VV[c].X();
00381 double v = VV[c].Y();
00382 double n = VV[c].Z();
00383
00384 A(c,0) = u*u;
00385 A(c,1) = u*v;
00386 A(c,2) = v*v;
00387 A(c,3) = u;
00388 A(c,4) = v;
00389
00390 b[c] = n;
00391 }
00392
00393
00394 static int count = 0, index = 0;
00395 double min = 0.000000000001;
00396
00397
00398
00399
00400
00401 if (detCheck && ((A.transpose()*A).determinant() < min && (A.transpose()*A).determinant() > -min))
00402 {
00403
00404
00405 printf("Quadric: unsolvable vertex %d %d\n", count, ++index);
00406
00407
00408 Eigen::JacobiSVD<Eigen::MatrixXd> svd(A);
00409 sol=svd.solve(b);
00410 return QuadricLocal(sol[0],sol[1],sol[2],sol[3],sol[4]);
00411 }
00412 count++;
00413
00414
00415 {
00416 if (svdRes)
00417 {
00418 Eigen::JacobiSVD<Eigen::MatrixXd> svd(A);
00419 sol=svd.solve(b);
00420
00421 }
00422 else
00423 sol = ((A.transpose()*A).inverse()*A.transpose())*b;
00424
00425 }
00426
00427 return QuadricLocal(sol[0],sol[1],sol[2],sol[3],sol[4]);
00428 }
00429 };
00430
00431 static void expandMaxLocal (MeshType & mesh, VertexType *v, int max, std::vector<VertexType*> *vv)
00432 {
00433 Nring<MeshType> rw = Nring<MeshType> (v, &mesh);
00434 do rw.expand (); while (rw.allV.size() < max+1);
00435 if (rw.allV[0] != v)
00436 printf ("rw.allV[0] != *v\n");
00437 vv->reserve ((size_t)max);
00438 for (int i = 1; i < max+1; i++)
00439 vv->push_back(rw.allV[i]);
00440
00441 rw.clear();
00442 }
00443
00444
00445 static void expandSphereLocal (MeshType & mesh, VertexType *v, float r, int min, std::vector<VertexType*> *vv)
00446 {
00447 Nring<MeshType> rw = Nring<MeshType> (v, &mesh);
00448
00449 bool isInside = true;
00450 while (isInside)
00451 {
00452 rw.expand();
00453 vv->reserve(rw.allV.size());
00454
00455 typename std::vector<VertexType*>::iterator b = rw.lastV.begin();
00456 typename std::vector<VertexType*>::iterator e = rw.lastV.end();
00457 isInside = false;
00458 while(b != e)
00459 {
00460 if (((*b)->P() - v->P()).Norm() < r)
00461 {
00462 vv->push_back(*b);;
00463 isInside = true;
00464 }
00465 ++b;
00466 }
00467 }
00468
00469 rw.clear();
00470
00471 if (vv->size() < min)
00472 {
00473 vv->clear();
00474 expandMaxLocal (mesh, v, min, vv);
00475 }
00476 }
00477
00478
00479 static void getAverageNormal (VertexType *vp, std::vector<VertexType*> &vv, CoordType *ppn)
00480 {
00481 *ppn = CoordType (0,0,0);
00482 for (typename std::vector<VertexType*>::iterator vpi = vv.begin(); vpi != vv.end(); ++vpi)
00483 *ppn += (*vpi)->N();
00484 *ppn += (*vp).N();
00485 *ppn /= vv.size() + 1;
00486 ppn->Normalize();
00487 }
00488
00489
00490 static void applyProjOnPlane (CoordType ppn, std::vector<VertexType*> &vin, std::vector<VertexType*> *vout)
00491 {
00492 for (typename std::vector<VertexType*>::iterator vpi = vin.begin(); vpi != vin.end(); ++vpi)
00493 if ((*vpi)->N() * ppn > 0.0f)
00494 vout->push_back (*vpi);
00495 }
00496
00497 static CoordType projectLocal(VertexType* v, VertexType* vp, CoordType ppn)
00498 {
00499 return vp->P() - (ppn * ((vp->P() - v->P()) * ppn));
00500 }
00501
00502
00503 static void computeReferenceFramesLocal (VertexType *v, CoordType ppn, std::vector<CoordType> *ref)
00504 {
00505 vcg::face::VFIterator<FaceType> vfi (v);
00506
00507 int i = (vfi.I() + 1) % 3;
00508 VertexTypeP vp = vfi.F()->V(i);
00509
00510 CoordType x = (projectLocal (v, vp, ppn) - v->P()).Normalize();
00511
00512 assert(fabs(x * ppn) < 0.1);
00513
00514 *ref = std::vector<CoordType>(3);
00515
00516 (*ref)[0] = x;
00517 (*ref)[1] = (ppn ^ (*ref)[0]).Normalize();
00518 (*ref)[2] = ppn.Normalize();
00519 }
00520
00521
00522 static void fitQuadricLocal (VertexType *v, std::vector<CoordType> ref, std::vector<VertexType*> &vv, QuadricLocal *q)
00523 {
00524 bool svdResolution = false;
00525 bool zeroDeterminantCheck = false;
00526
00527 std::vector<CoordType> points;
00528 points.reserve (vv.size());
00529
00530 typename std::vector<VertexType*>::iterator b = vv.begin();
00531 typename std::vector<VertexType*>::iterator e = vv.end();
00532
00533 while(b != e)
00534 {
00535 CoordType cp = (*b)->P();
00536
00537
00538 CoordType vTang = cp - v->P();
00539
00540 double x = vTang * ref[0];
00541 double y = vTang * ref[1];
00542 double z = vTang * ref[2];
00543 points.push_back(CoordType(x,y,z));
00544 ++b;
00545 }
00546
00547 *q = QuadricLocal::fit (points, svdResolution, zeroDeterminantCheck);
00548 }
00549
00550
00551 static void finalEigenStuff (VertexType *v, std::vector<CoordType> ref, QuadricLocal q)
00552 {
00553 double a = q.a();
00554 double b = q.b();
00555 double c = q.c();
00556 double d = q.d();
00557 double e = q.e();
00558
00559 double E = 1.0 + d*d;
00560 double F = d*e;
00561 double G = 1.0 + e*e;
00562
00563 CoordType n = CoordType(-d,-e,1.0).Normalize();
00564
00565 v->N() = ref[0] * n[0] + ref[1] * n[1] + ref[2] * n[2];
00566
00567 double L = 2.0 * a * n.Z();
00568 double M = b * n.Z();
00569 double N = 2 * c * n.Z();
00570
00571
00572 Eigen::Matrix2d m;
00573 m << L*G - M*F, M*E-L*F, M*E-L*F, N*E-M*F;
00574 m = m / (E*G-F*F);
00575 Eigen::SelfAdjointEigenSolver<Eigen::Matrix2d> eig(m);
00576
00577 Eigen::Vector2d c_val = eig.eigenvalues();
00578 Eigen::Matrix2d c_vec = eig.eigenvectors();
00579
00580 c_val = -c_val;
00581
00582 CoordType v1, v2;
00583 v1[0] = c_vec[0];
00584 v1[1] = c_vec[1];
00585 v1[2] = d * v1[0] + e * v1[1];
00586
00587 v2[0] = c_vec[2];
00588 v2[1] = c_vec[3];
00589 v2[2] = d * v2[0] + e * v2[1];
00590
00591 v1 = v1.Normalize();
00592 v2 = v2.Normalize();
00593
00594 CoordType v1global = ref[0] * v1[0] + ref[1] * v1[1] + ref[2] * v1[2];
00595 CoordType v2global = ref[0] * v2[0] + ref[1] * v2[1] + ref[2] * v2[2];
00596
00597 v1global.Normalize();
00598 v2global.Normalize();
00599
00600 v1global *= c_val[0];
00601 v2global *= c_val[1];
00602
00603 if (c_val[0] > c_val[1])
00604 {
00605 (*v).PD1() = v1global;
00606 (*v).PD2() = v2global;
00607 (*v).K1() = c_val[0];
00608 (*v).K2() = c_val[1];
00609 }
00610 else
00611 {
00612 (*v).PD1() = v2global;
00613 (*v).PD2() = v1global;
00614 (*v).K1() = c_val[1];
00615 (*v).K2() = c_val[0];
00616 }
00617
00618 }
00619
00620
00621
00622 static void updateCurvatureLocal (MeshType & mesh, float radiusSphere)
00623 {
00624 bool verbose = false;
00625 bool projectionPlaneCheck = true;
00626 int vertexesPerFit = 0;
00627
00628 int i = 0;
00629 VertexIterator vi;
00630 for(vi = mesh.vert.begin(); vi != mesh.vert.end(); ++vi, i++)
00631 {
00632 std::vector<VertexType*> vv;
00633 std::vector<VertexType*> vvtmp;
00634
00635 int count;
00636 if (verbose && !((count = (vi - mesh.vert.begin())) % 1000))
00637 printf ("vertex %d of %d\n",count,mesh.vert.size());
00638
00639
00640
00641
00642 expandSphereLocal (mesh, &*vi, radiusSphere, 5, &vv);
00643
00644 assert (vv.size() >= 5);
00645
00646 CoordType ppn;
00647
00648
00649 getAverageNormal (&*vi, vv, &ppn);
00650
00651
00652
00653 if (projectionPlaneCheck)
00654 {
00655 vvtmp.reserve (vv.size ());
00656 applyProjOnPlane (ppn, vv, &vvtmp);
00657 if (vvtmp.size() >= 5)
00658 vv = vvtmp;
00659 }
00660
00661 vvtmp.clear();
00662
00663
00664
00665
00666
00667
00668
00669
00670
00671
00672
00673
00674
00675 assert (vv.size() >= 5);
00676
00677 std::vector<CoordType> ref;
00678 computeReferenceFramesLocal (&*vi, ppn, &ref);
00679
00680
00681
00682
00683
00684
00685
00686
00687 vertexesPerFit += vv.size();
00688
00689
00690 QuadricLocal q;
00691 fitQuadricLocal (&*vi, ref, vv, &q);
00692
00693 finalEigenStuff (&*vi, ref, q);
00694
00695 }
00696
00697
00698
00699 if (verbose)
00700 printf ("average vertex num in each fit: %f\n", ((float) vertexesPerFit) / mesh.vn);
00701 }
00702
00703 };
00704
00705 }
00706 }
00707 #endif