hole.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 #ifndef __VCG_TRI_UPDATE_HOLE
00024 #define __VCG_TRI_UPDATE_HOLE
00025 
00026 #include <vcg/complex/algorithms/clean.h>
00027 
00028 // This file contains three Ear Classes
00029 // - TrivialEar
00030 // - MinimumWeightEar
00031 // - SelfIntersectionEar
00032 // and a static class Hole for filling holes that is templated on the ear class
00033 
00034 
00035 
00036 namespace vcg {
00037     namespace tri {
00038 
00039     /*
00040     An ear is identified by TWO pos.
00041     The Three vertexes of an Ear are:
00042     e0.VFlip().v
00043     e0.v
00044     e1.v
00045     Invariants:
00046       e1 == e0.NextB();
00047       e1.FlipV() == e0;
00048 
00049     Situazioni ear non manifold, e degeneri (buco triangolare)
00050 
00051     T  XXXXXXXXXXXXX    A        /XXXXX        B      en/XXXXX
00052     /XXXXXXXXXXXXXXX            /XXXXXX                /XXXXXX
00053     XXXXXXep==en XXX     ep\   /en XXXX               /e1 XXXX
00054     XXXXXX ----/| XX   ------ ----/| XX       ------ ----/|XXX
00055     XXXXXX|   /e1 XX   XXXXXX|   /e1 XX       XXXXXX|  o/e0 XX
00056     XXXXXX|  /XXXXXX   XXXXXX|  /XXXXXX       XXXXXX|  /XXXXXX
00057     XXX e0|o/XXXXXXX   XXX e0|o/XXXXXXX       XXX ep| /XXXXXXX
00058     XXX  \|/XXXXXXXX   XXX  \|/XXXXXXXX       XXX  \|/XXXXXXXX
00059     XXXXXXXXXXXXXXXX   XXXXXXXXXXXXXXXX       XXXXXXXXXXXXXXXX
00060     */
00061 template<class MESH> class TrivialEar
00062 {
00063 public:
00064   typedef typename MESH::FaceType FaceType;
00065   typedef typename MESH::FacePointer FacePointer;
00066   typedef typename MESH::VertexPointer VertexPointer;
00067   typedef typename face::Pos<FaceType>    PosType;
00068   typedef typename MESH::ScalarType ScalarType;
00069   typedef typename MESH::CoordType CoordType;
00070 
00071   PosType e0;
00072   PosType e1;
00073   CoordType n; // the normal of the face defined by the ear
00074   const char * Dump() {return 0;}
00075   // The following members are useful to consider the Ear as a generic <triangle>
00076   // with p0 the 'center' of the ear.
00077   const CoordType &cP(int i) const {return P(i);}
00078   const CoordType &P(int i) const {
00079     switch(i) {
00080     case 0 : return e0.v->P();
00081     case 1 : return e1.v->P();
00082     case 2 : return e0.VFlip()->P();
00083     default: assert(0);
00084     }
00085     return e0.v->P();
00086   }
00087 
00088   ScalarType quality;
00089   ScalarType angleRad;
00090   TrivialEar(){}
00091   TrivialEar(const PosType & ep)
00092   {
00093     e0=ep;
00094     assert(e0.IsBorder());
00095     e1=e0;
00096     e1.NextB();
00097     n=TriangleNormal<TrivialEar>(*this);
00098     ComputeQuality();
00099     ComputeAngle();
00100   }
00101 
00103   // it tries to make the computation in a precision safe way.
00104   // the angle computation takes into account the case of reversed ears
00105   void ComputeAngle()
00106   {
00107     angleRad=Angle(cP(2)-cP(0), cP(1)-cP(0));
00108     ScalarType flipAngle = n.dot(e0.v->N());
00109     if(flipAngle<0)             angleRad = (2.0 *(ScalarType)M_PI) - angleRad;
00110   }
00111 
00112   virtual inline bool operator < ( const TrivialEar & c ) const { return quality <  c.quality; }
00113 
00114   bool IsNull(){return e0.IsNull() || e1.IsNull();}
00115   void SetNull(){e0.SetNull();e1.SetNull();}
00116   virtual       void ComputeQuality() { quality = QualityFace(*this) ; }
00117   bool IsUpToDate()     {return ( e0.IsBorder() && e1.IsBorder());}
00118   // An ear is degenerated if both of its two endpoints are non manifold.
00119   bool IsDegen(const int nonManifoldBit)
00120   {
00121     if(e0.VFlip()->IsUserBit(nonManifoldBit) && e1.V()->IsUserBit(nonManifoldBit))
00122       return true;
00123     else return false;
00124   }
00125   bool IsConcave() const {return(angleRad > (float)M_PI);}
00126 
00127   // When you close an ear you have to check that the newly added triangle does not create non manifold situations
00128   // This can happen if the new edge already exists in the mesh.
00129   // We test that looping around one extreme of the ear we do not find the other vertex
00130   bool CheckManifoldAfterEarClose()
00131   {
00132     PosType pp = e1;
00133     VertexPointer otherV =  e0.VFlip();
00134     assert(pp.IsBorder());
00135     do
00136     {
00137       pp.FlipE();
00138       pp.FlipF();
00139       if(pp.VFlip()==otherV) return false;
00140     }
00141     while(!pp.IsBorder());
00142     return true;
00143   }
00144 
00145   virtual bool Close(PosType &np0, PosType &np1, FaceType * f)
00146   {
00147     // simple topological check
00148     if(e0.f==e1.f) {
00149       //printf("Avoided bad ear");
00150       return false;
00151     }
00152 
00153     //usato per generare una delle due nuove orecchie.
00154     PosType     ep=e0; ep.FlipV(); ep.NextB(); ep.FlipV(); // he precedente a e0
00155     PosType     en=e1; en.NextB();                                                                                               // he successivo a e1
00156     if(ep!=en)
00157       if(!CheckManifoldAfterEarClose()) return false;
00158 
00159     (*f).V(0) = e0.VFlip();
00160     (*f).V(1) = e0.v;
00161     (*f).V(2) = e1.v;
00162     f->N() = TriangleNormal(*f).Normalize();
00163 
00164     face::FFAttachManifold(f,0,e0.f,e0.z);
00165     face::FFAttachManifold(f,1,e1.f,e1.z);
00166     face::FFSetBorder(f,2);
00167 
00168     // caso ear degenere per buco triangolare
00169     if(ep==en)
00170     {
00171       //printf("Closing the last triangle");
00172       face::FFAttachManifold(f,2,en.f,en.z);
00173       np0.SetNull();
00174       np1.SetNull();
00175     }
00176     // Caso ear non manifold a
00177     else if(ep.v==en.v)
00178     {
00179       //printf("Ear Non manif A\n");
00180       PosType   enold=en;
00181       en.NextB();
00182       face::FFAttachManifold(f,2,enold.f,enold.z);
00183       np0=ep;
00184       np1=en;
00185     }
00186     // Caso ear non manifold b
00187     else if(ep.VFlip()==e1.v)
00188     {
00189       //printf("Ear Non manif B\n");
00190       PosType   epold=ep;
00191       ep.FlipV(); ep.NextB(); ep.FlipV();
00192       face::FFAttachManifold(f,2,epold.f,epold.z);
00193       np0=ep;  // assign the two new
00194       np1=en;  // pos that denote the ears
00195     }
00196     else // caso standard // Now compute the new ears;
00197     {
00198       np0=ep;
00199       np1=PosType(f,2,e1.v);
00200     }
00201 
00202     return true;
00203   }
00204 
00205 };  // end TrivialEar Class
00206 
00207 //Ear with FillHoleMinimumWeight's quality policy
00208 template<class MESH> class MinimumWeightEar : public TrivialEar<MESH>
00209 {
00210 public:
00211   static float &DiedralWeight() { static float _dw=0.1; return _dw;}
00212   typedef TrivialEar<MESH> TE;
00213   typename MESH::ScalarType dihedralRad;
00214   typename MESH::ScalarType aspectRatio;
00215   const char * Dump() {
00216     static char buf[200];
00217     if(this->IsConcave()) sprintf(buf,"Dihedral -(deg) %6.2f Quality %6.2f\n",math::ToDeg(dihedralRad),aspectRatio);
00218     else sprintf(buf,"Dihedral  (deg) %6.2f Quality %6.2f\n",math::ToDeg(dihedralRad),aspectRatio);
00219     return buf;
00220   }
00221 
00222   MinimumWeightEar(){}
00223   MinimumWeightEar(const typename face::Pos<typename MESH::FaceType>& ep) : TrivialEar<MESH>(ep)
00224   {
00225     ComputeQuality();
00226   }
00227 
00228   // In the heap, by default, we retrieve the LARGEST value,
00229   // so if we need the ear with minimal dihedral angle, we must reverse the sign of the comparison.
00230   // The concave elements must be all in the end of the heap, sorted accordingly,
00231   // So if only one of the two ear is Concave that one is always the minimum one.
00232   // the pow function is here just to give a way to play with different weighting schemas, balancing in a different way
00233 
00234   virtual inline bool operator <  ( const MinimumWeightEar & c ) const
00235   {
00236     if(TE::IsConcave()  && ! c.IsConcave() ) return true;
00237     if(!TE::IsConcave()  &&  c.IsConcave() ) return false;
00238 
00239     return aspectRatio - (dihedralRad/M_PI)*DiedralWeight() < c.aspectRatio -(c.dihedralRad/M_PI)*DiedralWeight();
00240 
00241 //      return (pow((float)dihedralRad,(float)DiedralWeight())/aspectRatio) > (pow((float)c.dihedralRad,(float)DiedralWeight())/c.aspectRatio);
00242   }
00243 
00244   // the real core of the whole hole filling strategy.
00245   virtual void ComputeQuality()
00246   {
00247     //compute quality by (dihedral ancgle, area/sum(edge^2) )
00248     typename MESH::CoordType  n1=TE::e0.FFlip()->cN();
00249     typename MESH::CoordType n2=TE::e1.FFlip()->cN();
00250 
00251     dihedralRad = std::max(Angle(TE::n,n1),Angle(TE::n,n2));
00252     aspectRatio = QualityFace(*this);
00253   }
00254 
00255 };  // end class MinimumWeightEar
00256 
00257 
00258 //Ear for selfintersection algorithm
00259 template<class MESH> class SelfIntersectionEar : public MinimumWeightEar<MESH>
00260 {
00261 public:
00262   typedef typename MESH::FaceType FaceType;
00263   typedef typename MESH::FacePointer FacePointer;
00264   typedef typename face::Pos<FaceType>    PosType;
00265   typedef typename MESH::ScalarType ScalarType;
00266   typedef typename MESH::CoordType CoordType;
00267 
00268   static std::vector<FacePointer> &AdjacencyRing()
00269   {
00270     static std::vector<FacePointer> ar;
00271     return ar;
00272   }
00273 
00274   SelfIntersectionEar(){}
00275   SelfIntersectionEar(const PosType & ep):MinimumWeightEar<MESH>(ep){}
00276 
00277   virtual bool Close(PosType &np0, PosType &np1, FacePointer f)
00278   {
00279     PosType     ep=this->e0; ep.FlipV(); ep.NextB(); ep.FlipV(); // he precedente a e0
00280     PosType     en=this->e1; en.NextB();        // he successivo a e1
00281 //    bool triangularHole = false;
00282 //    if(en==ep || en-) triangularHole=true;
00283 
00284 
00285     //costruisco la faccia e poi testo, o copio o butto via.
00286     (*f).V(0) = this->e0.VFlip();
00287     (*f).V(1) = this->e0.v;
00288     (*f).V(2) = this->e1.v;
00289     face::FFSetBorder(f,0);
00290     face::FFSetBorder(f,1);
00291     face::FFSetBorder(f,2);
00292 
00293     typename std::vector< FacePointer >::iterator it;
00294     for(it = this->AdjacencyRing().begin();it!= this->AdjacencyRing().end();++it)
00295     {
00296       if(!(*it)->IsD())
00297       {
00298         if(     tri::Clean<MESH>::TestFaceFaceIntersection(f,*it))
00299           return false;
00300         // We must also check that the newly created face does not have any edge in common with other existing surrounding faces
00301         // Only the two faces of the ear can share an edge with the new face
00302         if(face::CountSharedVertex(f,*it)==2)
00303         {
00304           int e0,e1;
00305           bool ret=face::FindSharedEdge(f,*it,e0,e1);
00306           assert(ret);
00307           if(!face::IsBorder(**it,e1))
00308             return false;
00309         }
00310       }
00311     }
00312     bool ret=TrivialEar<MESH>::Close(np0,np1,f);
00313     if(ret) AdjacencyRing().push_back(f);
00314     return ret;
00315   }
00316 }; // end class SelfIntersectionEar
00317 
00318 // Funzione principale per chiudier un buco in maniera topologicamente corretta.
00319 // Gestisce situazioni non manifold ragionevoli
00320 // (tutte eccetto quelle piu' di 2 facce per 1 edge).
00321 // Controlla che non si generino nuove situazioni non manifold chiudendo orecchie
00322 // che sottendono un edge che gia'esiste.
00323 
00324 template <class MESH>
00325 class Hole
00326 {
00327 public:
00328             typedef typename MESH::VertexType                           VertexType;
00329             typedef typename MESH::VertexPointer                VertexPointer;
00330             typedef     typename MESH::ScalarType                               ScalarType;
00331             typedef typename MESH::FaceType                                     FaceType;
00332             typedef typename MESH::FacePointer                  FacePointer;
00333             typedef typename MESH::FaceIterator                 FaceIterator;
00334             typedef typename MESH::CoordType                            CoordType;
00335       typedef typename vcg::Box3<ScalarType>  Box3Type;
00336             typedef typename face::Pos<FaceType>    PosType;
00337 
00338 public:
00339 
00340         class Info
00341         {
00342         public:
00343             Info(){}
00344             Info(PosType const &pHole, int  const pHoleSize, Box3<ScalarType> &pHoleBB)
00345             {
00346                 p=pHole;
00347                 size=pHoleSize;
00348                 bb=pHoleBB;
00349             }
00350 
00351             PosType p;
00352             int size;
00353             Box3Type  bb;
00354 
00355             bool operator <  (const  Info & hh) const {return size <  hh.size;}
00356 
00357             ScalarType Perimeter()
00358             {
00359                 ScalarType sum=0;
00360                 PosType ip = p;
00361                 do
00362                 {
00363                     sum+=Distance(ip.v->cP(),ip.VFlip()->cP());
00364                     ip.NextB();
00365                 }
00366                 while (ip != p);
00367                 return sum;
00368             }
00369 
00370       // Support function to test the validity of a single hole loop
00371       // for now it test only that all the edges are border;
00372       // The real test should check if all non manifold vertices
00373       // are touched only by edges belonging to this hole loop.
00374       bool CheckValidity()
00375       {
00376        if(!p.IsBorder())
00377          return false;
00378        PosType ip=p;ip.NextB();
00379        for(;ip!=p;ip.NextB())
00380        {
00381           if(!ip.IsBorder())
00382             return false;
00383        }
00384        return true;
00385       }
00386         };
00387 
00388 
00389         class EdgeToBeAvoided
00390         {
00391           VertexPointer v0,v1;
00392           EdgeToBeAvoided(VertexPointer _v0, VertexPointer _v1):v0(_v0),v1(_v1)
00393           {
00394             if(v0>v1) swap(v0,v1);
00395           }
00396           bool operator < (const EdgeToBeAvoided &e)
00397           {
00398             if(this->v0!=e.v0) return this->v0<e.v0;
00399             return this->v1<e.v1;
00400           }
00401         };
00406 
00407 template<class EAR>
00408     static void FillHoleEar(MESH &m, // The mesh to be filled
00409                             Info &h, // the particular hole to be filled
00410                             std::vector<FacePointer *> &facePointersToBeUpdated)
00411     {
00412       //Aggiungo le facce e aggiorno il puntatore alla faccia!
00413       FaceIterator f = tri::Allocator<MESH>::AddFaces(m, h.size-2, facePointersToBeUpdated);
00414 
00415       assert(h.p.f >= &*m.face.begin());
00416       assert(h.p.f <= &m.face.back());
00417       assert(h.p.IsBorder());
00418 
00419       std::vector< EAR > EarHeap;
00420       EarHeap.reserve(h.size);
00421       int nmBit= VertexType::NewBitFlag(); // non manifoldness bit
00422 
00423       //First loops around the hole to mark non manifold vertices.
00424       PosType ip = h.p;   // Pos iterator
00425       do{
00426         ip.V()->ClearUserBit(nmBit);
00427         ip.V()->ClearV();
00428         ip.NextB();
00429       } while(ip!=h.p);
00430 
00431       ip = h.p;   // Re init the pos iterator for another loop (useless if everithing is ok!!)
00432       do{
00433         if(!ip.V()->IsV())
00434           ip.V()->SetV();   // All the vertexes that are visited more than once are non manifold
00435         else ip.V()->SetUserBit(nmBit);
00436         ip.NextB();
00437       } while(ip!=h.p);
00438 
00439       PosType fp = h.p;
00440       do{
00441         EAR appEar = EAR(fp);
00442         EarHeap.push_back( appEar );
00443         //printf("Adding ear %s ",app.Dump());
00444         fp.NextB();
00445         assert(fp.IsBorder());
00446       }while(fp!=h.p);
00447 
00448       int cnt=h.size;
00449 
00450       make_heap(EarHeap.begin(), EarHeap.end());
00451 
00452       //finche' il buco non e' chiuso o non ci sono piu' orecchie da analizzare.
00453       while( cnt > 2 && !EarHeap.empty() )
00454       {
00455         //printf("Front of the heap is %s", H.front().Dump());
00456         pop_heap(EarHeap.begin(), EarHeap.end());        // retrieve the MAXIMUM value and put in the back;
00457         EAR BestEar=EarHeap.back();
00458         EarHeap.pop_back();
00459 
00460         if(BestEar.IsUpToDate() && !BestEar.IsDegen(nmBit))
00461         {
00462           if((*f).HasPolyInfo()) (*f).Alloc(3);
00463           PosType ep0,ep1;
00464           if(BestEar.Close(ep0,ep1,&*f))
00465           {
00466             if(!ep0.IsNull()){
00467               EarHeap.push_back(EAR(ep0));
00468               push_heap( EarHeap.begin(), EarHeap.end());
00469             }
00470             if(!ep1.IsNull()){
00471               EarHeap.push_back(EAR(ep1));
00472               push_heap( EarHeap.begin(), EarHeap.end());
00473             }
00474             --cnt;
00475             ++f;
00476           }
00477         }//is update()
00478       }//fine del while principale.
00479 
00480       while(f!=m.face.end()){
00481         tri::Allocator<MESH>::DeleteFace(m,*f);
00482         f++;
00483       }
00484 
00485       VertexType::DeleteBitFlag(nmBit); // non manifoldness bit
00486     }
00487 
00488     template<class EAR>
00489     static int EarCuttingFill(MESH &m, int sizeHole, bool Selected = false, CallBackPos *cb=0)
00490     {
00491       std::vector< Info > vinfo;
00492       GetInfo(m, Selected,vinfo);
00493 
00494       typename std::vector<Info >::iterator ith;
00495       int indCb=0;
00496       int holeCnt=0;
00497       std::vector<FacePointer *> facePtrToBeUpdated;
00498       for(ith = vinfo.begin(); ith!= vinfo.end(); ++ith)
00499         facePtrToBeUpdated.push_back( &(*ith).p.f );
00500 
00501       for(ith = vinfo.begin(); ith!= vinfo.end(); ++ith)
00502       {
00503         indCb++;
00504         if(cb) (*cb)(indCb*10/vinfo.size(),"Closing Holes");
00505         if((*ith).size < sizeHole){
00506           holeCnt++;
00507           FillHoleEar< EAR >(m, *ith,facePtrToBeUpdated);
00508         }
00509       }
00510       return holeCnt;
00511     }
00512 
00516 
00517 template<class EAR>
00518     static int EarCuttingIntersectionFill(MESH &m, const int maxSizeHole, bool Selected, CallBackPos *cb=0)
00519     {
00520       std::vector<Info > vinfo;
00521       GetInfo(m, Selected,vinfo);
00522       typename std::vector<Info>::iterator ith;
00523 
00524       // collect the face pointer that has to be updated by the various addfaces
00525       std::vector<FacePointer *> vfpOrig;
00526       for(ith = vinfo.begin(); ith!= vinfo.end(); ++ith)
00527         vfpOrig.push_back( &(*ith).p.f );
00528 
00529       int indCb=0;
00530       int holeCnt=0;
00531       for(ith = vinfo.begin(); ith!= vinfo.end(); ++ith)
00532       {
00533         indCb++;
00534         if(cb) (*cb)(indCb*10/vinfo.size(),"Closing Holes");
00535         if((*ith).size < maxSizeHole){
00536           std::vector<FacePointer *> facePtrToBeUpdated;
00537           holeCnt++;
00538           facePtrToBeUpdated=vfpOrig;
00539           EAR::AdjacencyRing().clear();
00540           //Loops around the hole to collect the faces that have to be tested for intersection.
00541           PosType ip = (*ith).p;
00542           do
00543           {
00544             PosType inp = ip;
00545             do
00546             {
00547               inp.FlipE();
00548               inp.FlipF();
00549               EAR::AdjacencyRing().push_back(inp.f);
00550             } while(!inp.IsBorder());
00551             ip.NextB();
00552           }while(ip != (*ith).p);
00553 
00554           typename std::vector<FacePointer>::iterator fpi;
00555           for(fpi=EAR::AdjacencyRing().begin();fpi!=EAR::AdjacencyRing().end();++fpi)
00556             facePtrToBeUpdated.push_back( &*fpi );
00557 
00558           FillHoleEar<EAR >(m, *ith,facePtrToBeUpdated);
00559           EAR::AdjacencyRing().clear();
00560         }
00561       }
00562       return holeCnt;
00563     }
00564 
00565 
00566 
00567     static void GetInfo(MESH &m, bool Selected ,std::vector<Info >& VHI)
00568         {
00569       tri::UpdateFlags<MESH>::FaceClearV(m);
00570             for(FaceIterator fi = m.face.begin(); fi!=m.face.end(); ++fi)
00571             {
00572                 if(!(*fi).IsD())
00573                 {
00574                     if(Selected && !(*fi).IsS())
00575                     {
00576                         //se devo considerare solo i triangoli selezionati e
00577                         //quello che sto considerando non lo e' lo marchio e vado avanti
00578                       (*fi).SetV();
00579                     }
00580                     else
00581                     {
00582                             for(int j =0; j<3 ; ++j)
00583                             {
00584                               if( face::IsBorder(*fi,j) && !(*fi).IsV() )
00585                                 {//Trovato una faccia di bordo non ancora visitata.
00586                                     (*fi).SetV();
00587                                 PosType sp(&*fi, j, (*fi).V(j));
00588                                     PosType fp=sp;
00589                                     int holesize=0;
00590 
00591                                     Box3Type hbox;
00592                                     hbox.Add(sp.v->cP());
00593                   //printf("Looping %i : (face %i edge %i) \n", VHI.size(),sp.f-&*m.face.begin(),sp.z);
00594                                     sp.f->SetV();
00595                                     do
00596                                     {
00597                                         sp.f->SetV();
00598                                         hbox.Add(sp.v->cP());
00599                                         ++holesize;
00600                                         sp.NextB();
00601                                         sp.f->SetV();
00602                                         assert(sp.IsBorder());
00603                                     }while(sp != fp);
00604 
00605                                     //ho recuperato l'inofrmazione su tutto il buco
00606                                     VHI.push_back( Info(sp,holesize,hbox) );
00607                                 }
00608                             }//for sugli edge del triangolo
00609                     }//S & !S
00610                 }
00611             }//for principale!!!
00612         }
00613 
00614         //Minimum Weight Algorithm
00615         class Weight
00616         {
00617         public:
00618 
00619             Weight() { ang = 180; ar = FLT_MAX ;}
00620             Weight( float An, float Ar ) { ang=An ; ar= Ar;}
00621             ~Weight() {}
00622 
00623             float angle() const { return ang; }
00624             float area()  const { return ar; }
00625 
00626             Weight operator+( const Weight & other ) const {return Weight( std::max( angle(), other.angle() ), area() + other.area());}
00627             bool operator<( const Weight & rhs ) const {return ( angle() < rhs.angle() ||(angle() == rhs.angle() && area() < rhs.area()));      }
00628 
00629         private:
00630             float ang;
00631             float ar;
00632         };
00633 
00634         /*
00635     \ /        \/
00636    v1*---------*v4
00637     / \       /
00638    /   \     /
00639   /       \   /
00640  /ear      \ /
00641 *---------*-
00642 | v3      v2\
00643 */
00644 
00645     static float ComputeDihedralAngle(CoordType  p1,CoordType  p2,CoordType  p3,CoordType  p4)
00646         {
00647             CoordType  n1 = Normal(p1,p3,p2);
00648             CoordType  n2 = Normal(p1,p2,p4);
00649             return  math::ToDeg(AngleN(n1,n2));
00650         }
00651 
00652   static bool existEdge(PosType pi,PosType pf)
00653         {
00654             PosType app = pi;
00655             PosType appF = pi;
00656             PosType tmp;
00657             assert(pi.IsBorder());
00658             appF.NextB();
00659             appF.FlipV();
00660             do
00661             {
00662                 tmp = app;
00663                 tmp.FlipV();
00664                 if(tmp.v == pf.v)
00665                     return true;
00666                 app.FlipE();
00667                 app.FlipF();
00668 
00669                 if(app == pi)return false;
00670             }while(app != appF);
00671             return false;
00672         }
00673 
00674     static Weight computeWeight( int i, int j, int k,
00675             std::vector<PosType > pv,
00676             std::vector< std::vector< int > >  v)
00677         {
00678             PosType pi = pv[i];
00679             PosType pj = pv[j];
00680             PosType pk = pv[k];
00681 
00682             //test complex edge
00683             if(existEdge(pi,pj) || existEdge(pj,pk)|| existEdge(pk,pi)  )
00684             {
00685                 return Weight();
00686             }
00687             // Return an infinite weight, if one of the neighboring patches
00688             // could not be created.
00689             if(v[i][j] == -1){return Weight();}
00690             if(v[j][k] == -1){return Weight();}
00691 
00692             //calcolo il massimo angolo diedrale, se esiste.
00693             float angle = 0.0f;
00694             PosType px;
00695             if(i + 1 == j)
00696             {
00697                 px = pj;
00698                 px.FlipE(); px.FlipV();
00699                 angle = std::max<float>(angle , ComputeDihedralAngle(pi.v->P(), pj.v->P(), pk.v->P(), px.v->P())        );
00700             }
00701             else
00702             {
00703                 angle = std::max<float>( angle, ComputeDihedralAngle(pi.v->P(),pj.v->P(), pk.v->P(), pv[ v[i][j] ].v->P()));
00704             }
00705 
00706             if(j + 1 == k)
00707             {
00708                 px = pk;
00709                 px.FlipE(); px.FlipV();
00710                 angle = std::max<float>(angle , ComputeDihedralAngle(pj.v->P(), pk.v->P(), pi.v->P(), px.v->P())        );
00711             }
00712             else
00713             {
00714                 angle = std::max<float>( angle, ComputeDihedralAngle(pj.v->P(),pk.v->P(), pi.v->P(), pv[ v[j][k] ].v->P()));
00715             }
00716 
00717             if( i == 0 && k == (int)v.size() - 1)
00718             {
00719                 px = pi;
00720                 px.FlipE(); px.FlipV();
00721                 angle = std::max<float>(angle , ComputeDihedralAngle(pk.v->P(), pi.v->P(),  pj.v->P(),px.v->P() )       );
00722             }
00723 
00724             ScalarType area = ( (pj.v->P() - pi.v->P()) ^ (pk.v->P() - pi.v->P()) ).Norm() * 0.5;
00725 
00726             return Weight(angle, area);
00727         }
00728 
00729     static void calculateMinimumWeightTriangulation(MESH &m, FaceIterator f,std::vector<PosType > vv )
00730         {
00731             std::vector< std::vector< Weight > > w; //matrice dei pesi minimali di ogni orecchio preso in conzideraione
00732             std::vector< std::vector< int    > > vi;//memorizza l'indice del terzo vertice del triangolo
00733 
00734             //hole size
00735             int nv = vv.size();
00736 
00737             w.clear();
00738             w.resize( nv, std::vector<Weight>( nv, Weight() ) );
00739 
00740             vi.resize( nv, std::vector<int>( nv, 0 ) );
00741 
00742             //inizializzo tutti i pesi possibili del buco
00743             for ( int i = 0; i < nv-1; ++i )
00744                 w[i][i+1] = Weight( 0, 0 );
00745 
00746             //doppio ciclo for per calcolare di tutti i possibili triangoli i loro pesi.
00747             for ( int j = 2; j < nv; ++j )
00748             {
00749                 for ( int i = 0; i + j < nv; ++i )
00750                 {
00751                     //per ogni triangolazione mi mantengo il minimo valore del peso tra i triangoli possibili
00752                     Weight minval;
00753 
00754                     //indice del vertice che da il peso minimo nella triangolazione corrente
00755                     int minIndex = -1;
00756 
00757                     //ciclo tra i vertici in mezzo a i due prefissati
00758                     for ( int m = i + 1; m < i + j; ++m )
00759                     {
00760                         Weight a = w[i][m];
00761                         Weight b = w[m][i+j];
00762                         Weight newval =  a + b + computeWeight( i, m, i+j, vv, vi);
00763                         if ( newval < minval )
00764                         {
00765                             minval = newval;
00766                             minIndex = m;
00767                         }
00768                     }
00769                     w[i][i+j] = minval;
00770                     vi[i][i+j] = minIndex;
00771                 }
00772             }
00773 
00774             //Triangulate
00775             int i, j;
00776             i=0; j=nv-1;
00777 
00778             triangulate(m,f, i, j, vi, vv);
00779 
00780             while(f!=m.face.end())
00781             {
00782                 (*f).SetD();
00783                 ++f;
00784                 m.fn--;
00785             }
00786         }
00787 
00788 
00789     static void triangulate(MESH &m, FaceIterator &f,int i, int j,
00790                           std::vector< std::vector<int> > vi, std::vector<PosType > vv)
00791         {
00792             if(i + 1 == j){return;}
00793             if(i==j)return;
00794 
00795             int k = vi[i][j];
00796 
00797             if(k == -1) return;
00798 
00799             //Setto i vertici
00800             f->V(0) = vv[i].v;
00801             f->V(1) = vv[k].v;
00802             f->V(2) = vv[j].v;
00803 
00804             f++;
00805             triangulate(m,f,i,k,vi,vv);
00806             triangulate(m,f,k,j,vi,vv);
00807         }
00808 
00809   static void MinimumWeightFill(MESH &m, int holeSize, bool Selected)
00810         {
00811             std::vector<PosType > vvi;
00812             std::vector<FacePointer * > vfp;
00813 
00814             std::vector<Info > vinfo;
00815             typename std::vector<Info >::iterator VIT;
00816             GetInfo(m, Selected,vinfo);
00817 
00818             for(VIT = vinfo.begin(); VIT != vinfo.end();++VIT)
00819             {
00820                 vvi.push_back(VIT->p);
00821             }
00822 
00823             typename std::vector<PosType >::iterator ith;
00824             typename std::vector<PosType >::iterator ithn;
00825             typename std::vector<VertexPointer >::iterator itf;
00826 
00827             std::vector<PosType > app;
00828             PosType ps;
00829             std::vector<FaceType > tr;
00830             std::vector<VertexPointer > vf;
00831 
00832             for(ith = vvi.begin(); ith!= vvi.end(); ++ith)
00833             {
00834                 tr.clear();
00835                 vf.clear();
00836                 app.clear();
00837                 vfp.clear();
00838 
00839                 ps = *ith;
00840                 getBoundHole(ps,app);
00841 
00842         if(app.size() <= size_t(holeSize) )
00843                 {
00844                     typename std::vector<PosType >::iterator itP;
00845                     std::vector<FacePointer *> vfp;
00846 
00847                     for(ithn = vvi.begin(); ithn!= vvi.end(); ++ithn)
00848                         vfp.push_back(&(ithn->f));
00849 
00850                     for(itP = app.begin (); itP != app.end ();++itP)
00851                         vfp.push_back( &(*itP).f );
00852 
00853                     //aggiungo le facce
00854                     FaceIterator f = tri::Allocator<MESH>::AddFaces(m, (app.size()-2) , vfp);
00855 
00856                     calculateMinimumWeightTriangulation(m,f, app);
00857                 }
00858             }
00859 
00860         }
00861 
00862     static void getBoundHole (PosType sp,std::vector<PosType >&ret)
00863         {
00864             PosType fp = sp;
00865             //take vertex around the hole
00866             do
00867             {
00868                 assert(fp.IsBorder());
00869                 ret.push_back(fp);
00870                 fp.NextB();
00871             }while(sp != fp);
00872         }
00873 
00874 };//close class Hole
00875 
00876 } // end namespace tri
00877 } // end namespace vcg
00878 #endif


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