clean.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 __VCGLIB_CLEAN
00025 #define __VCGLIB_CLEAN
00026 
00027 // VCG headers
00028 #include <vcg/complex/complex.h>
00029 #include <vcg/simplex/face/pos.h>
00030 #include <vcg/simplex/face/topology.h>
00031 #include <vcg/simplex/edge/topology.h>
00032 #include <vcg/complex/algorithms/closest.h>
00033 #include <vcg/space/index/grid_static_ptr.h>
00034 #include <vcg/space/index/spatial_hashing.h>
00035 #include <vcg/complex/algorithms/update/selection.h>
00036 #include <vcg/complex/algorithms/update/flag.h>
00037 #include <vcg/complex/algorithms/update/normal.h>
00038 #include <vcg/complex/algorithms/update/topology.h>
00039 #include <vcg/space/triangle3.h>
00040 
00041 namespace vcg {
00042 namespace tri{
00043 
00044 template <class ConnectedMeshType>
00045 class ConnectedComponentIterator
00046 {
00047 public:
00048   typedef ConnectedMeshType MeshType;
00049   typedef typename MeshType::VertexType     VertexType;
00050   typedef typename MeshType::VertexPointer  VertexPointer;
00051   typedef typename MeshType::VertexIterator VertexIterator;
00052   typedef typename MeshType::ScalarType     ScalarType;
00053   typedef typename MeshType::FaceType       FaceType;
00054   typedef typename MeshType::FacePointer    FacePointer;
00055   typedef typename MeshType::FaceIterator   FaceIterator;
00056   typedef typename MeshType::ConstFaceIterator   ConstFaceIterator;
00057   typedef typename MeshType::FaceContainer  FaceContainer;
00058 
00059 public:
00060   void operator ++()
00061   {
00062     FacePointer fpt=sf.top();
00063     sf.pop();
00064     for(int j=0;j<3;++j)
00065       if( !face::IsBorder(*fpt,j) )
00066       {
00067         FacePointer l=fpt->FFp(j);
00068         if( !tri::IsMarked(*mp,l) )
00069         {
00070           tri::Mark(*mp,l);
00071           sf.push(l);
00072         }
00073       }
00074   }
00075 
00076   void start(MeshType &m, FacePointer p)
00077   {
00078     tri::RequirePerFaceMark(m);
00079     mp=&m;
00080     while(!sf.empty()) sf.pop();
00081     UnMarkAll(m);
00082     assert(p);
00083     assert(!p->IsD());
00084     tri::Mark(m,p);
00085     sf.push(p);
00086   }
00087 
00088   bool completed() {
00089     return sf.empty();
00090   }
00091 
00092   FacePointer operator *()
00093   {
00094     return sf.top();
00095   }
00096 private:
00097   std::stack<FacePointer> sf;
00098   MeshType *mp;
00099 };
00100 
00101 
00103 
00105 
00106 template <class CleanMeshType>
00107 class Clean
00108 {
00109 
00110 public:
00111   typedef CleanMeshType MeshType;
00112   typedef typename MeshType::VertexType           VertexType;
00113   typedef typename MeshType::VertexPointer        VertexPointer;
00114   typedef typename MeshType::VertexIterator       VertexIterator;
00115   typedef typename MeshType::ConstVertexIterator  ConstVertexIterator;
00116   typedef typename MeshType::EdgeIterator         EdgeIterator;
00117   typedef typename MeshType::EdgePointer          EdgePointer;
00118   typedef typename MeshType::CoordType            CoordType;
00119   typedef typename MeshType::ScalarType           ScalarType;
00120   typedef typename MeshType::FaceType             FaceType;
00121   typedef typename MeshType::FacePointer          FacePointer;
00122   typedef typename MeshType::FaceIterator         FaceIterator;
00123   typedef typename MeshType::ConstFaceIterator    ConstFaceIterator;
00124   typedef typename MeshType::FaceContainer        FaceContainer;
00125   typedef typename vcg::Box3<ScalarType>  Box3Type;
00126 
00127   typedef GridStaticPtr<FaceType, ScalarType > TriMeshGrid;
00128 
00129   /* classe di confronto per l'algoritmo di eliminazione vertici duplicati*/
00130   class RemoveDuplicateVert_Compare{
00131   public:
00132     inline bool operator()(VertexPointer const &a, VertexPointer const &b)
00133     {
00134         return ((*a).cP() == (*b).cP()) ? (a<b): ((*a).cP() < (*b).cP());
00135     }
00136   };
00137 
00138 
00143   static int RemoveDuplicateVertex( MeshType & m, bool RemoveDegenerateFlag=true)    // V1.0
00144   {
00145     if(m.vert.size()==0 || m.vn==0) return 0;
00146 
00147     std::map<VertexPointer, VertexPointer> mp;
00148     size_t i,j;
00149     VertexIterator vi;
00150     int deleted=0;
00151     int k=0;
00152     size_t num_vert = m.vert.size();
00153     std::vector<VertexPointer> perm(num_vert);
00154     for(vi=m.vert.begin(); vi!=m.vert.end(); ++vi, ++k)
00155       perm[k] = &(*vi);
00156 
00157     RemoveDuplicateVert_Compare c_obj;
00158 
00159     std::sort(perm.begin(),perm.end(),c_obj);
00160 
00161     j = 0;
00162     i = j;
00163     mp[perm[i]] = perm[j];
00164     ++i;
00165     for(;i!=num_vert;)
00166     {
00167       if( (! (*perm[i]).IsD()) &&
00168           (! (*perm[j]).IsD()) &&
00169           (*perm[i]).P() == (*perm[j]).cP() )
00170       {
00171         VertexPointer t = perm[i];
00172         mp[perm[i]] = perm[j];
00173         ++i;
00174         Allocator<MeshType>::DeleteVertex(m,*t);
00175         deleted++;
00176       }
00177       else
00178       {
00179         j = i;
00180         ++i;
00181       }
00182     }
00183 
00184     for(FaceIterator fi = m.face.begin(); fi!=m.face.end(); ++fi)
00185       if( !(*fi).IsD() )
00186         for(k = 0; k < (*fi).VN(); ++k)
00187           if( mp.find( (typename MeshType::VertexPointer)(*fi).V(k) ) != mp.end() )
00188           {
00189             (*fi).V(k) = &*mp[ (*fi).V(k) ];
00190           }
00191 
00192 
00193     for(EdgeIterator ei = m.edge.begin(); ei!=m.edge.end(); ++ei)
00194       if( !(*ei).IsD() )
00195         for(k = 0; k < 2; ++k)
00196           if( mp.find( (typename MeshType::VertexPointer)(*ei).V(k) ) != mp.end() )
00197           {
00198             (*ei).V(k) = &*mp[ (*ei).V(k) ];
00199           }
00200     if(RemoveDegenerateFlag) RemoveDegenerateFace(m);
00201     if(RemoveDegenerateFlag && m.en>0) {
00202       RemoveDegenerateEdge(m);
00203       RemoveDuplicateEdge(m);
00204     }
00205     return deleted;
00206   }
00207 
00208   class SortedPair
00209   {
00210   public:
00211     SortedPair() {}
00212     SortedPair(unsigned int v0, unsigned int v1, EdgePointer _fp)
00213     {
00214       v[0]=v0;v[1]=v1;
00215       fp=_fp;
00216       if(v[0]>v[1]) std::swap(v[0],v[1]);
00217     }
00218     bool operator < (const SortedPair &p) const
00219     {
00220       return (v[1]!=p.v[1])?(v[1]<p.v[1]):
00221         (v[0]<p.v[0]);                          }
00222 
00223       bool operator == (const SortedPair &s) const
00224       {
00225       if( (v[0]==s.v[0]) && (v[1]==s.v[1]) ) return true;
00226       return false;
00227     }
00228 
00229     unsigned int v[2];
00230     EdgePointer fp;
00231   };
00232   class SortedTriple
00233   {
00234   public:
00235     SortedTriple() {}
00236     SortedTriple(unsigned int v0, unsigned int v1, unsigned int v2,FacePointer _fp)
00237     {
00238       v[0]=v0;v[1]=v1;v[2]=v2;
00239       fp=_fp;
00240       std::sort(v,v+3);
00241     }
00242     bool operator < (const SortedTriple &p) const
00243     {
00244       return (v[2]!=p.v[2])?(v[2]<p.v[2]):
00245         (v[1]!=p.v[1])?(v[1]<p.v[1]):
00246           (v[0]<p.v[0]);                                }
00247 
00248       bool operator == (const SortedTriple &s) const
00249       {
00250       if( (v[0]==s.v[0]) && (v[1]==s.v[1]) && (v[2]==s.v[2]) ) return true;
00251       return false;
00252     }
00253 
00254     unsigned int v[3];
00255     FacePointer fp;
00256   };
00257 
00258 
00264   static int RemoveDuplicateFace( MeshType & m)    // V1.0
00265   {
00266     std::vector<SortedTriple> fvec;
00267     for(FaceIterator fi=m.face.begin();fi!=m.face.end();++fi)
00268       if(!(*fi).IsD())
00269       {
00270         fvec.push_back(SortedTriple(    tri::Index(m,(*fi).V(0)),
00271                                         tri::Index(m,(*fi).V(1)),
00272                                         tri::Index(m,(*fi).V(2)),
00273                                         &*fi));
00274       }
00275     assert (size_t(m.fn) == fvec.size());
00276     std::sort(fvec.begin(),fvec.end());
00277     int total=0;
00278     for(int i=0;i<int(fvec.size())-1;++i)
00279     {
00280       if(fvec[i]==fvec[i+1])
00281       {
00282         total++;
00283         tri::Allocator<MeshType>::DeleteFace(m, *(fvec[i].fp) );
00284       }
00285     }
00286     return total;
00287   }
00288 
00294   static int RemoveDuplicateEdge( MeshType & m)    // V1.0
00295   {
00296     if (m.en==0) return 0;
00297     std::vector<SortedPair> eVec;
00298     for(EdgeIterator ei=m.edge.begin();ei!=m.edge.end();++ei)
00299       if(!(*ei).IsD())
00300       {
00301         eVec.push_back(SortedPair(      tri::Index(m,(*ei).V(0)), tri::Index(m,(*ei).V(1)), &*ei));
00302       }
00303     assert (size_t(m.en) == eVec.size());
00304     //for(int i=0;i<fvec.size();++i) qDebug("fvec[%i] = (%i %i %i)(%i)",i,fvec[i].v[0],fvec[i].v[1],fvec[i].v[2],tri::Index(m,fvec[i].fp));
00305     std::sort(eVec.begin(),eVec.end());
00306     int total=0;
00307     for(int i=0;i<int(eVec.size())-1;++i)
00308     {
00309       if(eVec[i]==eVec[i+1])
00310       {
00311         total++;
00312         tri::Allocator<MeshType>::DeleteEdge(m, *(eVec[i].fp) );
00313         //qDebug("deleting face %i (pos in fvec %i)",tri::Index(m,fvec[i].fp) ,i);
00314       }
00315     }
00316     return total;
00317   }
00318 
00319   static int CountUnreferencedVertex( MeshType& m)
00320   {
00321     return RemoveUnreferencedVertex(m,false);
00322   }
00323 
00324 
00329   static int RemoveUnreferencedVertex( MeshType& m, bool DeleteVertexFlag=true)   // V1.0
00330   {
00331     FaceIterator fi;
00332     EdgeIterator ei;
00333     VertexIterator vi;
00334     int referredBit = VertexType::NewBitFlag();
00335 
00336     int j;
00337     int deleted = 0;
00338 
00339     for(vi=m.vert.begin();vi!=m.vert.end();++vi)
00340       (*vi).ClearUserBit(referredBit);
00341 
00342     for(fi=m.face.begin();fi!=m.face.end();++fi)
00343       if( !(*fi).IsD() )
00344         for(j=0;j<(*fi).VN();++j)
00345           (*fi).V(j)->SetUserBit(referredBit);
00346 
00347     for(ei=m.edge.begin();ei!=m.edge.end();++ei)
00348       if( !(*ei).IsD() ){
00349         (*ei).V(0)->SetUserBit(referredBit);
00350         (*ei).V(1)->SetUserBit(referredBit);
00351       }
00352 
00353     for(vi=m.vert.begin();vi!=m.vert.end();++vi)
00354       if( (!(*vi).IsD()) && (!(*vi).IsUserBit(referredBit)))
00355       {
00356         if(DeleteVertexFlag) Allocator<MeshType>::DeleteVertex(m,*vi);
00357         ++deleted;
00358       }
00359     VertexType::DeleteBitFlag(referredBit);
00360     return deleted;
00361   }
00362 
00367   static int RemoveDegenerateVertex(MeshType& m)
00368   {
00369     VertexIterator vi;
00370     int count_vd = 0;
00371 
00372     for(vi=m.vert.begin(); vi!=m.vert.end();++vi)
00373       if(math::IsNAN( (*vi).P()[0]) ||
00374          math::IsNAN( (*vi).P()[1]) ||
00375          math::IsNAN( (*vi).P()[2]) )
00376       {
00377         count_vd++;
00378         Allocator<MeshType>::DeleteVertex(m,*vi);
00379       }
00380 
00381     FaceIterator fi;
00382     int count_fd = 0;
00383 
00384     for(fi=m.face.begin(); fi!=m.face.end();++fi)
00385       if(!(*fi).IsD())
00386         if( (*fi).V(0)->IsD() ||
00387             (*fi).V(1)->IsD() ||
00388             (*fi).V(2)->IsD() )
00389         {
00390           count_fd++;
00391           Allocator<MeshType>::DeleteFace(m,*fi);
00392         }
00393     return count_vd;
00394   }
00395 
00404   static int RemoveDegenerateFace(MeshType& m)
00405   {
00406     int count_fd = 0;
00407 
00408     for(FaceIterator fi=m.face.begin(); fi!=m.face.end();++fi)
00409       if(!(*fi).IsD())
00410       {
00411         if((*fi).V(0) == (*fi).V(1) ||
00412            (*fi).V(0) == (*fi).V(2) ||
00413            (*fi).V(1) == (*fi).V(2) )
00414         {
00415           count_fd++;
00416           Allocator<MeshType>::DeleteFace(m,*fi);
00417         }
00418       }
00419     return count_fd;
00420   }
00421 
00422   static int RemoveDegenerateEdge(MeshType& m)
00423   {
00424     int count_ed = 0;
00425 
00426     for(EdgeIterator ei=m.edge.begin(); ei!=m.edge.end();++ei)
00427       if(!(*ei).IsD())
00428       {
00429         if((*ei).V(0) == (*ei).V(1) )
00430         {
00431           count_ed++;
00432           Allocator<MeshType>::DeleteEdge(m,*ei);
00433         }
00434       }
00435     return count_ed;
00436   }
00437 
00438   static int RemoveNonManifoldVertex(MeshType& m)
00439   {
00440     CountNonManifoldVertexFF(m,true);
00441     tri::UpdateSelection<MeshType>::FaceFromVertexLoose(m);
00442     int count_removed = 0;
00443     FaceIterator fi;
00444     for(fi=m.face.begin(); fi!=m.face.end();++fi)
00445       if(!(*fi).IsD() && (*fi).IsS())
00446         Allocator<MeshType>::DeleteFace(m,*fi);
00447     VertexIterator vi;
00448     for(vi=m.vert.begin(); vi!=m.vert.end();++vi)
00449       if(!(*vi).IsD() && (*vi).IsS()) {
00450         ++count_removed;
00451         Allocator<MeshType>::DeleteVertex(m,*vi);
00452       }
00453     return count_removed;
00454   }
00455 
00456   static int SplitSelectedVertexOnEdgeMesh(MeshType& m)
00457   {
00458     tri::RequireCompactness(m);
00459     tri::UpdateFlags<MeshType>::VertexClearV(m);
00460     int count_split = 0;
00461     for(size_t i=0;i<m.edge.size();++i)
00462     {
00463       for(int j=0;j<2;++j)
00464       {
00465         VertexPointer vp = m.edge[i].V(j);
00466         if(vp->IsS())
00467         {
00468           if(!vp->IsV())
00469             {
00470             m.edge[i].V(j) = &*(tri::Allocator<MeshType>::AddVertex(m,vp->P()));
00471             ++count_split;
00472             }
00473           else 
00474             {
00475               vp->SetV();
00476             }
00477           
00478         }
00479       }
00480     }
00481     return count_split;
00482   }
00483 
00484 
00485   static void SelectNonManifoldVertexOnEdgeMesh(MeshType &m)
00486   {
00487     tri::RequireCompactness(m);
00488     tri::UpdateSelection<MeshType>::VertexClear(m);
00489     std::vector<int> cnt(m.vn,0);
00490 
00491     for(size_t i=0;i<m.edge.size();++i)
00492     {
00493       cnt[tri::Index(m,m.edge[i].V(0))]++;
00494       cnt[tri::Index(m,m.edge[i].V(1))]++;
00495     }
00496     for(size_t i=0;i<m.vert.size();++i)
00497       if(cnt[i]>2) m.vert[i].SetS();
00498   }
00499 
00500   static void SelectCreaseVertexOnEdgeMesh(MeshType &m, ScalarType AngleRadThr)
00501   {
00502     tri::RequireCompactness(m);
00503     tri::RequireVEAdjacency(m);
00504     tri::UpdateTopology<MeshType>::VertexEdge(m);
00505     for(size_t i=0;i<m.vert.size();++i)
00506     {
00507       std::vector<VertexPointer> VVStarVec;
00508       edge::VVStarVE(&(m.vert[i]),VVStarVec);
00509       if(VVStarVec.size()==2)
00510       {
00511         CoordType v0 = m.vert[i].P() - VVStarVec[0]->P();
00512         CoordType v1 = m.vert[i].P() - VVStarVec[1]->P();
00513         float angle = M_PI-vcg::Angle(v0,v1);
00514         if(angle > AngleRadThr) m.vert[i].SetS();
00515       }
00516     }
00517   }
00518 
00519 
00521 
00522   // Given a mesh with FF adjacency
00523   // it search for non manifold vertices and duplicate them.
00524   // Duplicated vertices are moved apart according to the move threshold param.
00525   // that is a percentage of the average vector from the non manifold vertex to the barycenter of the incident faces.
00526 
00527   static int SplitNonManifoldVertex(MeshType& m, ScalarType moveThreshold)
00528   {
00529     RequireFFAdjacency(m);
00530     typedef std::pair<FacePointer,int> FaceInt; // a face and the index of the vertex that we have to change
00531     //
00532     std::vector<std::pair<VertexPointer, std::vector<FaceInt> > >ToSplitVec;
00533 
00534     SelectionStack<MeshType> ss(m);
00535     ss.push();
00536     CountNonManifoldVertexFF(m,true);
00537     UpdateFlags<MeshType>::VertexClearV(m);
00538     for (FaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi)    if (!fi->IsD())
00539     {
00540       for(int i=0;i<3;i++)
00541         if((*fi).V(i)->IsS() && !(*fi).V(i)->IsV())
00542         {
00543           (*fi).V(i)->SetV();
00544           face::Pos<FaceType> startPos(&*fi,i);
00545           face::Pos<FaceType> curPos = startPos;
00546           std::set<FaceInt> faceSet;
00547           do
00548           {
00549             faceSet.insert(std::make_pair(curPos.F(),curPos.VInd()));
00550             curPos.NextE();
00551           } while (curPos != startPos);
00552 
00553           ToSplitVec.push_back(make_pair((*fi).V(i),std::vector<FaceInt>()));
00554 
00555           typename std::set<FaceInt>::const_iterator iii;
00556 
00557           for(iii=faceSet.begin();iii!=faceSet.end();++iii)
00558             ToSplitVec.back().second.push_back(*iii);
00559         }
00560     }
00561     ss.pop();
00562     // Second step actually add new vertices and split them.
00563     typename tri::Allocator<MeshType>::template PointerUpdater<VertexPointer> pu;
00564     VertexIterator firstVp = tri::Allocator<MeshType>::AddVertices(m,ToSplitVec.size(),pu);
00565     for(size_t i =0;i<ToSplitVec.size();++i)
00566     {
00567       //          qDebug("Splitting Vertex %i",ToSplitVec[i].first-&*m.vert.begin());
00568       VertexPointer np=ToSplitVec[i].first;
00569       pu.Update(np);
00570       firstVp->ImportData(*np);
00571       // loop on the face to be changed, and also compute the movement vector;
00572       CoordType delta(0,0,0);
00573       for(size_t j=0;j<ToSplitVec[i].second.size();++j)
00574       {
00575         FaceInt ff=ToSplitVec[i].second[j];
00576         ff.first->V(ff.second)=&*firstVp;
00577         delta+=Barycenter(*(ff.first))-np->cP();
00578       }
00579       delta /= ToSplitVec[i].second.size();
00580       firstVp->P() = firstVp->P() + delta * moveThreshold;
00581       firstVp++;
00582     }
00583 
00584     return ToSplitVec.size();
00585   }
00586 
00587 
00588   // Auxiliary function for sorting the non manifold faces according to their area. Used in  RemoveNonManifoldFace
00589   struct CompareAreaFP {
00590     bool operator ()(FacePointer const& f1, FacePointer const& f2) const {
00591       return DoubleArea(*f1) < DoubleArea(*f2);
00592     }
00593   };
00594 
00596   static int RemoveNonManifoldFace(MeshType& m)
00597   {
00598     FaceIterator fi;
00599     int count_fd = 0;
00600     std::vector<FacePointer> ToDelVec;
00601 
00602     for(fi=m.face.begin(); fi!=m.face.end();++fi)
00603       if (!fi->IsD())
00604       {
00605         if ((!IsManifold(*fi,0))||
00606             (!IsManifold(*fi,1))||
00607             (!IsManifold(*fi,2)))
00608           ToDelVec.push_back(&*fi);
00609       }
00610 
00611     std::sort(ToDelVec.begin(),ToDelVec.end(),CompareAreaFP());
00612 
00613     for(size_t i=0;i<ToDelVec.size();++i)
00614     {
00615       if(!ToDelVec[i]->IsD())
00616       {
00617         FaceType &ff= *ToDelVec[i];
00618         if ((!IsManifold(ff,0))||
00619             (!IsManifold(ff,1))||
00620             (!IsManifold(ff,2)))
00621         {
00622           for(int j=0;j<3;++j)
00623             if(!face::IsBorder<FaceType>(ff,j))
00624               vcg::face::FFDetach<FaceType>(ff,j);
00625 
00626           Allocator<MeshType>::DeleteFace(m,ff);
00627           count_fd++;
00628         }
00629       }
00630     }
00631     return count_fd;
00632   }
00633 
00634   /*
00635       The following functions remove faces that are geometrically "bad" according to edges and area criteria.
00636       They remove the faces that are out of a given range of area or edges (e.g. faces too large or too small, or with edges too short or too long)
00637       but that could be topologically correct.
00638       These functions can optionally take into account only the selected faces.
00639       */
00640   template<bool Selected>
00641   static int RemoveFaceOutOfRangeAreaSel(MeshType& m, ScalarType MinAreaThr=0, ScalarType MaxAreaThr=(std::numeric_limits<ScalarType>::max)())
00642   {
00643     FaceIterator fi;
00644     int count_fd = 0;
00645     MinAreaThr*=2;
00646     MaxAreaThr*=2;
00647     for(fi=m.face.begin(); fi!=m.face.end();++fi)
00648       if(!(*fi).IsD())
00649         if(!Selected || (*fi).IsS())
00650         {
00651           const ScalarType doubleArea=DoubleArea<FaceType>(*fi);
00652           if((doubleArea<=MinAreaThr) || (doubleArea>=MaxAreaThr) )
00653           {
00654             Allocator<MeshType>::DeleteFace(m,*fi);
00655             count_fd++;
00656           }
00657         }
00658     return count_fd;
00659   }
00660 
00661   // alias for the old style. Kept for backward compatibility
00662   static int RemoveZeroAreaFace(MeshType& m) { return RemoveFaceOutOfRangeArea(m);}
00663 
00664   // Aliases for the functions that do not look at selection
00665   static int RemoveFaceOutOfRangeArea(MeshType& m, ScalarType MinAreaThr=0, ScalarType MaxAreaThr=(std::numeric_limits<ScalarType>::max)())
00666   {
00667     return RemoveFaceOutOfRangeAreaSel<false>(m,MinAreaThr,MaxAreaThr);
00668   }
00669 
00673   static bool IsBitQuadOnly(const MeshType &m)
00674   {
00675     typedef typename MeshType::FaceType F;
00676     tri::RequirePerFaceFlags(m);
00677     for (ConstFaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi) if (!fi->IsD()) {
00678       unsigned int tmp = fi->Flags()&(F::FAUX0|F::FAUX1|F::FAUX2);
00679       if ( tmp != F::FAUX0 && tmp != F::FAUX1 && tmp != F::FAUX2) return false;
00680     }
00681     return true;
00682   }
00683 
00684 
00685   static bool IsFaceFauxConsistent(MeshType &m)
00686   {
00687     RequirePerFaceFlags(m);
00688     RequireFFAdjacency(m);
00689     for(FaceIterator fi=m.face.begin();fi!=m.face.end();++fi) if(!(*fi).IsD())
00690     {
00691       for(int z=0;z<(*fi).VN();++z)
00692       {
00693         FacePointer fp = fi->FFp(z);
00694         int zp = fi->FFi(z);
00695         if(fi->IsF(z) != fp->IsF(zp)) return false;
00696       }
00697     }
00698     return true;
00699   }
00700 
00704   static bool IsBitTriOnly(const MeshType &m)
00705   {
00706     tri::RequirePerFaceFlags(m);
00707     for (ConstFaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi) {
00708       if ( !fi->IsD()  &&  fi->IsAnyF() ) return false;
00709     }
00710     return true;
00711   }
00712 
00713   static bool IsBitPolygonal(const MeshType &m){
00714     return !IsBitTriOnly(m);
00715   }
00716 
00721   static bool IsBitTriQuadOnly(const MeshType &m)
00722   {
00723     tri::RequirePerFaceFlags(m);
00724     typedef typename MeshType::FaceType F;
00725     for (ConstFaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi) if (!fi->IsD()) {
00726       unsigned int tmp = fi->cFlags()&(F::FAUX0|F::FAUX1|F::FAUX2);
00727       if ( tmp!=F::FAUX0 && tmp!=F::FAUX1 && tmp!=F::FAUX2 && tmp!=0 ) return false;
00728     }
00729     return true;
00730   }
00731 
00736   static int CountBitQuads(const MeshType &m)
00737   {
00738     tri::RequirePerFaceFlags(m);
00739     typedef typename MeshType::FaceType F;
00740     int count=0;
00741     for (ConstFaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi) if (!fi->IsD()) {
00742       unsigned int tmp = fi->cFlags()&(F::FAUX0|F::FAUX1|F::FAUX2);
00743       if ( tmp==F::FAUX0 || tmp==F::FAUX1 || tmp==F::FAUX2) count++;
00744     }
00745     return count / 2;
00746   }
00747 
00751   static int CountBitTris(const MeshType &m)
00752   {
00753     tri::RequirePerFaceFlags(m);
00754     int count=0;
00755     for (ConstFaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi) if (!fi->IsD()) {
00756       if (!(fi->IsAnyF())) count++;
00757     }
00758     return count;
00759   }
00760 
00765   static int CountBitPolygons(const MeshType &m)
00766   {
00767     tri::RequirePerFaceFlags(m);
00768     int count = 0;
00769     for (ConstFaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi) if (!fi->IsD())  {
00770       if (fi->IsF(0)) count++;
00771       if (fi->IsF(1)) count++;
00772       if (fi->IsF(2)) count++;
00773     }
00774     return m.fn - count/2;
00775   }
00776 
00788   static int CountBitLargePolygons(MeshType &m)
00789   {
00790     tri::RequirePerFaceFlags(m);
00791     UpdateFlags<MeshType>::VertexSetV(m);
00792     // First loop Clear all referenced vertices
00793     for (FaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi)
00794       if (!fi->IsD())
00795         for(int i=0;i<3;++i) fi->V(i)->ClearV();
00796 
00797 
00798     // Second Loop, count (twice) faux edges and mark all vertices touched by non faux edges
00799     // (e.g vertexes on the boundary of a polygon)
00800     int countE = 0;
00801     for (FaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi)
00802       if (!fi->IsD())  {
00803         for(int i=0;i<3;++i)
00804         {
00805           if (fi->IsF(i))
00806             countE++;
00807           else
00808           {
00809             fi->V0(i)->SetV();
00810             fi->V1(i)->SetV();
00811           }
00812         }
00813       }
00814     // Third Loop, count the number of referenced vertexes that are completely surrounded by faux edges.
00815 
00816     int countV = 0;
00817     for (VertexIterator vi = m.vert.begin(); vi != m.vert.end(); ++vi)
00818       if (!vi->IsD() && !vi->IsV()) countV++;
00819 
00820     return m.fn - countE/2 + countV ;
00821   }
00822 
00823 
00831   static bool HasConsistentPerFaceFauxFlag(const MeshType &m)
00832   {
00833     RequireFFAdjacency(m);
00834     RequirePerFaceFlags(m);
00835 
00836     for (ConstFaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi)
00837       if(!(*fi).IsD())
00838         for (int k=0; k<3; k++)
00839           if( ( fi->IsF(k) != fi->cFFp(k)->IsF(fi->cFFi(k)) ) ||
00840               ( fi->IsF(k) && face::IsBorder(*fi,k)) )
00841           {
00842             return false;
00843           }
00844     return true;
00845   }
00846 
00851   static int CountNonManifoldEdgeEE( MeshType & m, bool SelectFlag=false)
00852   {
00853     assert(m.fn == 0 && m.en >0); // just to be sure we are using an edge mesh...
00854     RequireEEAdjacency(m);
00855     tri::UpdateTopology<MeshType>::EdgeEdge(m);
00856 
00857     if(SelectFlag) UpdateSelection<MeshType>::VertexClear(m);
00858 
00859     int nonManifoldCnt=0;
00860     SimpleTempData<typename MeshType::VertContainer, int > TD(m.vert,0);
00861 
00862     // First Loop, just count how many faces are incident on a vertex and store it in the TemporaryData Counter.
00863     EdgeIterator ei;
00864     for (ei = m.edge.begin(); ei != m.edge.end(); ++ei) if (!ei->IsD())
00865     {
00866       TD[(*ei).V(0)]++;
00867       TD[(*ei).V(1)]++;
00868     }
00869 
00870     tri::UpdateFlags<MeshType>::VertexClearV(m);
00871     // Second Loop, Check that each vertex have been seen 1 or 2 times.
00872     for (VertexIterator vi = m.vert.begin(); vi != m.vert.end(); ++vi)  if (!vi->IsD())
00873     {
00874       if( TD[vi] >2 )
00875       {
00876         if(SelectFlag) (*vi).SetS();
00877         nonManifoldCnt++;
00878       }
00879     }
00880     return nonManifoldCnt;
00881   }
00882 
00889   static int CountNonManifoldEdgeFF( MeshType & m, bool SelectFlag=false)
00890   {
00891     RequireFFAdjacency(m);
00892     int nmfBit[3];
00893     nmfBit[0]= FaceType::NewBitFlag();
00894     nmfBit[1]= FaceType::NewBitFlag();
00895     nmfBit[2]= FaceType::NewBitFlag();
00896 
00897 
00898     UpdateFlags<MeshType>::FaceClear(m,nmfBit[0]+nmfBit[1]+nmfBit[2]);
00899 
00900     if(SelectFlag){
00901       UpdateSelection<MeshType>::VertexClear(m);
00902       UpdateSelection<MeshType>::FaceClear(m);
00903     }
00904 
00905     int edgeCnt = 0;
00906     for (FaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi)
00907     {
00908       if (!fi->IsD())
00909       {
00910         for(int i=0;i<3;++i)
00911           if(!IsManifold(*fi,i))
00912           {
00913             if(!(*fi).IsUserBit(nmfBit[i]))
00914             {
00915               ++edgeCnt;
00916               if(SelectFlag)
00917               {
00918                 (*fi).V0(i)->SetS();
00919                 (*fi).V1(i)->SetS();
00920               }
00921               // follow the ring of faces incident on edge i;
00922               face::Pos<FaceType> nmf(&*fi,i);
00923               do
00924               {
00925                 if(SelectFlag) nmf.F()->SetS();
00926                 nmf.F()->SetUserBit(nmfBit[nmf.E()]);
00927                 nmf.NextF();
00928               }
00929               while(nmf.f != &*fi);
00930             }
00931           }
00932       }
00933     }
00934     return edgeCnt;
00935   }
00936 
00941   static int CountNonManifoldVertexFF( MeshType & m, bool selectVert = true )
00942   {
00943     RequireFFAdjacency(m);
00944     if(selectVert) UpdateSelection<MeshType>::VertexClear(m);
00945 
00946     int nonManifoldCnt=0;
00947     SimpleTempData<typename MeshType::VertContainer, int > TD(m.vert,0);
00948 
00949     // First Loop, just count how many faces are incident on a vertex and store it in the TemporaryData Counter.
00950     FaceIterator fi;
00951     for (fi = m.face.begin(); fi != m.face.end(); ++fi) if (!fi->IsD())
00952     {
00953       TD[(*fi).V(0)]++;
00954       TD[(*fi).V(1)]++;
00955       TD[(*fi).V(2)]++;
00956     }
00957 
00958     tri::UpdateFlags<MeshType>::VertexClearV(m);
00959     // Second Loop.
00960     // mark out of the game the vertexes that are incident on non manifold edges.
00961     for (fi = m.face.begin(); fi != m.face.end(); ++fi) if (!fi->IsD())
00962     {
00963       for(int i=0;i<3;++i)
00964         if (!IsManifold(*fi,i))  {
00965           (*fi).V0(i)->SetV();
00966           (*fi).V1(i)->SetV();
00967         }
00968     }
00969     // Third Loop, for safe vertexes, check that the number of faces that you can reach starting
00970     // from it and using FF is the same of the previously counted.
00971     for (fi = m.face.begin(); fi != m.face.end(); ++fi) if (!fi->IsD())
00972     {
00973       for(int i=0;i<3;i++) if(!(*fi).V(i)->IsV()){
00974         (*fi).V(i)->SetV();
00975         face::Pos<FaceType> pos(&(*fi),i);
00976 
00977         int starSizeFF = pos.NumberOfIncidentFaces();
00978 
00979         if (starSizeFF != TD[(*fi).V(i)])
00980         {
00981           if(selectVert) (*fi).V(i)->SetS();
00982           nonManifoldCnt++;
00983         }
00984       }
00985     }
00986     return nonManifoldCnt;
00987   }
00995   static bool IsWaterTight(MeshType & m)
00996   {
00997     int edgeNum=0,edgeBorderNum=0,edgeNonManifNum=0;
00998     CountEdgeNum(m, edgeNum, edgeBorderNum,edgeNonManifNum);
00999     return  (edgeBorderNum==0) && (edgeNonManifNum==0);
01000   }
01001 
01002   static void CountEdgeNum( MeshType & m, int &total_e, int &boundary_e, int &non_manif_e )
01003   {
01004     std::vector< typename tri::UpdateTopology<MeshType>::PEdge > edgeVec;
01005     tri::UpdateTopology<MeshType>::FillEdgeVector(m,edgeVec,true);
01006     sort(edgeVec.begin(), edgeVec.end());               // Lo ordino per vertici
01007     total_e=0;
01008     boundary_e=0;
01009     non_manif_e=0;
01010 
01011     size_t f_on_cur_edge =1;
01012     for(size_t i=0;i<edgeVec.size();++i)
01013     {
01014       if(( (i+1) == edgeVec.size()) ||  !(edgeVec[i] == edgeVec[i+1]))
01015       {
01016         ++total_e;
01017         if(f_on_cur_edge==1)
01018           ++boundary_e;
01019         if(f_on_cur_edge>2)
01020           ++non_manif_e;
01021         f_on_cur_edge=1;
01022       }
01023       else
01024       {
01025         ++f_on_cur_edge;
01026       }
01027     } // end for
01028   }
01029 
01030 
01031 
01032   static int CountHoles( MeshType & m)
01033   {
01034     int numholev=0;
01035     FaceIterator fi;
01036 
01037     FaceIterator gi;
01038     vcg::face::Pos<FaceType> he;
01039     vcg::face::Pos<FaceType> hei;
01040 
01041     std::vector< std::vector<CoordType> > holes; //indices of vertices
01042 
01043     vcg::tri::UpdateFlags<MeshType>::VertexClearS(m);
01044 
01045     gi=m.face.begin(); fi=gi;
01046 
01047     for(fi=m.face.begin();fi!=m.face.end();fi++)//for all faces do
01048     {
01049       for(int j=0;j<3;j++)//for all edges
01050       {
01051         if(fi->V(j)->IsS()) continue;
01052 
01053         if(face::IsBorder(*fi,j))//found an unvisited border edge
01054         {
01055           he.Set(&(*fi),j,fi->V(j)); //set the face-face iterator to the current face, edge and vertex
01056           std::vector<CoordType> hole; //start of a new hole
01057           hole.push_back(fi->P(j)); // including the first vertex
01058           numholev++;
01059           he.v->SetS(); //set the current vertex as selected
01060           he.NextB(); //go to the next boundary edge
01061 
01062 
01063           while(fi->V(j) != he.v)//will we do not encounter the first boundary edge.
01064           {
01065             CoordType newpoint = he.v->P(); //select its vertex.
01066             if(he.v->IsS())//check if this vertex was selected already, because then we have an additional hole.
01067             {
01068               //cut and paste the additional hole.
01069               std::vector<CoordType> hole2;
01070               int index = static_cast<int>(find(hole.begin(),hole.end(),newpoint)
01071                                            - hole.begin());
01072               for(unsigned int i=index; i<hole.size(); i++)
01073                 hole2.push_back(hole[i]);
01074 
01075               hole.resize(index);
01076               if(hole2.size()!=0) //annoying in degenerate cases
01077                 holes.push_back(hole2);
01078             }
01079             hole.push_back(newpoint);
01080             numholev++;
01081             he.v->SetS(); //set the current vertex as selected
01082             he.NextB(); //go to the next boundary edge
01083           }
01084           holes.push_back(hole);
01085         }
01086       }
01087     }
01088     return static_cast<int>(holes.size());
01089   }
01090 
01091   /*
01092   Compute the set of connected components of a given mesh
01093   it fills a vector of pair < int , faceptr > with, for each connecteed component its size and a represnant
01094  */
01095   static int CountConnectedComponents(MeshType &m)
01096   {
01097     std::vector< std::pair<int,FacePointer> > CCV;
01098     return ConnectedComponents(m,CCV);
01099   }
01100 
01101   static int ConnectedComponents(MeshType &m, std::vector< std::pair<int,FacePointer> > &CCV)
01102   {
01103     tri::RequireFFAdjacency(m);
01104     CCV.clear();
01105     tri::UpdateSelection<MeshType>::FaceClear(m);
01106     std::stack<FacePointer> sf;
01107     FacePointer fpt=&*(m.face.begin());
01108     for(FaceIterator fi=m.face.begin();fi!=m.face.end();++fi)
01109     {
01110       if(!((*fi).IsD()) && !(*fi).IsS())
01111       {
01112         (*fi).SetS();
01113         CCV.push_back(std::make_pair(0,&*fi));
01114         sf.push(&*fi);
01115         while (!sf.empty())
01116         {
01117           fpt=sf.top();
01118           ++CCV.back().first;
01119           sf.pop();
01120           for(int j=0;j<3;++j)
01121           {
01122             if( !face::IsBorder(*fpt,j) )
01123             {
01124               FacePointer l = fpt->FFp(j);
01125               if( !(*l).IsS() )
01126               {
01127                 (*l).SetS();
01128                 sf.push(l);
01129               }
01130             }
01131           }
01132         }
01133       }
01134     }
01135     return int(CCV.size());
01136   }
01137 
01138   static void ComputeValence( MeshType &m, typename MeshType::PerVertexIntHandle &h)
01139   {
01140     for(VertexIterator vi=m.vert.begin(); vi!= m.vert.end();++vi)
01141       h[vi]=0;
01142 
01143     for(FaceIterator fi=m.face.begin();fi!=m.face.end();++fi)
01144     {
01145       if(!((*fi).IsD()))
01146         for(int j=0;j<fi->VN();j++)
01147           ++h[tri::Index(m,fi->V(j))];
01148     }
01149   }
01150 
01186   static int MeshGenus(int nvert,int nedges,int nfaces, int numholes, int numcomponents)
01187   {
01188     return -((nvert + nfaces - nedges + numholes - 2 * numcomponents) / 2);
01189   }
01190 
01191   static int MeshGenus(MeshType &m)
01192   {
01193     int nvert=m.vn;
01194     int nfaces=m.fn;
01195     int boundary_e,total_e,nonmanif_e;
01196     CountEdgeNum(m,total_e,boundary_e,nonmanif_e);
01197     int numholes=CountHoles(m);
01198     int numcomponents=CountConnectedComponents(m);
01199     int G=MeshGenus(nvert,total_e,nfaces,numholes,numcomponents);
01200     return G;
01201   }
01202 
01214   static void IsRegularMesh(MeshType &m, bool &Regular, bool &Semiregular)
01215   {
01216     RequireVFAdjacency(m);
01217     Regular = true;
01218 
01219     VertexIterator vi;
01220 
01221     // for each vertex the number of edges are count
01222     for (vi = m.vert.begin(); vi != m.vert.end(); ++vi)
01223     {
01224       if (!vi->IsD())
01225       {
01226         face::Pos<FaceType> he((*vi).VFp(), &*vi);
01227         face::Pos<FaceType> ht = he;
01228 
01229         int n=0;
01230         bool border=false;
01231         do
01232         {
01233           ++n;
01234           ht.NextE();
01235           if (ht.IsBorder())
01236             border=true;
01237         }
01238         while (ht != he);
01239 
01240         if (border)
01241           n = n/2;
01242 
01243         if ((n != 6)&&(!border && n != 4))
01244         {
01245           Regular = false;
01246           break;
01247         }
01248       }
01249     }
01250 
01251     if (!Regular)
01252       Semiregular = false;
01253     else
01254     {
01255       // For now we do not account for semi-regularity
01256       Semiregular = false;
01257     }
01258   }
01259 
01260 
01261   static bool IsCoherentlyOrientedMesh(MeshType &m)
01262   {
01263     for (FaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi)
01264       if (!fi->IsD())
01265         for(int i=0;i<3;++i)
01266           if(!face::CheckOrientation(*fi,i))
01267             return false;
01268 
01269     return true;
01270   }
01271 
01272   static void OrientCoherentlyMesh(MeshType &m, bool &Oriented, bool &Orientable)
01273   {
01274       RequireFFAdjacency(m);
01275       assert(&Oriented != &Orientable);
01276       assert(m.face.back().FFp(0));    // This algorithms require FF topology initialized
01277 
01278       Orientable = true;
01279       Oriented = true;
01280 
01281       tri::UpdateSelection<MeshType>::FaceClear(m);
01282       std::stack<FacePointer> faces;
01283 
01284       for (FaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi)
01285       {
01286           if (!fi->IsD() && !fi->IsS())
01287           {
01288               // each face put in the stack is selected (and oriented)
01289               fi->SetS();
01290               // New section of code to orient the initial face correctly
01291               if(fi->N()[2]>0.0)
01292               {
01293                   face::SwapEdge<FaceType,true>(*fi, 0);
01294                   //fi->N = vcg::Normal<float>(*fi);
01295                   vcg::face::ComputeNormal(*fi);
01296               }
01297               // End of new code section.
01298               faces.push(&(*fi));
01299 
01300               // empty the stack
01301               while (!faces.empty())
01302               {
01303                   FacePointer fp = faces.top();
01304                   faces.pop();
01305 
01306                   // make consistently oriented the adjacent faces
01307                   for (int j = 0; j < 3; j++)
01308                   {
01309                      //get one of the adjacent face
01310                      FacePointer fpaux = fp->FFp(j);
01311                      int iaux = fp->FFi(j);
01312 
01313                      if (!fpaux->IsD() && fpaux != fp && face::IsManifold<FaceType>(*fp, j))
01314                      {
01315                         if (!CheckOrientation(*fpaux, iaux))
01316                         {
01317                             Oriented = false;
01318 
01319                             if (!fpaux->IsS())
01320                             {
01321                                  face::SwapEdge<FaceType,true>(*fpaux, iaux);
01322                                  // New line to update face normal
01323                                  //fpaux->N = vcg::Normal<float>(*fpaux);
01324                                  face::ComputeNormal(*fpaux);
01325                                  // end of new section.
01326                                  assert(CheckOrientation(*fpaux, iaux));
01327                             }
01328                             else
01329                             {
01330                                  Orientable = false;
01331                                  break;
01332                             }
01333                          }
01334 
01335                          // put the oriented face into the stack
01336 
01337                          if (!fpaux->IsS())
01338                          {
01339                               fpaux->SetS();
01340                               faces.push(fpaux);
01341                          }
01342                      }
01343                  }
01344              }
01345          }
01346          if (!Orientable) break;
01347       }
01348   }
01349 
01350 
01352   static void FlipMesh(MeshType &m, bool selected=false)
01353   {
01354     for (FaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi) if(!(*fi).IsD())
01355       if(!selected || (*fi).IsS())
01356       {
01357         face::SwapEdge<FaceType,false>((*fi), 0);
01358         if (HasPerWedgeTexCoord(m))
01359           std::swap((*fi).WT(0),(*fi).WT(1));
01360       }
01361   }
01367   static bool FlipNormalOutside(MeshType &m)
01368   {
01369     if(m.vert.empty()) return false;
01370 
01371     tri::UpdateNormal<MeshType>::PerVertexAngleWeighted(m);
01372     tri::UpdateNormal<MeshType>::NormalizePerVertex(m);
01373 
01374     std::vector< VertexPointer > minVertVec;
01375     std::vector< VertexPointer > maxVertVec;
01376 
01377     // The set of directions to be choosen
01378     std::vector< CoordType > dirVec;
01379     dirVec.push_back(CoordType(1,0,0));
01380     dirVec.push_back(CoordType(0,1,0));
01381     dirVec.push_back(CoordType(0,0,1));
01382     dirVec.push_back(CoordType( 1, 1,1));
01383     dirVec.push_back(CoordType(-1, 1,1));
01384     dirVec.push_back(CoordType(-1,-1,1));
01385     dirVec.push_back(CoordType( 1,-1,1));
01386     for(size_t i=0;i<dirVec.size();++i)
01387     {
01388       Normalize(dirVec[i]);
01389       minVertVec.push_back(&*m.vert.begin());
01390       maxVertVec.push_back(&*m.vert.begin());
01391     }
01392     for (VertexIterator vi = m.vert.begin(); vi != m.vert.end(); ++vi) if(!(*vi).IsD())
01393     {
01394       for(size_t i=0;i<dirVec.size();++i)
01395       {
01396         if( (*vi).cP().dot(dirVec[i]) < minVertVec[i]->P().dot(dirVec[i])) minVertVec[i] = &*vi;
01397         if( (*vi).cP().dot(dirVec[i]) > maxVertVec[i]->P().dot(dirVec[i])) maxVertVec[i] = &*vi;
01398       }
01399     }
01400 
01401     int voteCount=0;
01402     ScalarType angleThreshold = cos(math::ToRad(85.0));
01403     for(size_t i=0;i<dirVec.size();++i)
01404     {
01405       //          qDebug("Min vert along (%f %f %f) is %f %f %f",dirVec[i][0],dirVec[i][1],dirVec[i][2],minVertVec[i]->P()[0],minVertVec[i]->P()[1],minVertVec[i]->P()[2]);
01406       //          qDebug("Max vert along (%f %f %f) is %f %f %f",dirVec[i][0],dirVec[i][1],dirVec[i][2],maxVertVec[i]->P()[0],maxVertVec[i]->P()[1],maxVertVec[i]->P()[2]);
01407       if(minVertVec[i]->N().dot(dirVec[i]) > angleThreshold ) voteCount++;
01408       if(maxVertVec[i]->N().dot(dirVec[i]) < -angleThreshold ) voteCount++;
01409     }
01410     //        qDebug("votecount = %i",voteCount);
01411     if(voteCount < int(dirVec.size())/2) return false;
01412     FlipMesh(m);
01413     return true;
01414   }
01415 
01416   // Search and remove small single triangle folds
01417   // - a face has normal opposite to all other faces
01418   // - choose the edge that brings to the face f1 containing the vertex opposite to that edge.
01419   static int RemoveFaceFoldByFlip(MeshType &m, float normalThresholdDeg=175, bool repeat=true)
01420   {
01421     RequireFFAdjacency(m);
01422     RequirePerVertexMark(m);
01423     //Counters for logging and convergence
01424     int count, total = 0;
01425 
01426     do {
01427       tri::UpdateTopology<MeshType>::FaceFace(m);
01428       tri::UnMarkAll(m);
01429       count = 0;
01430 
01431       ScalarType NormalThrRad = math::ToRad(normalThresholdDeg);
01432       ScalarType eps = 0.0001; // this epsilon value is in absolute value. It is a distance from edge in baricentric coords.
01433       //detection stage
01434       for(FaceIterator fi=m.face.begin();fi!= m.face.end();++fi ) if(!(*fi).IsV())
01435       { Point3<ScalarType> NN = vcg::TriangleNormal((*fi)).Normalize();
01436         if( vcg::AngleN(NN,TriangleNormal(*(*fi).FFp(0)).Normalize()) > NormalThrRad &&
01437             vcg::AngleN(NN,TriangleNormal(*(*fi).FFp(1)).Normalize()) > NormalThrRad &&
01438             vcg::AngleN(NN,TriangleNormal(*(*fi).FFp(2)).Normalize()) > NormalThrRad )
01439         {
01440           (*fi).SetS();
01441           //(*fi).C()=Color4b(Color4b::Red);
01442           // now search the best edge to flip
01443           for(int i=0;i<3;i++)
01444           {
01445             Point3<ScalarType> &p=(*fi).P2(i);
01446             Point3<ScalarType> L;
01447             bool ret = vcg::InterpolationParameters((*(*fi).FFp(i)),TriangleNormal(*(*fi).FFp(i)),p,L);
01448             if(ret && L[0]>eps && L[1]>eps && L[2]>eps)
01449             {
01450               (*fi).FFp(i)->SetS();
01451               (*fi).FFp(i)->SetV();
01452               //(*fi).FFp(i)->C()=Color4b(Color4b::Green);
01453               if(face::CheckFlipEdge<FaceType>( *fi, i ))  {
01454                 face::FlipEdge<FaceType>( *fi, i );
01455                 ++count; ++total;
01456               }
01457             }
01458           }
01459         }
01460       }
01461 
01462       // tri::UpdateNormal<MeshType>::PerFace(m);
01463     }
01464     while( repeat && count );
01465     return total;
01466   }
01467 
01468 
01469   static int RemoveTVertexByFlip(MeshType &m, float threshold=40, bool repeat=true)
01470   {
01471     RequireFFAdjacency(m);
01472     RequirePerVertexMark(m);
01473     //Counters for logging and convergence
01474     int count, total = 0;
01475 
01476     do {
01477       tri::UpdateTopology<MeshType>::FaceFace(m);
01478       tri::UnMarkAll(m);
01479       count = 0;
01480 
01481       //detection stage
01482       for(unsigned int index = 0 ; index < m.face.size(); ++index )
01483       {
01484         FacePointer f = &(m.face[index]);    float sides[3]; CoordType dummy;
01485         sides[0] = Distance(f->P(0), f->P(1));
01486         sides[1] = Distance(f->P(1), f->P(2));
01487         sides[2] = Distance(f->P(2), f->P(0));
01488         // Find largest triangle side
01489         int i = std::find(sides, sides+3, std::max( std::max(sides[0],sides[1]), sides[2])) - (sides);
01490         if( tri::IsMarked(m,f->V2(i) )) continue;
01491 
01492         if( PSDist(f->P2(i),f->P(i),f->P1(i),dummy)*threshold <= sides[i] )
01493         {
01494           tri::Mark(m,f->V2(i));
01495           if(face::CheckFlipEdge<FaceType>( *f, i ))  {
01496             // Check if EdgeFlipping improves quality
01497             FacePointer g = f->FFp(i); int k = f->FFi(i);
01498             Triangle3<ScalarType> t1(f->P(i), f->P1(i), f->P2(i)), t2(g->P(k), g->P1(k), g->P2(k)),
01499                 t3(f->P(i), g->P2(k), f->P2(i)), t4(g->P(k), f->P2(i), g->P2(k));
01500 
01501             if ( std::min( QualityFace(t1), QualityFace(t2) ) < std::min( QualityFace(t3), QualityFace(t4) ))
01502             {
01503               face::FlipEdge<FaceType>( *f, i );
01504               ++count; ++total;
01505             }
01506           }
01507 
01508         }
01509       }
01510 
01511       // tri::UpdateNormal<MeshType>::PerFace(m);
01512     }
01513     while( repeat && count );
01514     return total;
01515   }
01516 
01517   static int RemoveTVertexByCollapse(MeshType &m, float threshold=40, bool repeat=true)
01518   {
01519     RequirePerVertexMark(m);
01520     //Counters for logging and convergence
01521     int count, total = 0;
01522 
01523     do {
01524       tri::UnMarkAll(m);
01525       count = 0;
01526 
01527       //detection stage
01528       for(unsigned int index = 0 ; index < m.face.size(); ++index )
01529       {
01530         FacePointer f = &(m.face[index]);
01531         float sides[3];
01532         CoordType dummy;
01533 
01534         sides[0] = Distance(f->P(0), f->P(1));
01535         sides[1] = Distance(f->P(1), f->P(2));
01536         sides[2] = Distance(f->P(2), f->P(0));
01537         int i = std::find(sides, sides+3, std::max( std::max(sides[0],sides[1]), sides[2])) - (sides);
01538         if( tri::IsMarked(m,f->V2(i) )) continue;
01539 
01540         if( PSDist(f->P2(i),f->P(i),f->P1(i),dummy)*threshold <= sides[i] )
01541         {
01542           tri::Mark(m,f->V2(i));
01543 
01544           int j = Distance(dummy,f->P(i))<Distance(dummy,f->P1(i))?i:(i+1)%3;
01545           f->P2(i) = f->P(j);  tri::Mark(m,f->V(j));
01546           ++count; ++total;
01547         }
01548       }
01549 
01550 
01551       tri::Clean<MeshType>::RemoveDuplicateVertex(m);
01552       tri::Allocator<MeshType>::CompactFaceVector(m);
01553       tri::Allocator<MeshType>::CompactVertexVector(m);
01554     }
01555     while( repeat && count );
01556 
01557     return total;
01558   }
01559 
01560   static bool SelfIntersections(MeshType &m, std::vector<FaceType*> &ret)
01561   {
01562     RequirePerFaceMark(m);
01563     ret.clear();
01564     int referredBit = FaceType::NewBitFlag();
01565     tri::UpdateFlags<MeshType>::FaceClear(m,referredBit);
01566 
01567     TriMeshGrid gM;
01568     gM.Set(m.face.begin(),m.face.end());
01569 
01570     for(FaceIterator fi=m.face.begin();fi!=m.face.end();++fi) if(!(*fi).IsD())
01571     {
01572       (*fi).SetUserBit(referredBit);
01573       Box3< ScalarType> bbox;
01574       (*fi).GetBBox(bbox);
01575       std::vector<FaceType*> inBox;
01576       vcg::tri::GetInBoxFace(m, gM, bbox,inBox);
01577       bool Intersected=false;
01578       typename std::vector<FaceType*>::iterator fib;
01579       for(fib=inBox.begin();fib!=inBox.end();++fib)
01580       {
01581         if(!(*fib)->IsUserBit(referredBit) && (*fib != &*fi) )
01582           if(Clean<MeshType>::TestFaceFaceIntersection(&*fi,*fib)){
01583             ret.push_back(*fib);
01584             if(!Intersected) {
01585               ret.push_back(&*fi);
01586               Intersected=true;
01587             }
01588           }
01589       }
01590       inBox.clear();
01591     }
01592 
01593     FaceType::DeleteBitFlag(referredBit);
01594     return (ret.size()>0);
01595   }
01596 
01600   static bool IsSizeConsistent(MeshType &m)
01601   {
01602     int DeletedVertNum=0;
01603     for (VertexIterator vi = m.vert.begin(); vi != m.vert.end(); ++vi)
01604       if((*vi).IsD()) DeletedVertNum++;
01605 
01606     int DeletedEdgeNum=0;
01607     for (EdgeIterator ei = m.edge.begin(); ei != m.edge.end(); ++ei)
01608       if((*ei).IsD()) DeletedEdgeNum++;
01609 
01610     int DeletedFaceNum=0;
01611     for (FaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi)
01612       if((*fi).IsD()) DeletedFaceNum++;
01613 
01614     if(size_t(m.vn+DeletedVertNum) != m.vert.size()) return false;
01615     if(size_t(m.en+DeletedEdgeNum) != m.edge.size()) return false;
01616     if(size_t(m.fn+DeletedFaceNum) != m.face.size()) return false;
01617 
01618     return true;
01619   }
01620 
01625   static bool IsFFAdjacencyConsistent(MeshType &m)
01626   {
01627     RequireFFAdjacency(m);
01628 
01629     for (FaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi)
01630       if(!(*fi).IsD())
01631       {
01632         for(int i=0;i<3;++i)
01633           if(!FFCorrectness(*fi, i)) return false;
01634       }
01635     return true;
01636   }
01637 
01641   static bool HasConsistentPerWedgeTexCoord(MeshType &m)
01642   {
01643     tri::RequirePerFaceWedgeTexCoord(m);
01644 
01645     for (FaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi)
01646       if(!(*fi).IsD())
01647       { FaceType &f=(*fi);
01648         if( ! ( (f.WT(0).N() == f.WT(1).N()) && (f.WT(0).N() == (*fi).WT(2).N()) )  )
01649           return false; // all the vertices must have the same index.
01650 
01651         if((*fi).WT(0).N() <0) return false; // no undefined texture should be allowed
01652       }
01653     return true;
01654   }
01655 
01659   static bool HasZeroTexCoordFace(MeshType &m)
01660   {
01661     tri::RequirePerFaceWedgeTexCoord(m);
01662 
01663     for (FaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi)
01664       if(!(*fi).IsD())
01665       {
01666         if( (*fi).WT(0).P() == (*fi).WT(1).P() && (*fi).WT(0).P() == (*fi).WT(2).P() ) return false;
01667       }
01668     return true;
01669   }
01670 
01671 
01679   static        bool TestFaceFaceIntersection(FaceType *f0,FaceType *f1)
01680   {
01681     assert(f0!=f1);
01682     int sv = face::CountSharedVertex(f0,f1);
01683     if(sv==3) return true;
01684     if(sv==0) return (vcg::IntersectionTriangleTriangle<FaceType>((*f0),(*f1)));
01685     //  if the faces share only a vertex, the opposite edge (as a segment) is tested against the face
01686     //  to avoid degenerate cases where the two triangles have the opposite edge on a common plane
01687     //  we offset the segment to test toward the shared vertex
01688     if(sv==1)
01689     {
01690       int i0,i1; ScalarType a,b;
01691       face::FindSharedVertex(f0,f1,i0,i1);
01692       CoordType shP = f0->V(i0)->P()*0.5;
01693       if(vcg::IntersectionSegmentTriangle(Segment3<ScalarType>((*f0).V1(i0)->P()*0.5+shP,(*f0).V2(i0)->P()*0.5+shP), *f1, a, b) )
01694       {
01695         // a,b are the param coords of the intersection point of the segment.
01696         if(a+b>=1 || a<=EPSIL || b<=EPSIL ) return false;
01697         return true;
01698       }
01699       if(vcg::IntersectionSegmentTriangle(Segment3<ScalarType>((*f1).V1(i1)->P()*0.5+shP,(*f1).V2(i1)->P()*0.5+shP), *f0, a, b) )
01700       {
01701         // a,b are the param coords of the intersection point of the segment.
01702         if(a+b>=1 || a<=EPSIL || b<=EPSIL ) return false;
01703         return true;
01704       }
01705 
01706     }
01707     return false;
01708   }
01709 
01710 
01711 
01715   static int MergeCloseVertex(MeshType &m, const ScalarType radius)
01716   {
01717     int mergedCnt=0;
01718     mergedCnt = ClusterVertex(m,radius);
01719     RemoveDuplicateVertex(m,true);
01720     return mergedCnt;
01721   }
01722 
01723   static int ClusterVertex(MeshType &m, const ScalarType radius)
01724   {
01725     if(m.vn==0) return 0;
01726     // some spatial indexing structure does not work well with deleted vertices...
01727     tri::Allocator<MeshType>::CompactVertexVector(m);
01728     typedef vcg::SpatialHashTable<VertexType, ScalarType> SampleSHT;
01729     SampleSHT sht;
01730     tri::EmptyTMark<MeshType> markerFunctor;
01731     std::vector<VertexType*> closests;
01732     int mergedCnt=0;
01733     sht.Set(m.vert.begin(), m.vert.end());
01734     UpdateFlags<MeshType>::VertexClearV(m);
01735     for(VertexIterator viv = m.vert.begin(); viv!= m.vert.end(); ++viv)
01736       if(!(*viv).IsD() && !(*viv).IsV())
01737       {
01738         (*viv).SetV();
01739         Point3<ScalarType> p = viv->cP();
01740         Box3<ScalarType> bb(p-Point3<ScalarType>(radius,radius,radius),p+Point3<ScalarType>(radius,radius,radius));
01741         GridGetInBox(sht, markerFunctor, bb, closests);
01742         // qDebug("Vertex %i has %i closest", &*viv - &*m.vert.begin(),closests.size());
01743         for(size_t i=0; i<closests.size(); ++i)
01744         {
01745           ScalarType dist = Distance(p,closests[i]->cP());
01746           if(dist < radius && !closests[i]->IsV())
01747           {
01748             //                                                                                                  printf("%f %f \n",dist,radius);
01749             mergedCnt++;
01750             closests[i]->SetV();
01751             closests[i]->P()=p;
01752           }
01753         }
01754       }
01755     return mergedCnt;
01756   }
01757 
01758 
01759   static std::pair<int,int>  RemoveSmallConnectedComponentsSize(MeshType &m, int maxCCSize)
01760   {
01761     std::vector< std::pair<int, typename MeshType::FacePointer> > CCV;
01762     int TotalCC=ConnectedComponents(m, CCV);
01763     int DeletedCC=0;
01764 
01765     ConnectedComponentIterator<MeshType> ci;
01766     for(unsigned int i=0;i<CCV.size();++i)
01767     {
01768       std::vector<typename MeshType::FacePointer> FPV;
01769       if(CCV[i].first<maxCCSize)
01770       {
01771         DeletedCC++;
01772         for(ci.start(m,CCV[i].second);!ci.completed();++ci)
01773           FPV.push_back(*ci);
01774 
01775         typename std::vector<typename MeshType::FacePointer>::iterator fpvi;
01776         for(fpvi=FPV.begin(); fpvi!=FPV.end(); ++fpvi)
01777           Allocator<MeshType>::DeleteFace(m,(**fpvi));
01778       }
01779     }
01780     return std::make_pair(TotalCC,DeletedCC);
01781   }
01782 
01783 
01785   // it returns a pair with the number of connected components and the number of deleted ones.
01786   static std::pair<int,int> RemoveSmallConnectedComponentsDiameter(MeshType &m, ScalarType maxDiameter)
01787   {
01788     std::vector< std::pair<int, typename MeshType::FacePointer> > CCV;
01789     int TotalCC=ConnectedComponents(m, CCV);
01790     int DeletedCC=0;
01791     tri::ConnectedComponentIterator<MeshType> ci;
01792     for(unsigned int i=0;i<CCV.size();++i)
01793     {
01794       Box3<ScalarType> bb;
01795       std::vector<typename MeshType::FacePointer> FPV;
01796       for(ci.start(m,CCV[i].second);!ci.completed();++ci)
01797       {
01798         FPV.push_back(*ci);
01799         bb.Add((*ci)->P(0));
01800         bb.Add((*ci)->P(1));
01801         bb.Add((*ci)->P(2));
01802       }
01803       if(bb.Diag()<maxDiameter)
01804       {
01805         DeletedCC++;
01806         typename std::vector<typename MeshType::FacePointer>::iterator fpvi;
01807         for(fpvi=FPV.begin(); fpvi!=FPV.end(); ++fpvi)
01808           tri::Allocator<MeshType>::DeleteFace(m,(**fpvi));
01809       }
01810     }
01811     return std::make_pair(TotalCC,DeletedCC);
01812   }
01813 
01815   // it returns a pair with the number of connected components and the number of deleted ones.
01816   static std::pair<int,int> RemoveHugeConnectedComponentsDiameter(MeshType &m, ScalarType minDiameter)
01817   {
01818     std::vector< std::pair<int, typename MeshType::FacePointer> > CCV;
01819     int TotalCC=ConnectedComponents(m, CCV);
01820     int DeletedCC=0;
01821     tri::ConnectedComponentIterator<MeshType> ci;
01822     for(unsigned int i=0;i<CCV.size();++i)
01823     {
01824       Box3f bb;
01825       std::vector<typename MeshType::FacePointer> FPV;
01826       for(ci.start(m,CCV[i].second);!ci.completed();++ci)
01827       {
01828         FPV.push_back(*ci);
01829         bb.Add((*ci)->P(0));
01830         bb.Add((*ci)->P(1));
01831         bb.Add((*ci)->P(2));
01832       }
01833       if(bb.Diag()>minDiameter)
01834       {
01835         DeletedCC++;
01836         typename std::vector<typename MeshType::FacePointer>::iterator fpvi;
01837         for(fpvi=FPV.begin(); fpvi!=FPV.end(); ++fpvi)
01838           tri::Allocator<MeshType>::DeleteFace(m,(**fpvi));
01839       }
01840     }
01841     return std::make_pair(TotalCC,DeletedCC);
01842   }
01843 
01844 
01845 
01852   static void SelectFoldedFaceFromOneRingFaces(MeshType &m, ScalarType cosThreshold)
01853   {
01854     tri::RequireVFAdjacency(m);
01855     tri::RequirePerFaceNormal(m);
01856     tri::RequirePerVertexNormal(m);
01857     vcg::tri::UpdateSelection<MeshType>::FaceClear(m);
01858     vcg::tri::UpdateNormal<MeshType>::PerFaceNormalized(m);
01859     vcg::tri::UpdateNormal<MeshType>::PerVertexNormalized(m);
01860     vcg::tri::UpdateTopology<MeshType>::VertexFace(m);
01861     if (cosThreshold > 0)
01862       cosThreshold = 0;
01863 
01864 #pragma omp parallel for schedule(dynamic, 10)
01865     for (int i = 0; i < m.face.size(); i++)
01866     {
01867       std::vector<typename MeshType::VertexPointer> nearVertex;
01868       std::vector<typename MeshType::CoordType> point;
01869       typename MeshType::FacePointer f = &m.face[i];
01870       for (int j = 0; j < 3; j++)
01871       {
01872         std::vector<typename MeshType::VertexPointer> temp;
01873         vcg::face::VVStarVF<typename MeshType::FaceType>(f->V(j), temp);
01874               typename std::vector<typename MeshType::VertexPointer>::iterator iter = temp.begin();
01875         for (; iter != temp.end(); iter++)
01876         {
01877           if ((*iter) != f->V1(j) && (*iter) != f->V2(j))
01878           {
01879             nearVertex.push_back((*iter));
01880             point.push_back((*iter)->P());
01881           }
01882         }
01883         nearVertex.push_back(f->V(j));
01884         point.push_back(f->P(j));
01885       }
01886 
01887       if (point.size() > 3)
01888       {
01889         vcg::Plane3<typename MeshType::ScalarType> plane;
01890         vcg::FitPlaneToPointSet(point, plane);
01891         float avgDot = 0;
01892         for (int j = 0; j < nearVertex.size(); j++)
01893           avgDot += plane.Direction().dot(nearVertex[j]->N());
01894         avgDot /= nearVertex.size();
01895         typename MeshType::VertexType::NormalType normal;
01896         if (avgDot < 0)
01897           normal = -plane.Direction();
01898         else
01899           normal = plane.Direction();
01900         if (normal.dot(f->N()) < cosThreshold)
01901           f->SetS();
01902       }
01903     }
01904   }
01905 
01906 }; // end class
01909 } //End Namespace Tri
01910 } // End Namespace vcg
01911 #endif


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