edge_collapse.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_TETRA_TRI_COLLAPSE
00024 #define __VCG_TETRA_TRI_COLLAPSE
00025 
00026 
00027 #include<vcg/simplex/face/pos.h>
00028 #include<vcg/simplex/face/topology.h>
00029 
00030 namespace vcg{
00031 namespace tri{
00032 
00033 template < class VERTEX_TYPE>
00034 class BasicVertexPair {
00035 public:
00036   inline BasicVertexPair() {}
00037   inline BasicVertexPair( VERTEX_TYPE * v0, VERTEX_TYPE * v1){V(0) = v0; V(1) = v1; }
00038   void Sort() {if(V(0)<V(0)) std::swap(V(0),V(0)); }
00039   VERTEX_TYPE *&V(int i) { return v[i]; }
00040   VERTEX_TYPE *cV(int i) const { return v[i]; }
00041 private:
00042   VERTEX_TYPE *v[2]; // remember that v[0] will be deleted and v[1] will survive (eventually with a new position)
00043 };
00044 
00045 
00053 template <class TRI_MESH_TYPE, class VertexPair>
00054 class EdgeCollapser
00055 {
00056     public:
00058   typedef        TRI_MESH_TYPE TriMeshType;
00060   typedef       typename TriMeshType::FaceType FaceType;
00062     typedef     typename FaceType::VertexType VertexType;
00063   typedef       typename FaceType::VertexPointer VertexPointer;
00065   typedef       typename TriMeshType::VertexIterator VertexIterator;
00067   typedef       typename TriMeshType::FaceIterator FaceIterator;
00069     typedef     typename FaceType::VertexType::CoordType CoordType;
00071   typedef       typename TriMeshType::VertexType::ScalarType ScalarType;
00073   typedef typename TriMeshType::FaceContainer FaceContainer;
00075   typedef typename TriMeshType::VertContainer VertContainer;
00077   //typedef typename TriMeshType::FaceType::EdgeType EdgeType;
00079 //      typedef typename std::vector<EdgeType> EdgeVec;
00081     typedef typename vcg::face::VFIterator<FaceType>  VFI;
00083     typedef typename std::vector<vcg::face::VFIterator<FaceType> > VFIVec;
00084 private:
00085   struct EdgeSet
00086   {
00087      VFIVec av0,av1,av01;
00088      VFIVec & AV0() { return av0;}
00089      VFIVec & AV1() { return av1;}
00090      VFIVec & AV01(){ return av01;}
00091   };
00092 
00093   static void FindSets(VertexPair &p, EdgeSet &es)
00094     {
00095         VertexType * v0 = p.V(0);
00096         VertexType * v1 = p.V(1);
00097 
00098     es.AV0().clear();  // Facce incidenti in v0
00099     es.AV1().clear();  // Facce incidenti in v1
00100     es.AV01().clear(); // Facce incidenti in v0 e v1
00101 
00102         VFI x;
00103 
00104         for( x.f = v0->VFp(), x.z = v0->VFi(); x.f!=0; ++x)
00105         {
00106             int zv1 = -1;
00107 
00108             for(int j=0;j<3;++j)
00109                 if( x.f->V(j)==&*v1 )   {
00110                     zv1 = j;
00111                     break;
00112                 }
00113       if(zv1==-1)       es.AV0().push_back( x ); // la faccia x.f non ha il vertice v1 => e' incidente solo in v0
00114       else                      es.AV01().push_back( x );
00115         }
00116 
00117         for( x.f = v1->VFp(), x.z = v1->VFi(); x.f!=0; ++x )
00118         {
00119             int zv0 = -1;
00120 
00121             for(int j=0;j<3;++j)
00122                 if( x.f->V(j)==&*v0 )   {
00123                     zv0 = j;
00124                     break;
00125                 }
00126       if(zv0==-1)       es.AV1().push_back( x ); // la faccia x.f non ha il vertice v1 => e' incidente solo in v0
00127         }
00128 }
00129 /*
00130     Link Conditions test, as described in
00131 
00132     Topology Preserving Edge Contraction
00133     T. Dey, H. Edelsbrunner,
00134     Pub. Inst. Math. 1999
00135 
00136     Lk (sigma) is the set of all the faces of the cofaces of sigma that are disjoint from sigma
00137 
00138     Lk(v0) inters Lk(v1) == Lk(v0-v1)
00139 
00140     To perform these tests using only the VF adjacency we resort to some virtual counters over
00141     the vertices and the edges, we implement them as std::maps, and we increase these counters
00142     by running over all the faces around each vertex of the collapsing edge.
00143 
00144     At the end (after adding dummy stuff) we should have
00145        2 for vertices not shared
00146        4 for vertices shared
00147        2 for edges shared
00148        1 for edges not shared.
00149 
00150 
00151 */
00152 
00153 public:
00154   static bool LinkConditions(VertexPair &pos)
00155   {
00156     typedef typename vcg::face::VFIterator<FaceType> VFIterator;
00157     // at the end of the loop each vertex must be counted twice
00158     // except for boundary vertex.
00159     std::map<VertexPointer,int> VertCnt;
00160     std::map<std::pair<VertexPointer,VertexPointer>,int> EdgeCnt;
00161 
00162     // the list of the boundary vertexes for the two endpoints
00163     std::vector<VertexPointer> BoundaryVertexVec[2];
00164 
00165     // Collect vertexes and edges of V0 and V1
00166     VFIterator vfi;
00167     for(int i=0;i<2;++i)
00168     {
00169       vfi = VFIterator(pos.V(i));
00170       for( ;!vfi.End();++vfi)
00171       {
00172         ++ VertCnt[vfi.V1()];
00173         ++ VertCnt[vfi.V2()];
00174         if(vfi.V1()<vfi.V2()) ++EdgeCnt[std::make_pair(vfi.V1(),vfi.V2())];
00175                          else ++EdgeCnt[std::make_pair(vfi.V2(),vfi.V1())];
00176       }
00177       // Now a loop to add dummy stuff: add the dummy vertex and two dummy edges
00178       // (and remember to increase the counters for the two boundary vertexes involved)
00179       typename std::map<VertexPointer,int>::iterator vcmit;
00180       for(vcmit=VertCnt.begin();vcmit!=VertCnt.end();++vcmit)
00181       {
00182         if((*vcmit).second==1) // boundary vertexes are counted only once
00183           BoundaryVertexVec[i].push_back((*vcmit).first);
00184       }
00185       if(BoundaryVertexVec[i].size()==2)
00186       { // aha! one of the two vertex of the collapse is on the boundary
00187         // so add dummy vertex and two dummy edges
00188         VertCnt[0]+=2;
00189         ++ EdgeCnt[std::make_pair(VertexPointer(0),BoundaryVertexVec[i][0]) ] ;
00190         ++ EdgeCnt[std::make_pair(VertexPointer(0),BoundaryVertexVec[i][1]) ] ;
00191         // remember to hide the boundaryness of the two boundary vertexes
00192         ++VertCnt[BoundaryVertexVec[i][0]];
00193         ++VertCnt[BoundaryVertexVec[i][1]];
00194       }
00195     }
00196 
00197     // Final loop to find cardinality of Lk( V0-V1 )
00198     // Note that Lk(edge) is only a set of vertices.
00199     std::vector<VertexPointer> LkEdge;
00200 
00201     for( vfi = VFIterator(pos.V(0)); !vfi.End(); ++vfi)
00202     {
00203       if(vfi.V1() == pos.V(1) ) LkEdge.push_back(vfi.V2());
00204       if(vfi.V2() == pos.V(1) ) LkEdge.push_back(vfi.V1());
00205     }
00206 
00207     // if the collapsing edge was a boundary edge, we must add the dummy vertex.
00208     // Note that this implies that Lk(edge) >=2;
00209     if(LkEdge.size()==1)
00210     {
00211       LkEdge.push_back(0);
00212     }
00213 
00214     // NOW COUNT!!!
00215     size_t SharedEdgeCnt=0;
00216     typename std::map<std::pair<VertexPointer,VertexPointer>, int>::iterator eci;
00217     for(eci=EdgeCnt.begin();eci!=EdgeCnt.end();++eci)
00218       if((*eci).second == 2) SharedEdgeCnt ++;
00219 
00220     if(SharedEdgeCnt>0) return false;
00221     size_t SharedVertCnt=0;
00222     typename std::map<VertexPointer,int>::iterator vci;
00223     for(vci=VertCnt.begin();vci!=VertCnt.end();++vci)
00224       if((*vci).second == 4) SharedVertCnt++;
00225 
00226     if(SharedVertCnt != LkEdge.size() ) return false;
00227 
00228     return true;
00229   }
00230 
00231   // Main function; the one that actually make the collapse
00232   // remember that v[0] will be deleted and v[1] will survive (eventually with a new position)
00233   // hint to do a 'collapse onto a vertex simply pass p as the position of the surviving vertex
00234   static int Do(TriMeshType &m, VertexPair & c, const Point3<ScalarType> &p)
00235     {
00236     EdgeSet es;
00237     FindSets(c,es);
00238         typename VFIVec::iterator i;
00239     int n_face_del =0 ;
00240 
00241     for(i=es.AV01().begin();i!=es.AV01().end();++i)
00242         {
00243             FaceType  & f = *((*i).f);
00244             assert(f.V((*i).z) == c.V(0));
00245             vcg::face::VFDetach(f,((*i).z+1)%3);
00246             vcg::face::VFDetach(f,((*i).z+2)%3);
00247             Allocator<TriMeshType>::DeleteFace(m,f);
00248       n_face_del++;
00249     }
00250 
00251         //set Vertex Face topology
00252     for(i=es.AV0().begin();i!=es.AV0().end();++i)
00253         {
00254             (*i).f->V((*i).z) = c.V(1);                                                                  // In tutte le facce incidenti in v0, si sostituisce v0 con v1
00255             (*i).f->VFp((*i).z) = (*i).f->V((*i).z)->VFp(); // e appendo la lista di facce incidenti in v1 a questa faccia
00256             (*i).f->VFi((*i).z) = (*i).f->V((*i).z)->VFi();
00257             (*i).f->V((*i).z)->VFp() = (*i).f;
00258             (*i).f->V((*i).z)->VFi() = (*i).z;
00259         }
00260 
00261         Allocator<TriMeshType>::DeleteVertex(m,*(c.V(0)));
00262         c.V(1)->P()=p;
00263         return n_face_del;
00264     }
00265 
00266 };
00267 
00268 }
00269 }
00270 #endif


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