bitquad_support.h
Go to the documentation of this file.
00001 #ifndef VCG_BITQUAD_SUPPORT
00002 #define VCG_BITQUAD_SUPPORT
00003 #include <vcg/simplex/face/jumping_pos.h>
00004 #include <vcg/simplex/face/topology.h>
00005 #include <vcg/space/planar_polygon_tessellation.h>
00006 #include <vcg/complex/algorithms/update/quality.h>
00007 
00053 // these should become a parameter in the corresponding class
00054 #define DELETE_VERTICES 1
00055 // Reason not to delete vertices:
00056 // if not vertex TwoManyfold, the vertex could still be used elsewhere...
00057 
00058 // if one, use length to determine if rotations are profitable
00059 // if zero, maximize conformal quality
00060 #define LENGTH_CRITERION 1
00061 
00062 namespace vcg{namespace tri{
00063 
00064 /* simple geometric-interpolation mono-function class used
00065 as a default template parameter to BitQuad class */
00066 template <class VertexType>
00067 class GeometricInterpolator{
00068 public:
00069   typedef typename VertexType::ScalarType ScalarType;
00070   static void Apply( const VertexType &a,  const VertexType &b, ScalarType t, VertexType &res){
00071     /*assert (&a != &b);*/
00072     res.P() = a.cP()*(1-t) + b.cP()*(t);
00073     if (a.IsB()||b.IsB()) res.SetB();
00074   }
00075 };
00076 
00077 template <
00078   // first template parameter: the tri mesh (with face-edges flagged)
00079   class _MeshType,
00080   // second template parameter: used to define interpolations between points
00081   class Interpolator = GeometricInterpolator<typename _MeshType::VertexType>
00082 >
00083 class BitQuad{
00084 public:
00085 
00086 typedef _MeshType MeshType;
00087 typedef typename MeshType::ScalarType ScalarType;
00088 typedef typename MeshType::CoordType CoordType;
00089 typedef typename MeshType::FaceType FaceType;
00090 typedef typename MeshType::FaceType* FaceTypeP;
00091 typedef typename MeshType::VertexType VertexType;
00092 typedef typename MeshType::FaceIterator FaceIterator;
00093 typedef typename MeshType::VertexIterator VertexIterator;
00094 typedef typename MeshType::VertexPointer VertexPointer;
00095 
00096 class Pos{
00097   FaceType *f;
00098   int e;
00099 public:
00100   enum{ PAIR, AROUND , NOTHING } mode;
00101   FaceType* &F(){return f;}
00102   FaceType* F() const {return f;}
00103   VertexType* V() {return f->V(e);}
00104   const VertexType* cV() const {return f->V(e);}
00105   int& E(){return e;}
00106   int E() const {return e;}
00107 
00108 
00109   Pos(){ f=NULL; e=0; mode=AROUND;}
00110 
00111   Pos(FaceType* _f, int _e){f=_f; e=_e;}
00112   Pos NextE()const {return Pos(f, (e+1)%3); }
00113   Pos PrevE(){return Pos(f, (e+2)%3); }
00114   bool IsF(){return f->IsF(e);}
00115   Pos FlipF(){return Pos(f->FFp(e), f->FFi(e)); }
00116 
00117 };
00118 
00119 
00120 
00121 static void MarkFaceF(FaceType *f){
00122   f->V(0)->SetS();
00123   f->V(1)->SetS();
00124   f->V(2)->SetS();
00125   int i=FauxIndex(f);
00126   f->FFp( i )->V2( f->FFi(i) )->SetS();
00127   f->V(0)->SetV();
00128   f->V(1)->SetV();
00129   f->V(2)->SetV();
00130   f->FFp( i )->V2( f->FFi(i) )->SetV();
00131 }
00132 
00133 
00134 template <bool verse>
00135 static bool RotateEdge(FaceType& f, int w0a, MeshType &m, Pos *affected=NULL){
00136   FaceType *fa = &f;
00137   assert(! fa->IsF(w0a) );
00138 
00139   VertexType *v0, *v1;
00140   v0= fa->V0(w0a);
00141   v1= fa->V1(w0a);
00142 
00143 //  int w1a = (w0a+1)%3;
00144   int w2a = (w0a+2)%3;
00145 
00146   FaceType *fb = fa->FFp(w0a);
00147 
00148   MarkFaceF(fa);
00149   MarkFaceF(fb);
00150 
00151   int w0b = fa->FFi(w0a);
00152 //  int w1b = (w0b+1)%3;
00153   int w2b = (w0b+2)%3;
00154 
00155   if (fa->IsF(w2a) == verse) {
00156     if (!CheckFlipDiag(*fa)) return false;
00157     FlipDiag(*fa);
00158     // hack: recover edge index, so that (f, w0a) identifies the same edge as before
00159     fa = fb->FFp(w0b);
00160     w0a = fb->FFi(w0b);
00161   }
00162 
00163   if (fb->IsF(w2b) == verse) {
00164     if (!CheckFlipDiag(*fb)) return false;
00165     FlipDiag(*fb);
00166   }
00167 
00168   if (!CheckFlipEdge(*fa,w0a)) return false;
00169   FlipEdge(*fa,w0a,m);
00170   if (affected) {
00171     affected->F() = fa;
00172     affected->E() = (FauxIndex(fa)+2)%3;
00173     affected->mode = Pos::PAIR;
00174   }
00175   return true;
00176 }
00177 
00178 /* small helper function which returns the index of the only
00179    faux index, assuming there is exactly one (asserts out otherwise)
00180 */
00181 static int FauxIndex(const FaceType* f){
00182   if (f->IsF(0)) return 0;
00183   if (f->IsF(1)) return 1;
00184   assert(f->IsF(2));
00185   return 2;
00186 }
00187 
00188 // rotates the diagonal of a quad
00189 static void FlipDiag(FaceType &f){
00190   int faux = FauxIndex(&f);
00191   FaceType* fa = &f;
00192   FaceType* fb = f.FFp(faux);
00193   vcg::face::FlipEdge(f, faux);
00194   // ripristinate faux flags
00195   fb->ClearAllF();
00196   fa->ClearAllF();
00197   for (int k=0; k<3; k++) {
00198     if (fa->FFp(k) == fb) fa->SetF(k);
00199     if (fb->FFp(k) == fa) fb->SetF(k);
00200   }
00201 }
00202 
00203 
00204 // given a vertex (i.e. a face and a wedge),
00205 // this function tells us how the totale edge length around a vertex would change
00206 // if that vertex is rotated
00207 static ScalarType EdgeLenghtVariationIfVertexRotated(const FaceType &f, int w0)
00208 {
00209   assert(!f.IsD());
00210 
00211   ScalarType
00212     before=0, // sum of quad edges (originating from v)
00213     after=0;  // sum of quad diag (orginating from v)
00214   int guard = 0;
00215 
00216   // rotate arond vertex
00217   const FaceType* pf = &f;
00218   int pi = w0;
00219   int n = 0; // vertex valency
00220   int na = 0;
00221   do {
00222     ScalarType triEdge = (pf->P0(pi) - pf->P1(pi) ).Norm();
00223     if (pf->IsF(pi)) { after += triEdge; na++;}
00224     else { before+= triEdge; n++; }
00225     if ( pf->IsF((pi+1)%3)) { after += CounterDiag( pf ).Norm(); na++; }
00226 
00227     const FaceType *t = pf;
00228     t = pf->FFp( pi );
00229     if (pf == t ) return std::numeric_limits<ScalarType>::max(); // it's a mesh border! flee!
00230     pi = pf->cFFi( pi );
00231     pi = (pi+1)%3; // FaceType::Next( pf->FFi( pi ) );
00232     pf = t;
00233     guard++;
00234     assert(guard<100);
00235   } while (pf != &f);
00236   assert (na == n);
00237   return (after-before);
00238 }
00239 
00240 // given a vertex (i.e. a face and a wedge),
00241 // this function tells us how the totale edge length around a vertex would change
00242 // if that vertex is rotated
00243 static ScalarType QuadQualityVariationIfVertexRotated(const FaceType &f, int w0)
00244 {
00245   assert(!f.IsD());
00246 
00247   ScalarType
00248     before=0, // sum of quad quality around v
00249     after=0;  // same after the collapse
00250   int guard = 0;
00251 
00252   // rotate arond vertex
00253   const FaceType* pf = &f;
00254   int pi = w0;
00255   std::vector<const VertexType *> s; // 1 star around v
00256   do {
00257     // ScalarType triEdge = (pf->P0(pi) - pf->P1(pi) ).Norm();
00258     if (!pf->IsF(pi)) {
00259       if ( pf->IsF((pi+1)%3)) {
00260         s.push_back(pf->cFFp((pi+1)%3)->V2( pf->cFFi((pi+1)%3) ));
00261       } else {
00262         s.push_back( pf->V2(pi) );
00263       }
00264 
00265       s.push_back( pf->V1(pi) );
00266     }
00267 
00268     const FaceType *t = pf;
00269     t = pf->FFp( pi );
00270     if (pf == t ) return std::numeric_limits<ScalarType>::max(); // it's a mesh border! flee!
00271     pi = pf->cFFi( pi );
00272     pi = (pi+1)%3; // FaceType::Next( pf->FFi( pi ) );
00273     pf = t;
00274     guard++;
00275     assert(guard<100);
00276   } while (pf != &f);
00277 
00278   assert(s.size()%2==0);
00279   int N = s.size();
00280   for (int i=0; i<N; i+=2) {
00281     int h = (i+N-1)%N;
00282     int j = (i  +1)%N;
00283     int k = (i  +2)%N;
00284     before+=   quadQuality( s[i]->P(),s[j]->P(),s[k]->P(),f.P(w0) );
00285     after+=quadQuality( s[h]->P(),s[i]->P(),s[j]->P(),f.P(w0) );
00286   }
00287 
00288   return (after-before);
00289 }
00290 
00291 /*
00292   const FaceType* pf = &f;
00293   int pi = wedge;
00294   int res = 0, guard=0;
00295   do {
00296     if (!pf->IsAnyF()) return false; // there's a triangle!
00297     if (!pf->IsF(pi)) res++;
00298     const FaceType *t = pf;
00299     t = pf->FFp( pi );
00300     if (pf == t ) return false;
00301     pi = pf->cFFi( pi );
00302     pi = (pi+1)%3; // FaceType::Next( pf->FFi( pi ) );
00303     pf = t;
00304     assert(guard++<100);
00305   } while (pf != &f);
00306 */
00307 
00308 // given a vertex (i.e. a face and a wedge),
00309 // this function tells us if it should be rotated or not
00310 // (currently, we should iff it is shortened)
00311 static bool TestVertexRotation(const FaceType &f, int w0)
00312 {
00313   assert(!f.IsD());
00314 
00315 #if (LENGTH_CRITERION)
00316   // rotate vertex IFF this way edges become shorter:
00317   return EdgeLenghtVariationIfVertexRotated(f,w0)<0;
00318 #else
00319   // rotate vertex IFF overall Quality increase
00320 #endif
00321   return QuadQualityVariationIfVertexRotated(f,w0)<0;
00322 }
00323 
00324 
00325 static bool RotateVertex(FaceType &f, int w0, MeshType &/*m*/, Pos *affected=NULL)
00326 {
00327 
00328 //  int guard = 0;
00329 
00330   FaceType* pf = &f;
00331   int pi = w0;
00332 
00333   if (pf->IsF((pi+2) % 3)) {
00334       pi = (pi+2)%3;
00335       // do one step back
00336       int tmp = pf->FFi(pi); pf = pf->FFp(pi); pi = tmp;  // flipF
00337   }
00338 
00339   const FaceType* stopA = pf;
00340   const FaceType* stopB = pf->FFp(FauxIndex(pf));
00341 
00342   // rotate around vertex, flipping diagonals if necessary,
00343   do {
00344     bool mustFlip;
00345     if (pf->IsF(pi)) {
00346       // if next edge is faux, move on other side of quad
00347       int tmp = (pf->FFi(pi)+1)%3; pf = pf->FFp(pi); pi = tmp;  // flipF
00348       mustFlip = false;
00349     }
00350     else {
00351       mustFlip = true;
00352     }
00353 
00354     FaceType *lastF = pf;
00355 
00356     int tmp = (pf->FFi(pi)+1)%3; pf = pf->FFp(pi); pi = tmp;  // flipF
00357 
00358     if (mustFlip) {
00359       if (!CheckFlipDiag(*lastF)) return false; // cannot flip??
00360       FlipDiag(*lastF);
00361     }
00362     MarkFaceF(pf);
00363   } while (pf != stopA && pf!= stopB);
00364 
00365   // last pass: rotate arund vertex again, changing faux status
00366   stopA=pf;
00367   do {
00368     int j = pi;
00369     if (pf->IsF(j))
00370       { pf->ClearF(j); IncreaseValency(pf->V1(j));  }
00371     else
00372       { pf->SetF(j); DecreaseValencySimple(pf->V1(j),1); }
00373 
00374     j = (j+2)%3;
00375     if (pf->IsF(j)) pf->ClearF(j); else pf->SetF(j);
00376     int tmp = (pf->FFi(pi)+1)%3; pf = pf->FFp(pi); pi = tmp;  // flipF flipV
00377   } while (pf != stopA );
00378 
00379   if (affected) {
00380     affected->F() = pf;
00381     affected->E()=pi;
00382   }
00383   return true;
00384 }
00385 
00386 
00387 
00388 
00389 
00390 // flips the faux edge of a quad
00391 static void FlipEdge(FaceType &f, int k, MeshType &m){
00392   assert(!f.IsF(k));
00393   FaceType* fa = &f;
00394   FaceType* fb = f.FFp(k);
00395   assert(fa!=fb); // else, rotating a border edge
00396 
00397   // backup prev other-quads-halves
00398   FaceType* fa2 = fa->FFp( FauxIndex(fa) );
00399   FaceType* fb2 = fb->FFp( FauxIndex(fb) );
00400 
00401   IncreaseValency( fa->V2(k) );
00402   IncreaseValency( fb->V2(f.FFi(k)) );
00403   //DecreaseValency( fa->V0(k) );
00404   //DecreaseValency( fa->V1(k) );
00405   DecreaseValency(fa, k ,m);
00406   DecreaseValency(fa,(k+1)%3,m );
00407 
00408 
00409   vcg::face::FlipEdge(*fa, k);
00410 
00411   // ripristinate faux flags
00412   fb->ClearAllF();
00413   fa->ClearAllF();
00414   for (int k=0; k<3; k++) {
00415     //if (fa->FFp(k) == fa2) fa->SetF(k);
00416     //if (fb->FFp(k) == fb2) fb->SetF(k);
00417     if (fa->FFp(k)->IsF( fa->FFi(k) )) fa->SetF(k);
00418     if (fb->FFp(k)->IsF( fb->FFi(k) )) fb->SetF(k);
00419   }
00420 
00421 }
00422 
00423 // check if a quad diagonal can be topologically flipped
00424 static bool CheckFlipDiag(FaceType &f){
00425   return (vcg::face::CheckFlipEdge(f, FauxIndex(&f) ) );
00426 }
00427 
00428 // given a face (part of a quad), returns its diagonal
00429 static CoordType Diag(const FaceType* f){
00430   int i = FauxIndex(f);
00431   return f->P1( i ) - f->P0( i );
00432 }
00433 
00434 
00435 // given a face (part of a quad), returns other diagonal
00436 static CoordType CounterDiag(const FaceType* f){
00437   int i = FauxIndex(f);
00438   return f->cP2( i ) - f->cFFp( i )->cP2(f->cFFi(i) ) ;
00439 }
00440 
00441 /* helper function:
00442    collapses a single face along its faux edge.
00443    Updates FF adj of other edges. */
00444 static void _CollapseDiagHalf(FaceType &f, int faux, MeshType& /*m*/)
00445 {
00446   int faux1 = (faux+1)%3;
00447   int faux2 = (faux+2)%3;
00448 
00449   FaceType* fA = f.FFp( faux1 );
00450   FaceType* fB = f.FFp( faux2 );
00451 
00452   MarkFaceF(fA);
00453   MarkFaceF(fB);
00454 
00455   int iA = f.FFi( faux1 );
00456   int iB = f.FFi( faux2 );
00457 
00458   if (fA==&f && fB==&f) {
00459     // both non-faux edges are borders: tri-face disappears, just remove the vertex
00460     //if (DELETE_VERTICES)
00461     //if (GetValency(f.V(faux2))==0) Allocator<MeshType>::DeleteVertex(m,*(f.V(faux2)));
00462   } else {
00463     if (fA==&f) {
00464       fB->FFp(iB) = fB;  fB->FFi(iB) = iB;
00465     } else {
00466       fB->FFp(iB) = fA;  fB->FFi(iB) = iA;
00467     }
00468 
00469     if (fB==&f) {
00470       fA->FFp(iA) = fA;  fA->FFi(iA) = iA;
00471     } else {
00472       fA->FFp(iA) = fB;  fA->FFi(iA) = iB;
00473     }
00474   }
00475 
00476 
00477   //DecreaseValency(&f,faux2,m); // update valency
00478   //Allocator<MeshType>::DeleteFace(m,f);
00479 
00480 }
00481 
00482 static void RemoveDoublet(FaceType &f, int wedge, MeshType& m, Pos* affected=NULL){
00483   if (f.IsF((wedge+1)%3) ) {
00484     VertexType *v = f.V(wedge);
00485     FlipDiag(f);
00486     // quick hack: recover wedge index after flip
00487     if (f.V(0)==v) wedge = 0;
00488     else if (f.V(1)==v) wedge = 1;
00489     else {
00490       assert(f.V(2)==v);
00491       wedge = 2;
00492     }
00493   }
00494   ScalarType k=(f.IsF(wedge))?1:0;
00495   CollapseDiag(f, k, m, affected);
00496   VertexType *v = f.V(wedge);
00497 }
00498 
00499 static void RemoveSinglet(FaceType &f, int wedge, MeshType& m, Pos* affected=NULL){
00500   if (affected) affected->mode = Pos::NOTHING; // singlets leave nothing to update behind
00501 
00502   if (f.V(wedge)->IsB()) return; // hack: lets detect
00503 
00504   FaceType *fa, *fb; // these will die
00505   FaceType *fc, *fd; // their former neight
00506   fa = & f;
00507   fb = fa->FFp(wedge);
00508   int wa0 = wedge;
00509   int wa1 = (wa0+1)%3 ;
00510   int wa2 = (wa0+2)%3 ;
00511   int wb0 = (fa->FFi(wa0)+1)%3;
00512   int wb1 = (wb0+1)%3 ;
00513 //  int wb2 = (wb0+2)%3 ;
00514   assert (fb == fa->FFp( wa2 ) ); // otherwise, not a singlet
00515 
00516   // valency decrease
00517   DecreaseValency(fa, wa1, m);
00518   DecreaseValency(fa, wa2, m);
00519   if (fa->IsF(wa0)) {
00520     DecreaseValency(fa,wa2,m); // double decrease of valency on wa2
00521   } else {
00522     DecreaseValency(fa,wa1,m); // double decrease of valency on wa1
00523   }
00524 
00525   // no need to MarkFaceF !
00526 
00527   fc = fa->FFp(wa1);
00528   fd = fb->FFp(wb1);
00529   int wc = fa->FFi(wa1);
00530   int wd = fb->FFi(wb1);
00531   fc->FFp(wc) = fd;
00532   fc->FFi(wc) = wd;
00533   fd->FFp(wd) = fc;
00534   fd->FFi(wd) = wc;
00535   // faux status of survivors: unchanged
00536   assert( ! ( fc->IsF( wc) ) );
00537   assert( ! ( fd->IsF( wd) ) );
00538 
00539   Allocator<MeshType>::DeleteFace( m,*fa );
00540   Allocator<MeshType>::DeleteFace( m,*fb );
00541 
00542   DecreaseValency(fa,wedge,m );
00543   //if (DELETE_VERTICES)
00544   //if (GetValency(fa->V(wedge))==0) Allocator<MeshType>::DeleteVertex( m,*fa->V(wedge) );
00545 }
00546 
00547 
00548 static bool TestAndRemoveDoublet(FaceType &f, int wedge, MeshType& m){
00549   if (IsDoublet(f,wedge)) {
00550      RemoveDoublet(f,wedge,m);
00551      return true;
00552   }
00553   return false;
00554 }
00555 
00556 static bool TestAndRemoveSinglet(FaceType &f, int wedge, MeshType& m){
00557   if (IsSinglet(f,wedge)) {
00558      RemoveSinglet(f,wedge,m);
00559      return true;
00560   }
00561   return false;
00562 }
00563 
00564 // given a face and a wedge, counts its valency in terms of quads (and triangles)
00565 // uses only FF, assumes twomanyfold
00566 // returns -1 if border
00567 static int CountBitPolygonInternalValency(const FaceType& f, int wedge){
00568   const FaceType* pf = &f;
00569   int pi = wedge;
00570   int res = 0;
00571   do {
00572     if (!pf->IsF(pi)) res++;
00573     const FaceType *t = pf;
00574     t = pf->FFp( pi );
00575     if (pf == t ) return -1;
00576     pi = (pi+1)%3; // FaceType::Next( pf->FFi( pi ) );
00577     pf = t;
00578   } while (pf != &f);
00579   return res;
00580 }
00581 
00582 // given a face and a wedge, returns if it host a doubet
00583 // assumes tri and quad only. uses FF topology only.
00584 static bool IsDoubletFF(const FaceType& f, int wedge){
00585   const FaceType* pf = &f;
00586   int pi = wedge;
00587   int res = 0, guard=0;
00588   do {
00589     if (!pf->IsAnyF()) return false; // there's a triangle!
00590     if (!pf->IsF(pi)) res++;
00591     const FaceType *t = pf;
00592     t = pf->FFp( pi );
00593     if (pf == t ) return false;
00594     pi = pf->cFFi( pi );
00595     pi = (pi+1)%3; // FaceType::Next( pf->FFi( pi ) );
00596     pf = t;
00597     guard++;
00598     assert(guard<100);
00599   } while (pf != &f);
00600   return (res == 2);
00601 }
00602 
00603 // version that uses vertex valency
00604 static bool IsDoublet(const FaceType& f, int wedge){
00605   return (GetValency( f.V(wedge)) == 2) && (!f.V(wedge)->IsB() ) ;
00606 }
00607 
00608 static bool IsDoubletOrSinglet(const FaceType& f, int wedge){
00609   return (GetValency( f.V(wedge)) <= 2) && (!f.V(wedge)->IsB() ) ;
00610 }
00611 
00612 static bool RemoveDoubletOrSinglet(FaceType& f, int wedge, MeshType& m, Pos* affected=NULL){
00613  if (GetValency( f.V(wedge)) == 2) { RemoveDoublet(f,wedge,m,affected) ; return true; }
00614  assert (GetValency( f.V(wedge)) == 1) ;
00615  RemoveSinglet(f,wedge,m,affected) ;
00616  return true;
00617 }
00618 
00619 // given a face and a wedge, returns if it host a singlets
00620 // assumes tri and quad only. uses FF topology only.
00621 static bool IsSingletFF(const FaceType& f, int wedge){
00622   const FaceType* pf = &f;
00623   int pi = wedge;
00624   int res = 0, guard=0;
00625   do {
00626     if (!pf->IsAnyF()) return false; // there's a triangle!
00627     if (!pf->IsF(pi)) res++;
00628     const FaceType *t = pf;
00629     t = pf->FFp( pi );
00630     if (pf == t ) return false;
00631     pi = pf->cFFi( pi );
00632     pi = (pi+1)%3; // FaceType::Next( pf->FFi( pi ) );
00633     pf = t;
00634     guard++;
00635     assert(guard<100);
00636   } while (pf != &f);
00637   return (res == 1);
00638 }
00639 
00640 // version that uses vertex valency
00641 static bool IsSinglet(const FaceType& f, int wedge){
00642   return (GetValency( f.cV(wedge) ) == 1) && (!f.cV(wedge)->IsB() ) ;
00643 }
00644 
00645 static bool CollapseEdgeDirect(FaceType &f, int w0, MeshType& m){
00646   FaceType * f0 = &f;
00647 
00648   assert( !f0->IsF(w0) );
00649 
00650   VertexType *v0, *v1;
00651   v0 = f0->V0(w0);
00652   v1 = f0->V1(w0);
00653 
00654   if (!RotateVertex(*f0,w0,m)) return false;
00655 
00656   // quick hack: recover original wedge
00657   if      (f0->V(0) == v0) w0 = 0;
00658   else if (f0->V(1) == v0) w0 = 1;
00659   else if (f0->V(2) == v0) w0 = 2;
00660   else assert(0);
00661 
00662   assert( f0->V1(w0) == v1 );
00663   assert( f0->IsF(w0) );
00664 
00665   return CollapseDiag(*f0,PosOnDiag(*f0,false), m);
00666 }
00667 
00668 // collapses an edge. Optional output pos can be iterated around to find affected faces
00669 static bool CollapseEdge(FaceType &f, int w0, MeshType& m, Pos *affected=NULL){
00670   FaceTypeP f0 = &f;
00671   assert(!f0->IsF(w0)); // don't use this method to collapse diag.
00672 
00673   if (IsDoubletOrSinglet(f,w0)) return false; //{ RemoveDoubletOrSinglet(f,w0,m, affected); return true;}
00674   if (IsDoubletOrSinglet(f,(w0+1)%3)) return false; //{ RemoveDoubletOrSinglet(f,(w0+1)%3,m, affected); return true;}
00675 
00676   if (affected) {
00677     int w1 = 3-w0-FauxIndex(f0); // the edge whihc is not the collapsed one nor the faux
00678     affected->F() = f0->FFp(w1);
00679     affected->E() = (f0->FFi(w1)+2+w1-FauxIndex(f0))%3;
00680   }
00681 
00682   FaceTypeP f1 = f0->FFp(w0);
00683   int w1 = f0->FFi(w0);
00684 
00685   assert(f0!=f1); // can't collapse border edges!
00686 
00687   // choose: rotate around V0 or around V1?
00688   if (
00689     EdgeLenghtVariationIfVertexRotated(*f0,w0)
00690     <
00691     EdgeLenghtVariationIfVertexRotated(*f1,w1)
00692   )    return CollapseEdgeDirect(*f0,w0,m);
00693   else return CollapseEdgeDirect(*f1,w1,m);
00694 }
00695 
00696 
00697 
00704 static bool CollapseCounterDiag(FaceType &f, ScalarType interpol, MeshType& m, Pos* affected=NULL){
00705   if (!CheckFlipDiag(f)) return false;
00706   FlipDiag(f);
00707   return CollapseDiag(f,interpol,m,affected);
00708 }
00709 
00710 // rotates around vertex
00711 class Iterator{
00712 private:
00713   typedef typename face::Pos<FaceType> FPos;
00714   Pos  start, cur;
00715   bool over;
00716 public:
00717   Iterator(Pos& pos){
00718     if (pos.mode==Pos::NOTHING) {over = true; return; }
00719     start = pos; //FPos(pos.F(), pos.E());
00720     if (start.F()->IsD()) { over = true; return;}
00721     assert(!start.F()->IsD());
00722     if (pos.mode==Pos::AROUND) {
00723       if (start.F()->IsF((start.E()+2)%3))
00724       {
00725           int i = start.F()->FFi( start.E() );
00726             start.F() = start.F()->FFp( start.E() );
00727             start.E() = (i+1)%3;
00728       }
00729     }
00730       cur=start;
00731     over = false;
00732   }
00733   bool End() const {
00734     return over;
00735   }
00736   void operator ++ () {
00737     if (start.mode==Pos::PAIR)  {
00738       if (cur.F()!=start.F()) over=true;
00739       int i = (cur.E()+2)%3;
00740       cur.E() = (cur.F()->FFi( i )+1)%3;
00741       cur.F() = cur.F()->FFp( i );
00742     } else {
00743       if (cur.F()->IsF(cur.E())) {
00744         // jump over faux diag
00745         int i = cur.F()->FFi( cur.E() );
00746         cur.F() = cur.F()->FFp( cur.E() );
00747         cur.E() = (i+1)%3;
00748       }
00749       // jump over real edge
00750       FaceType *f =cur.F()->FFp( cur.E() );
00751       if (f==cur.F()) over=true; // border found
00752       cur.E() = (cur.F()->FFi( cur.E() ) +1 )%3;
00753       cur.F() = f;
00754       if (cur.F()==start.F()) over=true;
00755     }
00756   }
00757 
00758   Pos GetPos(){
00759     return cur;
00760   }
00761 };
00762 
00763 static bool CollapseDiag(FaceType &f, ScalarType interpol, MeshType& m, Pos* affected=NULL){
00764 
00765   FaceType* fa = &f; // fa lives
00766   int fauxa = FauxIndex(fa);
00767 
00768   //if (IsDoubletOrSinglet(f,fauxa)) { RemoveDoubletOrSinglet(f,fauxa,m, affected); return true;}
00769 //  if (IsDoubletOrSinglet(f,(fauxa+2)%3)) { RemoveDoubletOrSinglet(f,(fauxa+2)%3,m, affected); return true;}
00770   if (IsDoubletOrSinglet(f,(fauxa+2)%3)) return false;
00771   if (IsDoubletOrSinglet(*(f.FFp(fauxa)),(f.FFi(fauxa)+2)%3)) return false;
00772 
00773   if (affected) {
00774     int w1 = (fauxa+2)%3; // any edge but not the faux
00775     affected->F() = fa->FFp(w1);
00776     affected->E() = fa->FFi(w1);
00777     if (affected->F() == fa){
00778       int w1 = (fauxa+1)%3; // any edge but not the faux
00779       affected->F() = fa->FFp(w1);
00780       affected->E() = (fa->FFi(w1)+2)%3;
00781     }
00782   }
00783 
00784   FaceType* fb = fa->FFp(fauxa);  // fb dies
00785   assert (fb!=fa); // otherwise, its a singlet
00786   int fauxb = FauxIndex(fb);
00787 
00788   VertexType* va = fa->V(fauxa); // va lives
00789   VertexType* vb = fb->V(fauxb); // vb dies
00790 
00791   Interpolator::Apply( *(f.V0(fauxa)), *(f.V1(fauxa)), interpol, *va);
00792 
00793   bool border = false;
00794   int val =0; // number of faces around vb, which dies
00795 
00796   // update FV...
00797 
00798   // rotate around vb, (same-sense-as-face)-wise
00799   int pi = fauxb;
00800   FaceType* pf = fb; /* pf, pi could be put in a Pos<FaceType> p(pb, fauxb) */
00801      do {
00802     //pf->V(pi) = va;
00803     if (((pf->V2(pi) == va)||(pf->V1(pi) == va))
00804             &&(pf!=fa)&&(pf!=fb))
00805             return false;
00806     pi=(pi+2)%3;
00807     FaceType *t = pf->FFp(pi);
00808     if (t==pf) { border= true; break; }
00809     pi = pf->FFi(pi);
00810     pf = t;
00811   } while ((pf!=fb));
00812 
00813     pi = fauxb;
00814     pf = fb;
00815 
00816   do {
00817     pf->V(pi) = va;
00818 
00819     pi=(pi+2)%3;
00820     FaceType *t = pf->FFp(pi);
00821     if (t==pf) { border= true; break; }
00822     if (!pf->IsF(pi)) val++;
00823     pi = pf->FFi(pi);
00824     pf = t;
00825   } while (pf!=fb);
00826 
00827   // of found a border, also rotate around vb, (counter-sense-as-face)-wise
00828   if (border) {
00829     val++;
00830     int pi = fauxa;
00831     FaceType* pf = fa; /* pf, pi could be a Pos<FaceType> p(pf, pi) */
00832     do {
00833       pi=(pi+1)%3;
00834       pf->V(pi) = va;
00835       FaceType *t = pf->FFp(pi);
00836       if (t==pf) break;
00837       if (!pf->IsF(pi)) val++;
00838       pi = pf->FFi(pi);
00839       pf = t;
00840     } while (pf!=fb);
00841   }
00842 
00843   // update FF, delete faces
00844   _CollapseDiagHalf(*fb, fauxb, m);
00845   _CollapseDiagHalf(*fa, fauxa, m);
00846 
00847   SetValency(va, GetValency(va)+val-2);
00848   DecreaseValency(fb,(fauxb+2)%3,m); // update valency
00849   DecreaseValency(fa,(fauxa+2)%3,m); // update valency
00850   Allocator<MeshType>::DeleteFace(m,*fa);
00851   Allocator<MeshType>::DeleteFace(m,*fb);
00852 
00853   //assert(val == GetValency(vb));
00854 
00855 
00856   DecreaseValencyNoSingletTest(vb, val, m);
00857   // note: don't directly kill vb. In non-twomanifold, it could still be referecned
00858   // but: don't hunt for doublets either.
00859 
00860   assert(GetValency(vb)!=1 || vb->IsB());
00861   // if this asserts, you are in trouble.
00862   // It means  that the vertex that was supposed to die is still attached
00863   // somewhere else (non-twomanifold)
00864   // BUT in its other attachments it is a singlet, and that singlet cannot be
00865   // found now (would require VF)
00866 
00867 
00868   return true;
00869 }
00870 
00871 
00872 
00873 
00874 // helper function: find a good position on a diag to collapse a point
00875 // currently, it is point in the middle,
00876 //    unless a mixed border-non border edge is collapsed, then it is an exreme
00877 static ScalarType PosOnDiag(const FaceType& f, bool counterDiag){
00878   bool b0, b1, b2, b3; // which side of the quads are border
00879 
00880   const FaceType* fa=&f;
00881   int ia = FauxIndex(fa);
00882   const FaceType* fb=fa->cFFp(ia);
00883   int ib = fa->cFFi(ia);
00884 
00885   b0 = fa->FFp((ia+1)%3) == fa;
00886   b1 = fa->FFp((ia+2)%3) == fa;
00887   b2 = fb->FFp((ib+1)%3) == fb;
00888   b3 = fb->FFp((ib+2)%3) == fb;
00889 
00890   if (counterDiag) {
00891     if (  (b0||b1) && !(b2||b3) ) return 1;
00892     if ( !(b0||b1) &&  (b2||b3) ) return 0;
00893   } else {
00894     if (  (b1||b2) && !(b3||b0) ) return 0;
00895     if ( !(b1||b2) &&  (b3||b0) ) return 1;
00896   }
00897   //if (f->FF( FauxIndex(f) )->IsB(
00898   return 0.5f;
00899 }
00900 
00901 // trick! hide valency in flags
00902 typedef enum { VALENCY_FLAGS = 24 } ___; // this bit and the 4 successive one are devoted to store valency
00903 
00904 static void SetValency(VertexType *v, int n){
00905   //v->Q() = n;
00906   assert(n>=0 && n<=255);
00907   v->Flags()&= ~(255<<VALENCY_FLAGS);
00908   v->Flags()|= n<<VALENCY_FLAGS;
00909 }
00910 
00911 static int GetValency(const VertexType *v){
00912   //return (int)(v->cQ());
00913   return ( v->cFlags() >> (VALENCY_FLAGS) ) & 255;
00914 }
00915 
00916 static void IncreaseValency(VertexType *v, int dv=1){
00917 #ifdef NDEBUG
00918   v->Flags() += dv<<VALENCY_FLAGS;
00919 #else
00920   SetValency( v, GetValency(v)+dv );
00921 #endif
00922 }
00923 
00924 /*
00925 static void DecreaseValency(VertexType *v, int dv=1){
00926 #ifdef NDEBUG
00927   v->Flags() -= dv<<VALENCY_FLAGS;
00928 #else
00929   SetValency( v, GetValency(v)-dv );
00930 #endif
00931 }
00932 */
00933 
00934 // decrease valency, kills singlets on sight, remove unreferenced vertices too...
00935 static void DecreaseValency(FaceType *f, int wedge, MeshType &m){
00936   VertexType *v = f->V(wedge);
00937   int val = GetValency(v)-1;
00938   SetValency( v, val );
00939   if (val==0) Allocator<MeshType>::DeleteVertex(m,*v);
00940   if (val==1) // singlet!
00941     RemoveSinglet(*f,wedge,m); // this could be recursive...
00942 }
00943 
00944 // decrease valency, remove unreferenced vertices too, but don't check for singlets...
00945 static void DecreaseValencyNoSingletTest(VertexType *v, int dv,  MeshType &m){
00946   int val = GetValency(v)-dv;
00947   SetValency( v, val );
00948   if (DELETE_VERTICES)
00949   if (val==0) Allocator<MeshType>::DeleteVertex(m,*v);
00950 }
00951 
00952 static void DecreaseValencySimple(VertexType *v, int dv){
00953   int val = GetValency(v)-dv;
00954   SetValency( v, val );
00955 }
00956 
00957 static void UpdateValencyInFlags(MeshType& m){
00958   for (VertexIterator vi = m.vert.begin();  vi!=m.vert.end(); vi++) if (!vi->IsD()) {
00959     SetValency(&*vi,0);
00960   }
00961   for (FaceIterator fi = m.face.begin();  fi!=m.face.end(); fi++) if (!fi->IsD()) {
00962      for (int w=0; w<3; w++)
00963      if (!fi->IsF(w))
00964        IncreaseValency( fi->V(w));
00965   }
00966 }
00967 
00968 static void UpdateValencyInQuality(MeshType& m){
00969   tri::UpdateQuality<MeshType>::VertexConstant(m,0);
00970 
00971   for (FaceIterator fi = m.face.begin();  fi!=m.face.end(); fi++) if (!fi->IsD()) {
00972      for (int w=0; w<3; w++)
00973          fi->V(w)->Q() += (fi->IsF(w)||fi->IsF((w+2)%3) )? 0.5f:1;
00974   }
00975 }
00976 
00977 static bool HasConsistentValencyFlag(MeshType &m) {
00978   UpdateValencyInQuality(m);
00979   bool isok=true;
00980   for (FaceIterator fi = m.face.begin();  fi!=m.face.end(); fi++) if (!fi->IsD()) {
00981     for (int k=0; k<3; k++)
00982       if (GetValency(fi->V(k))!=fi->V(k)->Q()){
00983         MarkFaceF(&*fi);
00984         isok=false;
00985       }
00986   }
00987   return isok;
00988 }
00989 
00990 // helper function:
00991 // returns quality of a given (potential) quad
00992 static ScalarType quadQuality(FaceType *f, int edgeInd){
00993 
00994   CoordType
00995     a = f->V0(edgeInd)->P(),
00996     b = f->FFp(edgeInd)->V2( f->FFi(edgeInd) )->P(),
00997     c = f->V1(edgeInd)->P(),
00998     d = f->V2(edgeInd)->P();
00999 
01000   return quadQuality(a,b,c,d);
01001 }
01002 
01012 static int TestEdgeRotation(const FaceType &f, int w0, ScalarType *gain=NULL)
01013 {
01014   const FaceType *fa = &f;
01015   assert(! fa->IsF(w0) );
01016   ScalarType q0,q1,q2;
01017   CoordType v0,v1,v2,v3,v4,v5;
01018   int w1 = (w0+1)%3;
01019   int w2 = (w0+2)%3;
01020 
01021   v0 = fa->P(w0);
01022   v3 = fa->P(w1);
01023 
01024   if (fa->IsF(w2) ) {
01025     v1 = fa->cFFp(w2)->V2( fa->cFFi(w2) )->P();
01026     v2 = fa->P(w2);
01027   } else {
01028     v1 = fa->P(w2);
01029     v2 = fa->cFFp(w1)->V2( fa->cFFi(w1) )->P();
01030   }
01031 
01032   const FaceType *fb = fa->cFFp(w0);
01033   w0 = fa->cFFi(w0);
01034 
01035   w1 = (w0+1)%3;
01036   w2 = (w0+2)%3;
01037   if (fb->IsF(w2) ) {
01038     v4 = fb->cFFp(w2)->V2( fb->cFFi(w2) )->P();
01039     v5 = fb->P(w2);
01040   } else {
01041     v4 = fb->P(w2);
01042     v5 = fb->cFFp(w1)->V2( fb->cFFi(w1) )->P();
01043   }
01044 
01045 
01046 #if (!LENGTH_CRITERION)
01047   //  max overall CONFORMAL quality criterion:
01048   q0 = quadQuality(v0,v1,v2,v3) +  quadQuality(v3,v4,v5,v0); // keep as is?
01049   q1 = quadQuality(v1,v2,v3,v4) +  quadQuality(v4,v5,v0,v1); // rotate CW?
01050   q2 = quadQuality(v5,v0,v1,v2) +  quadQuality(v2,v3,v4,v5); // rotate CCW?
01051 
01052   if (q0>=q1 && q0>=q2) return 0;
01053   if (q1>=q2) return 1;
01054 
01055 #else
01056   // min distance (shortcut criterion)
01057   q0 = (v0 - v3).SquaredNorm();
01058   q1 = (v1 - v4).SquaredNorm();
01059   q2 = (v5 - v2).SquaredNorm();
01060 
01061   if (q0<=q1 && q0<=q2) return 0; // there's no rotation shortening this edge
01062 
01063   //static int stop=0;
01064   //static int go=0;
01065   //if ((stop+go)%100==99) printf("Stop: %4.1f%%\n",(stop*100.0/(stop+go)) );
01066 
01067   if (q1<=q2) {
01068     if (gain) *gain = sqrt(q1)-sqrt(q0);
01069     // test: two diagonals should become shorter (the other two reamin the same)
01070     if (
01071       (v0-v2).SquaredNorm() < (v4-v2).SquaredNorm() ||
01072       (v3-v5).SquaredNorm() < (v1-v5).SquaredNorm()
01073     ) {
01074       //stop++;
01075       return 0;
01076     }
01077     //go++;
01078     return 1;
01079   }
01080 
01081   {
01082     if (gain) *gain = sqrt(q2)-sqrt(q0);
01083     // diagonal test, as above:
01084     if (
01085       (v0-v4).SquaredNorm() < (v2-v4).SquaredNorm() ||
01086       (v3-v1).SquaredNorm() < (v5-v1).SquaredNorm()
01087     ) {
01088       //stop++;
01089       return 0;
01090     }
01091     //go++;
01092     return -1;
01093   }
01094 #endif
01095 }
01096 
01097 private:
01098 
01099 // helper function:
01100 // returns quality of a quad formed by points a,b,c,d
01101 // quality is computed as "how squared angles are"
01102 static ScalarType quadQuality(const CoordType &a, const CoordType &b, const CoordType &c, const CoordType &d){
01103   ScalarType score = 0;
01104   score += 1 - math::Abs( Cos( a,b,c) );
01105   score += 1 - math::Abs( Cos( b,c,d) );
01106   score += 1 - math::Abs( Cos( c,d,a) );
01107   score += 1 - math::Abs( Cos( d,a,b) );
01108   return score / 4;
01109 }
01110 
01111 
01112 
01113 
01114 private:
01115 
01116 // helper function:
01117 // cos of angle abc. This should probably go elsewhere
01118 static ScalarType Cos(const CoordType &a, const CoordType &b, const CoordType &c )
01119 {
01120   CoordType
01121     e0 = b - a,
01122     e1 = b - c;
01123   ScalarType d =  (e0.Norm()*e1.Norm());
01124   if (d==0) return 0.0;
01125   return (e0*e1)/d;
01126 }
01127 public:
01135 static void QuadTriangulate(std::vector<VertexPointer> &q)
01136 {
01137   typedef typename std::set<std::pair<VertexPointer,VertexPointer> > diagSetType;
01138   static diagSetType diagSet; // the set of already created diagonals
01139   if(q.size()!=4)
01140   {
01141     diagSet.clear();
01142     return;
01143   }
01144   const CoordType &P0=q[0]->cP();
01145   const CoordType &P1=q[1]->cP();
01146   const CoordType &P2=q[2]->cP();
01147   const CoordType &P3=q[3]->cP();
01148 
01149   CoordType N00 = Normal(P0,P1,P2);
01150   CoordType N01 = Normal(P0,P2,P3);
01151   CoordType N10 = Normal(P1,P2,P3);
01152   CoordType N11 = Normal(P1,P3,P0);
01153 
01154   ScalarType Angle0Rad=Angle(N00,N01);
01155   ScalarType Angle1Rad=Angle(N10,N11);
01156 
01157   // QualityRadii is inradius/circumradius; bad when close to zero.
01158   // swap diagonal if the worst triangle improve.
01159   bool qualityImprove = std::min<ScalarType>(QualityRadii(P0,P1,P2),QualityRadii(P0,P2,P3)) < std::min<ScalarType>(QualityRadii(P1,P2,P3),QualityRadii(P1,P3,P0));
01160   bool swapCauseFlip = (Angle1Rad > M_PI/2.0) && (Angle0Rad <M_PI/2.0);
01161 
01162   if ( qualityImprove && ! swapCauseFlip)
01163          std::rotate(q.begin(), q.begin()+1, q.end());
01164 
01165   std::pair<typename diagSetType::iterator,bool> res;
01166   if(q[0]<q[2]) res= diagSet.insert(std::make_pair(q[0],q[2]));
01167   else res= diagSet.insert(std::make_pair(q[2],q[0]));
01168 
01169   if(!res.second) // res.second is false if an element with the same value existed; in that case rotate again!
01170     std::rotate(q.begin(), q.begin()+1, q.end());
01171 }
01172 };
01173 }} // end namespace vcg::tri
01174 
01175 #endif


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