polygon_polychord_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 POLYGON_POLYCHORD_COLLAPSE_H
00024 #define POLYGON_POLYCHORD_COLLAPSE_H
00025 
00026 #include <vector>
00027 #include <list>
00028 #if __cplusplus >= 201103L
00029   #include <unordered_map>
00030 #else
00031   #include <map>
00032 #endif
00033 #include <set>
00034 #include <algorithm>
00035 #include <iterator>
00036 #include <vcg/complex/complex.h>
00037 #include <vcg/simplex/face/jumping_pos.h>
00038 
00039 namespace vcg {
00040 namespace tri {
00056 template < typename PolyMeshType >
00057 class PolychordCollapse {
00058 public:
00059   typedef typename PolyMeshType::CoordType      CoordType;
00060   typedef typename PolyMeshType::VertexType     VertexType;
00061   typedef typename PolyMeshType::VertexPointer  VertexPointer;
00062   typedef typename PolyMeshType::VertexIterator VertexIterator;
00063   typedef typename PolyMeshType::FaceType       FaceType;
00064   typedef typename PolyMeshType::FacePointer    FacePointer;
00065   typedef typename PolyMeshType::FaceIterator   FaceIterator;
00066 
00070   enum PC_ResultCode {
00071     PC_SUCCESS          = 0x000,
00072     PC_NOTMANIF         = 0x001,
00073     PC_NOTQUAD          = 0x002,
00074     PC_NOLINKCOND       = 0x004,
00075     PC_SINGSIDEA        = 0x008,
00076     PC_SINGSIDEB        = 0x010,
00077     PC_SINGBOTH         = 0x020,
00078     PC_SELFINTERSECT    = 0x040,
00079     PC_NOMOREMANIF      = 0x080,
00080     PC_VOID             = 0x100,
00081     PC_OTHER            = 0x100
00082   };
00083 
00087   struct PC_Chord {
00088     unsigned long mark;
00089     PC_ResultCode q;
00090     PC_Chord * prev;
00091     PC_Chord * next;
00092     PC_Chord() : mark(std::numeric_limits<unsigned long>::max()), q(PC_VOID), prev(NULL), next(NULL) { }
00093     inline void Reset() {
00094       mark = std::numeric_limits<unsigned long>::max();
00095       q = PC_VOID;
00096       prev = next = NULL;
00097     }
00098   };
00099 
00103   class PC_Chords {
00104   public:
00110     PC_Chords (const PolyMeshType &mesh) : _Chords(2*mesh.face.size()), _currentChord(NULL) {
00111       Reset(mesh);
00112     }
00113 
00117     void ResetMarks() {
00118       for (size_t i = 0; i < _Chords.size(); ++i)
00119         _Chords.at(i).mark = std::numeric_limits<unsigned long>::max();
00120     }
00121 
00127     void Reset(const PolyMeshType &mesh) {
00128       _Chords.resize(2*mesh.face.size());
00129       for (size_t j = 0; j < _Chords.size(); ++j)
00130         _Chords[j].Reset();
00131       _currentChord = NULL;
00132 
00133       PC_Chord *chord = NULL;
00134       long long j = 0;
00135       for (size_t i = 0; i < _Chords.size(); ++i) {
00136         // set the prev
00137         chord = NULL;
00138         if ((long long)i-1 >= 0) {
00139           chord = &_Chords[i-1];
00140           if (vcg::tri::HasPerFaceFlags(mesh)) {
00141             j = i-1;
00142             while (j >= 0 && mesh.face[j/2].IsD())
00143               --j;
00144             if (j >= 0)
00145               chord = &_Chords[j];
00146             else
00147               chord = NULL;
00148           }
00149         }
00150         _Chords[i].prev = chord;
00151 
00152         // set the next
00153         chord = NULL;
00154         if (i+1 < _Chords.size()) {
00155           chord = &_Chords[i+1];
00156           if (vcg::tri::HasPerFaceFlags(mesh)) {
00157             j = i+1;
00158             while (j < (long long)_Chords.size() && mesh.face[j/2].IsD())
00159               ++j;
00160             if (j < (long long)_Chords.size())
00161               chord = &_Chords[j];
00162             else
00163               chord = NULL;
00164           }
00165         }
00166         _Chords[i].next = chord;
00167       }
00168       if (mesh.face.size() > 0) {
00169         // set the current coord (first - not deleted - face)
00170         _currentChord = &_Chords[0];
00171         if (vcg::tri::HasPerFaceFlags(mesh) && mesh.face[0].IsD())
00172           _currentChord = _currentChord->next;
00173       }
00174     }
00175 
00181     inline PC_Chord & operator[] (const std::pair<size_t, unsigned char> &face_edge) {
00182       assert(face_edge.first >= 0 && 2*face_edge.first+face_edge.second < _Chords.size());
00183       return _Chords[2*face_edge.first + face_edge.second];
00184     }
00190     inline const PC_Chord & operator[] (const std::pair<size_t, unsigned char> &face_edge) const {
00191       assert(face_edge.first >= 0 && 2*face_edge.first+face_edge.second < _Chords.size());
00192       return _Chords[2*face_edge.first + face_edge.second];
00193     }
00194 
00200     inline std::pair<size_t, unsigned char> operator[] (PC_Chord const * const coord) {
00201       assert(coord >= &_Chords[0] && coord < &_Chords[0]+_Chords.size());
00202       return std::pair<size_t, unsigned char>((coord - &_Chords[0])/2, (coord - &_Chords[0])%2);
00203     }
00204 
00211     inline void UpdateCoord (PC_Chord &coord, const unsigned long mark, const PC_ResultCode resultCode) {
00212       // update prev and next
00213       if (coord.q == PC_VOID) {
00214         if (coord.prev != NULL && &coord != _currentChord)
00215           coord.prev->next = coord.next;
00216         if (coord.next != NULL && &coord != _currentChord)
00217           coord.next->prev = coord.prev;
00218       }
00219       coord.mark = mark;
00220       coord.q = resultCode;
00221     }
00222 
00226     inline void Next () {
00227       if (_currentChord != NULL)
00228         _currentChord = _currentChord->next;
00229     }
00230 
00235     inline void GetCurrent (std::pair<size_t, unsigned char> &face_edge) {
00236       if (_currentChord != NULL) {
00237         face_edge.first = (_currentChord - &_Chords[0])/2;
00238         face_edge.second = (_currentChord - &_Chords[0])%2;
00239       } else {
00240         face_edge.first = std::numeric_limits<size_t>::max();
00241         face_edge.second = 0;
00242       }
00243     }
00244 
00249     inline bool End () {
00250       return _currentChord == NULL;
00251     }
00252 
00253   private:
00254     std::vector<PC_Chord>   _Chords;
00255     PC_Chord                *_currentChord;
00256   };
00257 
00261   class LinkConditions {
00262   private:
00263     typedef long int                LCVertexIndex;
00264     typedef std::set<LCVertexIndex> LCVertexStar;   
00265     typedef long int                LCEdgeIndex;
00266     typedef std::set<LCEdgeIndex>   LCEdgeStar;     
00267 
00271     struct LCVertex {
00272       LCVertexStar star;  // vertex star
00273       LCEdgeStar edges;   // list of edges whose star involves this vertex
00274       LCVertex(){}        // default constructor
00275       LCVertex(const LCVertex &lcVertex) {  // copy constructor
00276         star = lcVertex.star;
00277         edges = lcVertex.edges;
00278       }
00279       LCVertex & operator=(const LCVertex &lcVertex) { // assignment operator
00280         star = lcVertex.star;
00281         edges = lcVertex.edges;
00282         return *this;
00283       }
00284       void reset() { star.clear(); edges.clear(); } // reset
00285     };
00286 
00290     struct LCEdge {
00291       LCVertexIndex v1, v2;       // endpoints
00292       LCVertexStar star;          // edge star
00293       LCEdge() {v1 = v2 = -1;}    // default contructor
00294       LCEdge(const LCEdge &lcEdge) {  // copy constructor
00295         v1 = lcEdge.v1;
00296         v2 = lcEdge.v2;
00297         star = lcEdge.star;
00298       }
00299       LCEdge & operator=(const LCEdge &lcEdge) {  // assignment operator
00300         v1 = lcEdge.v1;
00301         v2 = lcEdge.v2;
00302         star = lcEdge.star;
00303         return *this;
00304       }
00305       void reset() {  // reset
00306         v1 = -1;
00307         v2 = -1;
00308         star.clear();
00309       }
00310     };
00311 
00312   public:
00317     LinkConditions (const size_t size) : _lcVertices(size) { }
00318 
00323     inline void Resize(const size_t size) {
00324       _lcVertices.resize(size);
00325       LC_ResetStars();
00326     }
00327 
00337     bool CheckLinkConditions (const PolyMeshType &mesh, const vcg::face::Pos<FaceType> &startPos) {
00338       assert(!startPos.IsNull());
00339       assert(mesh.vert.size() == _lcVertices.size());
00340       std::vector<LCEdge> lcEdges;
00341       LCVertexStar intersection;
00342 
00343       // reset the stars
00344       LC_ResetStars();
00345 
00346       // compute the stars
00347       LC_computeStars(mesh, startPos, lcEdges);
00348 
00349       // for each edge e = (v1,v2)
00350       // if intersection( star(v1) , star(v2) ) == star(e)
00351       //      then collapse e
00352       // else
00353       //      return false (i.e. link conditions not satisfied)
00354       for (size_t e = 0; e < lcEdges.size(); e++) {
00355         // compute the intersetion
00356         intersection.clear();
00357         std::set_intersection(_lcVertices[lcEdges[e].v1].star.begin(), _lcVertices[lcEdges[e].v1].star.end(),
00358                               _lcVertices[lcEdges[e].v2].star.begin(), _lcVertices[lcEdges[e].v2].star.end(),
00359                               std::inserter(intersection, intersection.end()));
00360 
00361         // if intersection( star(v1) , star(v2) ) != star(e) then return false
00362         if (intersection != lcEdges[e].star)
00363             return false;
00364 
00365         // else simulate the collapse
00366         LC_SimulateEdgeCollapse(lcEdges, e);
00367       }
00368       // at this point all collapses are possible, thus return true
00369       return true;
00370     }
00371 
00372   private:
00376     void LC_ResetStars() {
00377       for (size_t v = 0; v < _lcVertices.size(); ++v)
00378         _lcVertices[v].reset();
00379     }
00380 
00388     void LC_computeStars (const PolyMeshType &mesh, const vcg::face::Pos<FaceType> &startPos, std::vector<LCEdge> &lcEdges) {
00389       assert(!startPos.IsNull());
00390       assert(mesh.vert.size() == _lcVertices.size());
00391       vcg::face::Pos<FaceType> runPos = startPos;
00392       vcg::face::JumpingPos<FaceType> vStarPos;
00393       vcg::face::Pos<FaceType> eStarPos;
00394       LCEdgeIndex edgeInd = -1;
00395       size_t nEdges = 0;
00396 
00397       // count how many edges
00398       do {
00399         ++nEdges;
00400         // go on the next edge
00401         runPos.FlipE();
00402         runPos.FlipV();
00403         runPos.FlipE();
00404         runPos.FlipF();
00405       } while (runPos != startPos && !runPos.IsBorder());
00406       if (runPos.IsBorder())
00407         ++nEdges;
00408 
00409       // resize the vector of edges
00410       lcEdges.resize(nEdges);
00411       for (size_t e = 0; e < nEdges; ++e)
00412         lcEdges[e].reset();
00413 
00415       runPos = startPos;
00416       do {
00417         // access the next lcedge
00418         edgeInd++;
00419         // set lcvertices references
00420         lcEdges[edgeInd].v1 = vcg::tri::Index(mesh, runPos.V());
00421         lcEdges[edgeInd].v2 = vcg::tri::Index(mesh, runPos.VFlip());
00422         // add this edge to its vertices edge-stars
00423         _lcVertices[lcEdges[edgeInd].v1].edges.insert(edgeInd);
00424         _lcVertices[lcEdges[edgeInd].v2].edges.insert(edgeInd);
00425         // compute the star of this edge
00426         lcEdges[edgeInd].star.insert(lcEdges[edgeInd].v1);  // its endpoints, clearly
00427         lcEdges[edgeInd].star.insert(lcEdges[edgeInd].v2);  // its endpoints, clearly
00428         // navigate over the other vertices of this facet
00429         eStarPos = runPos;
00430         eStarPos.FlipE();
00431         eStarPos.FlipV();
00432         while (eStarPos.V() != runPos.VFlip()) {
00433           // add current vertex to the star of this edge
00434           lcEdges[edgeInd].star.insert(vcg::tri::Index(mesh, eStarPos.V()));
00435           // add this edge to the edge-star of the current vertex
00436           _lcVertices[vcg::tri::Index(mesh, eStarPos.V())].edges.insert(edgeInd);
00437           // go on
00438           eStarPos.FlipE();
00439           eStarPos.FlipV();
00440         }
00441         // go on the opposite facet
00442         if (!runPos.IsBorder()) {
00443           eStarPos = runPos;
00444           eStarPos.FlipF();
00445           eStarPos.FlipE();
00446           eStarPos.FlipV();
00447           while (eStarPos.V() != runPos.VFlip()) {
00448             // add current vertex to the star of this edge
00449             lcEdges[edgeInd].star.insert(vcg::tri::Index(mesh, eStarPos.V()));
00450             // add this edge to the edge-star of the current vertex
00451             _lcVertices[vcg::tri::Index(mesh, eStarPos.V())].edges.insert(edgeInd);
00452             // go on
00453             eStarPos.FlipE();
00454             eStarPos.FlipV();
00455           }
00456         }
00457 
00458         // compute the star of vertex v2
00459         runPos.FlipV();
00460         vStarPos.Set(runPos.F(), runPos.E(), runPos.V());
00461         // v2 is in its star
00462         _lcVertices[vcg::tri::Index(mesh, vStarPos.V())].star.insert(vcg::tri::Index(mesh, vStarPos.V()));
00463         do {
00464           vStarPos.FlipV();
00465           vStarPos.FlipE();
00466           while (vStarPos.V() != runPos.V()) {
00467             // add the current vertex to the v2 star
00468             _lcVertices[vcg::tri::Index(mesh, runPos.V())].star.insert(vcg::tri::Index(mesh, vStarPos.V()));
00469             // add v2 to the star of the current vertex
00470             _lcVertices[vcg::tri::Index(mesh, vStarPos.V())].star.insert(vcg::tri::Index(mesh, runPos.V()));
00471             vStarPos.FlipV();
00472             vStarPos.FlipE();
00473           }
00474           vStarPos.NextFE();
00475         } while (vStarPos != runPos);
00476 
00477         // compute the star of vertex v1
00478         runPos.FlipV();
00479         vStarPos.Set(runPos.F(), runPos.E(), runPos.V());
00480         // v1 is in its star
00481         _lcVertices[vcg::tri::Index(mesh, vStarPos.V())].star.insert(vcg::tri::Index(mesh, vStarPos.V()));
00482         do {
00483           vStarPos.FlipV();
00484           vStarPos.FlipE();
00485           while (vStarPos.V() != runPos.V()) {
00486             // add the current vertex to the v2 star
00487             _lcVertices[vcg::tri::Index(mesh, runPos.V())].star.insert(vcg::tri::Index(mesh, vStarPos.V()));
00488             // add v2 to the star of the current vertex
00489             _lcVertices[vcg::tri::Index(mesh, vStarPos.V())].star.insert(vcg::tri::Index(mesh, runPos.V()));
00490             vStarPos.FlipV();
00491             vStarPos.FlipE();
00492           }
00493           vStarPos.NextFE();
00494         } while (vStarPos != runPos);
00495 
00496         // when arrive to a border, stop
00497         if (runPos != startPos && runPos.IsBorder())
00498           break;
00499 
00500         // go on the next edge
00501         runPos.FlipE();
00502         runPos.FlipV();
00503         runPos.FlipE();
00504         runPos.FlipF();
00505       } while (runPos != startPos);
00506 
00507       // check if the starting pos or the border has been reached
00508       assert(runPos == startPos || runPos.IsBorder());
00509     }
00510 
00516     void LC_SimulateEdgeCollapse (std::vector<LCEdge> &lcEdges, const LCEdgeIndex edgeInd) {
00517       // let v1 and v2 be the two end points
00518       LCVertexIndex v1 = lcEdges[edgeInd].v1;
00519       LCVertexIndex v2 = lcEdges[edgeInd].v2;
00520       LCVertexIndex v = -1;
00521 
00523       // star(v1) = star(v1) U star(v2)
00524       _lcVertices[v1].star.insert(_lcVertices[v2].star.begin(), _lcVertices[v2].star.end());
00525       _lcVertices[v1].star.erase(v2);     // remove v2 from v1-star
00526       _lcVertices[v2].star.erase(v1);     // remove v1 from v2-star
00527       // foreach v | v2 \in star(v) [i.e. v \in star(v2)]
00528       //      star(v) = star(v) U {v1} \ {v2}
00529       for (typename LCVertexStar::iterator vIt = _lcVertices[v2].star.begin(); vIt != _lcVertices[v2].star.end(); ++vIt) {
00530         v = *vIt;
00531         if (v == v2)  // skip v2 itself
00532           continue;
00533         _lcVertices[v].star.insert(v1);
00534         _lcVertices[v].star.erase(v2);
00535       }
00537       // foreach e | v1 \in star(e) ^ v2 \in star(e)
00538       //      star(e) = star(e) \ {v1,v2} U {v1}
00539       for (typename LCEdgeStar::iterator eIt = _lcVertices[v1].edges.begin(); eIt != _lcVertices[v1].edges.end(); ++eIt)
00540         lcEdges[*eIt].star.erase(v2);
00541       for (typename LCEdgeStar::iterator eIt = _lcVertices[v2].edges.begin(); eIt != _lcVertices[v2].edges.end(); ++eIt) {
00542         lcEdges[*eIt].star.erase(v2);
00543         lcEdges[*eIt].star.insert(v1);
00544       }
00545     }
00546 
00550     std::vector<LCVertex> _lcVertices;
00551   };
00552 
00553 
00554   // PolychordCollapse's methods begin here::::::::::::::::::::::::::::::::::::::::::::::::::::::::::::::::
00555 
00556 //  /**
00557 //   * @brief CheckConsistent checks for consistency. ONLY FOR DEBUG.
00558 //   * @param mesh
00559 //   * @return
00560 //   */
00561 //  static bool CheckConsistent(PolyMeshType &mesh) {
00562 //    vcg::tri::RequirePerFaceFlags(mesh);
00563 //    vcg::tri::RequirePerFaceColor(mesh);
00564 //    for (size_t f = 0; f < mesh.face.size(); ++f) {
00565 //      if (!mesh.face[f].IsD()) {
00566 //        for (int v = 0; v < mesh.face[f].VN(); ++v) {
00567 //          if (!vcg::face::IsBorder(mesh.face[f], v)) {
00568 //            if (mesh.face[f].FFp(v)->IsD()) {
00569 //              mesh.face[f].C() = vcg::Color4b(vcg::Color4b::Magenta);
00570 //              return false;
00571 //            }
00572 //            if (mesh.face[f].FFp(v)->FFp(mesh.face[f].FFi(v)) != &mesh.face[f]) {
00573 //              mesh.face[f].C() = vcg::Color4b(vcg::Color4b::Yellow);
00574 //              return false;
00575 //            }
00576 //          }
00577 //        }
00578 //      }
00579 //    }
00580 //    return true;
00581 //  }
00582 
00590   static void MarkPolychords(const PolyMeshType &mesh,
00591                              const vcg::face::Pos<FaceType> &startPos,
00592                              PC_Chords &chords,
00593                              const unsigned long mark) {
00594     vcg::face::Pos<FaceType> runPos = startPos;
00595     std::pair<size_t, unsigned char> face_edge(std::numeric_limits<size_t>::max(), 0);
00596     do {
00597       assert(runPos.F()->VN() == 4);
00598       face_edge.first = vcg::tri::Index(mesh, runPos.F());
00599       face_edge.second = runPos.E() % 2;
00600       chords[face_edge].mark = mark;
00601       runPos.FlipE();
00602       runPos.FlipV();
00603       runPos.FlipE();
00604       runPos.FlipF();
00605     } while (runPos != startPos && !runPos.IsBorder());
00606   }
00607 
00638   static PC_ResultCode CollapsePolychord (PolyMeshType &mesh,
00639                                           const vcg::face::Pos<FaceType> &pos,
00640                                           const unsigned long mark,
00641                                           PC_Chords &chords,
00642                                           LinkConditions &linkConditions,
00643                                           const bool checkSing = true) {
00644     vcg::tri::RequireFFAdjacency(mesh);
00645 
00646     if (mesh.IsEmpty())
00647       return PC_VOID;
00648 
00649     if (pos.IsNull())
00650       return PC_VOID;
00651 
00652     vcg::face::Pos<FaceType> tempPos, startPos;
00653 
00654     // check if the sequence of facets is a polychord and find the starting coord
00655     PC_ResultCode resultCode = CheckPolychordFindStartPosition(pos, startPos, checkSing);
00656     // if not successful, visit the sequence for marking it and return
00657     if (resultCode != PC_SUCCESS && resultCode != PC_SINGSIDEA && resultCode != PC_SINGSIDEB) {
00658       // if not manifold, visit the entire polychord ending on the non-manifold edge
00659       if (resultCode == PC_NOTMANIF) {
00660         tempPos = pos;
00661         VisitPolychord(mesh, tempPos, chords, mark, resultCode);
00662         if (tempPos.IsManifold() && !tempPos.IsBorder()) {
00663           tempPos.FlipF();
00664           VisitPolychord(mesh, tempPos, chords, mark, resultCode);
00665         }
00666         return resultCode;
00667       }
00668       // if not quad, visit all the polychords passing through this coord
00669       if (resultCode == PC_NOTQUAD) {
00670         tempPos = startPos;
00671         do {
00672           if (!tempPos.IsBorder()) {
00673             tempPos.FlipF();
00674             VisitPolychord(mesh, tempPos, chords, mark, resultCode);
00675             tempPos.FlipF();
00676           }
00677           tempPos.FlipV();
00678           tempPos.FlipE();
00679         } while (tempPos != startPos);
00680         VisitPolychord(mesh, startPos, chords, mark, resultCode);
00681         return resultCode;
00682       }
00683       VisitPolychord(mesh, startPos, chords, mark, resultCode);
00684       return resultCode;
00685     }
00686     // check if the link conditions are satisfied
00687     // if not satisfied, visit the sequence for marking it and return
00688     if (!linkConditions.CheckLinkConditions(mesh, startPos)) {
00689       VisitPolychord(mesh, startPos, chords, mark, PC_NOLINKCOND);
00690       return PC_NOLINKCOND;
00691     }
00692     // mark the polychord's chords
00693     MarkPolychords(mesh, startPos, chords, mark);
00694     // check if the polychord does not intersect itself
00695     // if it self-intersects, visit the polychord for marking it and return
00696     if (IsPolychordSelfIntersecting(mesh, startPos, chords, mark)) {
00697       VisitPolychord(mesh, startPos, chords, mark, PC_SELFINTERSECT);
00698       return PC_SELFINTERSECT;
00699     }
00700     // check if manifoldness remains
00701     // if it will loose manifoldness, visit the sequence for marking it and return
00702     if (!WillPolychordBeManifold(mesh, startPos, chords, mark)) {
00703       VisitPolychord(mesh, startPos, chords, mark, PC_NOMOREMANIF);
00704       return PC_NOMOREMANIF;
00705     }
00706     // at this point the polychord is collapsable, visit it for marking
00707     VisitPolychord(mesh, startPos, chords, mark, PC_SUCCESS);
00708 
00709     // now collapse
00710     CoordType point;
00711 //    int valenceA = 0, valenceB = 0;
00712     vcg::face::Pos<FaceType> runPos = startPos;
00713     vcg::face::JumpingPos<FaceType> tmpPos;
00714 //    bool onSideA = false, onSideB = false;
00715     vcg::face::Pos<FaceType> sideA, sideB;
00716     typedef std::queue<VertexPointer *> FacesVertex;
00717     typedef std::pair<VertexPointer, FacesVertex> FacesVertexPair;
00718     typedef std::queue<FacesVertexPair> FacesVertexPairQueue;
00719     FacesVertexPairQueue vQueue;
00720     typedef std::pair<FacePointer *, FacePointer> FFpPair;
00721     typedef std::pair<char *, char> FFiPair;
00722     typedef std::pair<FFpPair, FFiPair> FFPair;
00723     typedef std::queue<FFPair> FFQueue;
00724     FFQueue ffQueue;
00725     std::queue<VertexPointer> verticesToDeleteQueue;
00726     std::queue<FacePointer> facesToDeleteQueue;
00727 
00728     runPos = startPos;
00729     do {
00730       // compute new vertex
00731       point = (runPos.V()->P() + runPos.VFlip()->P()) / 2.f;
00732       if (checkSing) {
00733         if (resultCode == PC_SINGSIDEA)
00734           point = runPos.V()->P();
00735         else if (resultCode == PC_SINGSIDEB)
00736           point = runPos.VFlip()->P();
00737       }
00738       runPos.V()->P() = point;
00739       // list the vertex pointer of the faces on the other side to be updated
00740       vQueue.push(FacesVertexPair());
00741       vQueue.back().first = runPos.V();
00742       tmpPos.Set(runPos.F(), runPos.E(), runPos.V());
00743       tmpPos.FlipV();
00744       tmpPos.NextFE();    // go to next face
00745       while (tmpPos.F() != runPos.F()) {
00746         if (tmpPos.F() != runPos.FFlip())
00747           vQueue.back().second.push(&tmpPos.F()->V(tmpPos.VInd()));
00748         tmpPos.NextFE();    // go to next face
00749       }
00750 
00751       // enqueue to delete the other vertex
00752       verticesToDeleteQueue.push(runPos.VFlip());
00753 
00754       // list the adjacencies
00755       sideA = runPos;
00756       sideA.FlipE();
00757       sideA.FlipF();
00758       sideB = runPos;
00759       sideB.FlipV();
00760       sideB.FlipE();
00761       sideB.FlipF();
00762       // first side
00763       if (!sideA.IsBorder()) {
00764         ffQueue.push(FFPair(FFpPair(),FFiPair()));
00765         ffQueue.back().first.first = &sideA.F()->FFp(sideA.E());
00766         ffQueue.back().second.first = &sideA.F()->FFi(sideA.E());
00767         if (!sideB.IsBorder()) {
00768           ffQueue.back().first.second = sideB.F();
00769           ffQueue.back().second.second = sideB.E();
00770         } else {
00771           ffQueue.back().first.second = sideA.F();
00772           ffQueue.back().second.second = sideA.E();
00773         }
00774       }
00775       // second side
00776       if (!sideB.IsBorder()) {
00777         ffQueue.push(FFPair(FFpPair(),FFiPair()));
00778         ffQueue.back().first.first = &sideB.F()->FFp(sideB.E());
00779         ffQueue.back().second.first = &sideB.F()->FFi(sideB.E());
00780         if (!sideA.IsBorder()) {
00781           ffQueue.back().first.second = sideA.F();
00782           ffQueue.back().second.second = sideA.E();
00783         } else {
00784           ffQueue.back().first.second = sideB.F();
00785           ffQueue.back().second.second = sideB.E();
00786         }
00787       }
00788 
00789       // enqueue to delete the face
00790       facesToDeleteQueue.push(runPos.F());
00791 
00792       // go on next edge/face
00793       runPos.FlipE();
00794       runPos.FlipV();
00795       runPos.FlipE();
00796       runPos.FlipF();
00797     } while (runPos != startPos && !runPos.IsBorder());
00798     assert(runPos == startPos || vcg::face::IsBorder(*startPos.F(),startPos.E()));
00799     if (runPos.IsBorder()) {
00800       // compute new vertex on the last (border) edge
00801       point = (runPos.V()->P() + runPos.VFlip()->P()) / 2.f;
00802       if (checkSing) {
00803         if (resultCode == PC_SINGSIDEA)
00804           point = runPos.V()->P();
00805         else if (resultCode == PC_SINGSIDEB)
00806           point = runPos.VFlip()->P();
00807       }
00808       runPos.V()->P() = point;
00809       // list the vertex pointer of the faces on the other side to be updated
00810       vQueue.push(FacesVertexPair());
00811       vQueue.back().first = runPos.V();
00812       tmpPos.Set(runPos.F(), runPos.E(), runPos.V());
00813       tmpPos.FlipV();
00814       tmpPos.NextFE();    // go to next face
00815       while (tmpPos.F() != runPos.F()) {
00816         vQueue.back().second.push(&tmpPos.F()->V(tmpPos.VInd()));
00817         tmpPos.NextFE();
00818       }
00819 
00820       // enqueue to delete the other vertex
00821       verticesToDeleteQueue.push(runPos.VFlip());
00822     }
00823 
00824     // update vertices
00825     while (!vQueue.empty()) {
00826       while (!vQueue.front().second.empty()) {
00827         *vQueue.front().second.front() = vQueue.front().first;
00828         vQueue.front().second.pop();
00829       }
00830       vQueue.pop();
00831     }
00832 
00833     // update adjacencies
00834     while (!ffQueue.empty()) {
00835       *ffQueue.front().first.first = ffQueue.front().first.second;
00836       *ffQueue.front().second.first = ffQueue.front().second.second;
00837       ffQueue.pop();
00838     }
00839 
00840     // delete faces
00841     while (!facesToDeleteQueue.empty()) {
00842       vcg::tri::Allocator<PolyMeshType>::DeleteFace(mesh, *facesToDeleteQueue.front());
00843       facesToDeleteQueue.pop();
00844     }
00845 
00846     // delete vertices
00847     while (!verticesToDeleteQueue.empty()) {
00848       vcg::tri::Allocator<PolyMeshType>::DeleteVertex(mesh, *verticesToDeleteQueue.front());
00849       verticesToDeleteQueue.pop();
00850     }
00851 
00852     return PC_SUCCESS;
00853   }
00854 
00860   static void CollapseAllPolychords (PolyMeshType &mesh, const bool checkSing = true) {
00861     vcg::tri::RequireFFAdjacency(mesh);
00862 
00863     if (mesh.IsEmpty())
00864       return;
00865 
00866     vcg::face::Pos<FaceType> pos;
00867     PC_ResultCode resultCode;
00868     std::pair<size_t, unsigned char> face_edge;
00869     // construct the link conditions checker
00870     LinkConditions linkConditions(mesh.vert.size());
00871     // construct the vector of chords
00872     PC_Chords chords(mesh);
00873     unsigned long mark = 0;
00874 
00875     // iterate over all the chords
00876     while (!chords.End()) {
00877       // get the current coord
00878       chords.GetCurrent(face_edge);
00879       resultCode = chords[face_edge].q;
00880       assert(resultCode == PC_VOID);
00881       // construct a pos on the face and edge of the current coord
00882       pos.Set(&mesh.face[face_edge.first], face_edge.second, mesh.face[face_edge.first].V(face_edge.second));
00883       // (try to) collapse the polychord
00884       resultCode = CollapsePolychord(mesh, pos, mark, chords, linkConditions, checkSing);
00885       // go to the next coord
00886       chords.Next();
00887 
00888       // increment the mark
00889       ++mark;
00890       if (mark == std::numeric_limits<unsigned long>::max()) {
00891         chords.ResetMarks();
00892         mark = 0;
00893       }
00894     }
00895   }
00896 
00903   static void FindPolychords (PolyMeshType &mesh, std::deque< vcg::face::Pos<FaceType> > &polychords, const bool loopsOnly = false) {
00904     vcg::tri::RequireFFAdjacency(mesh);
00905 
00906     polychords.clear();
00907 
00908     if (mesh.IsEmpty())
00909       return;
00910 
00911     vcg::face::Pos<FaceType> pos, startPos;
00912     PC_ResultCode resultCode;
00913     std::pair<size_t, unsigned char> face_edge;
00914     // construct the vector of chords
00915     PC_Chords chords(mesh);
00916     unsigned long mark = 0;
00917 
00918     // iterate over all the chords
00919     while (!chords.End()) {
00920       // get the current coord
00921       chords.GetCurrent(face_edge);
00922       // construct a pos on the face and edge of the current coord
00923       pos.Set(&mesh.face[face_edge.first], face_edge.second, mesh.face[face_edge.first].V(face_edge.second));
00924 
00925       // check and find start pos
00926       resultCode = CheckPolychordFindStartPosition(pos, startPos, false);
00927       // visit the polychord
00928       if (resultCode == PC_SUCCESS || resultCode == PC_SINGBOTH || resultCode == PC_SINGSIDEA || resultCode == PC_SINGSIDEB) {
00929         VisitPolychord(mesh, startPos, chords, mark, PC_OTHER);
00930         // store a new polychord
00931         if (!loopsOnly)
00932           polychords.push_back(startPos);
00933         else if (!startPos.IsBorder())
00934           polychords.push_back(startPos);
00935       } else {
00936         if (resultCode == PC_NOTMANIF) {
00937           pos = startPos;
00938           VisitPolychord(mesh, pos, chords, mark, resultCode);
00939           if (pos.IsManifold() && !pos.IsBorder()) {
00940             pos.FlipF();
00941             VisitPolychord(mesh, pos, chords, mark, resultCode);
00942           }
00943         } else if (resultCode == PC_NOTQUAD) {
00944           // if not quad, visit all the polychords passing through this coord
00945           pos = startPos;
00946           do {
00947             if (!pos.IsBorder()) {
00948               pos.FlipF();
00949               VisitPolychord(mesh, pos, chords, mark, resultCode);
00950               pos.FlipF();
00951             }
00952             pos.FlipV();
00953             pos.FlipE();
00954           } while (pos != startPos);
00955           VisitPolychord(mesh, startPos, chords, mark, resultCode);
00956         }
00957         VisitPolychord(mesh, startPos, chords, mark, resultCode);
00958       }
00959 
00960       // go to the next coord
00961       chords.Next();
00962       // increment the mark
00963       ++mark;
00964       if (mark == std::numeric_limits<unsigned long>::max()) {
00965         chords.ResetMarks();
00966         mark = 0;
00967       }
00968     }
00969   }
00970 
00979   static void SplitPolychord (PolyMeshType &mesh, vcg::face::Pos<FaceType> &pos, const size_t n,
00980                               std::vector<FacePointer *> &facesToUpdate, std::vector<VertexPointer *> &verticesToUpdate) {
00981     vcg::tri::RequireFFAdjacency(mesh);
00982     vcg::tri::RequirePerFaceFlags(mesh);
00983 
00984     if (mesh.IsEmpty())
00985       return;
00986     if (pos.IsNull())
00987       return;
00988     if (n <= 1)
00989       return;
00990 
00991     // remember which face vertex has pos, for later updating
00992     int posVInd = pos.VInd();
00993 
00994     vcg::face::Pos<FaceType> startPos, runPos;
00995     PC_ResultCode result = CheckPolychordFindStartPosition(pos, startPos, false);
00996     if (result != PC_SUCCESS && result != PC_SINGBOTH && result != PC_SINGSIDEA && result != PC_SINGSIDEB)
00997       return;
00998 
00999     // since every face has an orientation, ensure that the new polychords are inserted on the right of the starting pos
01000     startPos.FlipE();
01001     int e = startPos.E();
01002     startPos.FlipE();
01003     if (startPos.F()->Next(startPos.E()) == e)
01004       startPos.FlipV();
01005 
01006     // clear flags
01007     vcg::tri::UpdateFlags<PolyMeshType>::FaceClearV(mesh);
01008     vcg::tri::UpdateFlags<PolyMeshType>::FaceClearS(mesh);
01009 
01010     // count how many faces there are
01011     size_t fn1 = 0, fn2 = 0;
01012     runPos = startPos;
01013     do {
01014       // increase the number of faces
01015       if (runPos.F()->IsV()) {
01016         ++fn2;
01017         --fn1;
01018         runPos.F()->SetS();
01019       } else {
01020         ++fn1;
01021         runPos.F()->SetV();
01022       }
01023 
01024       // go onto the next face
01025       runPos.FlipE();
01026       runPos.FlipV();
01027       runPos.FlipE();
01028       runPos.FlipF();
01029     } while (!runPos.IsBorder() && runPos != startPos);
01030 
01031     // clear flags
01032     runPos = startPos;
01033     do {
01034       // clear visited
01035       runPos.F()->ClearV();
01036       // go onto the next face
01037       runPos.FlipE();
01038       runPos.FlipV();
01039       runPos.FlipE();
01040       runPos.FlipF();
01041     } while (!runPos.IsBorder() && runPos != startPos);
01042 
01043     // compute the number of faces and vertices that must be added to the mesh in order to insert the new polychords
01044     size_t FN = fn1 * (n - 1) + fn2 * (n * n - 1);
01045     size_t VN = fn1 * (n - 1) + fn2 * (n + 1) * (n - 1);
01046     if (startPos.IsBorder())
01047       VN += n - 1;
01048 
01049     // add the pos to update face and vertex pointer to the list of things to update after re-allocation
01050     facesToUpdate.push_back(&pos.F());
01051     verticesToUpdate.push_back(&pos.V());
01052     // add the starting position's face and vertex pointers to the list of things to update after re-allocation
01053     facesToUpdate.push_back(&startPos.F());
01054     verticesToUpdate.push_back(&startPos.V());
01055 
01056     runPos.SetNull();
01057     // add faces to the mesh
01058     FaceIterator firstAddedFaceIt = vcg::tri::Allocator<PolyMeshType>::AddFaces(mesh, FN, facesToUpdate);
01059     // add vertices to the mesh
01060     VertexIterator firstAddedVertexIt = vcg::tri::Allocator<PolyMeshType>::AddVertices(mesh, VN, verticesToUpdate);
01061 
01062     // delete the added starting position's face and vertex pointers
01063     facesToUpdate.pop_back();
01064     verticesToUpdate.pop_back();
01065     // delete the added pos to update face and vertex pointers
01066     facesToUpdate.pop_back();
01067     verticesToUpdate.pop_back();
01068 
01069     // allocate and initialize 4 vertices and ffAdj for each new face
01070     for (FaceIterator fIt = firstAddedFaceIt; fIt != mesh.face.end(); ++fIt) {
01071       fIt->Alloc(4);
01072       for (size_t j = 0; j < 4; ++j) {
01073         fIt->FFp(j) = &*fIt;
01074         fIt->FFi(j) = j;
01075       }
01076     }
01077 
01078     // two structures to store temporary face data and splitting information
01079     struct FaceData {
01080       FacePointer                 faceP;
01081       std::vector<FacePointer>    ffpAdj;
01082       std::vector<int>            ffiAdj;
01083       std::vector<VertexPointer>  fvpAdj;
01084       FaceData() : faceP(0), ffpAdj(4, 0), ffiAdj(4, 0), fvpAdj(4, 0) { }
01085     };
01086     struct FaceSubdivision {
01087       int                                   firstEdge;
01088       int                                   firstVertex;
01089       std::vector< std::vector<FaceData> >  subfaces;
01090     };
01091 #if __cplusplus >= 201103L
01092     std::unordered_map<FacePointer,FaceSubdivision>                     faceSubdivisions;
01093     typename std::unordered_map<FacePointer,FaceSubdivision>::iterator  faceSubdivisionsIt;
01094     typename std::unordered_map<FacePointer,FaceSubdivision>::iterator  faceSubdivisionsPrevIt;
01095     typename std::unordered_map<FacePointer,FaceSubdivision>::iterator  faceSubdivisionsNeighbourIt;
01096 #else
01097     std::map<FacePointer,FaceSubdivision                                faceSubdivisions;
01098     typename std::map<FacePointer,FaceSubdivision>::iterator            faceSubdivisionsIt;
01099     typename std::map<FacePointer,FaceSubdivision>::iterator            faceSubdivisionsPrevIt;
01100     typename std::map<FacePointer,FaceSubdivision>::iterator            faceSubdivisionsNeighbourIt;
01101 #endif
01102     // structure to store temporary data to assign at external faces (close to polychord)
01103     struct ExternalFaceData {
01104       FacePointer faceTo;
01105       FacePointer faceFrom;
01106       int         edgeTo;
01107       int         edgeFrom;
01108       ExternalFaceData() : faceTo(0), faceFrom(0), edgeTo(0), edgeFrom(0) { }
01109       ExternalFaceData(const FacePointer &ft,
01110                        const FacePointer &ff,
01111                        const int et,
01112                        const int ef) : faceTo(ft), faceFrom(ff), edgeTo(et), edgeFrom(ef) { }
01113     };
01114     std::list<ExternalFaceData>                                         externalFaces;
01115     typename std::list<ExternalFaceData>::iterator                      externalFacesIt;
01116 
01117     int leftEdge, rightEdge, topEdge, bottomEdge, blVInd, brVInd, tlVInd, trVInd;
01118     int pleftEdge, prightEdge, ptopEdge, pbottomEdge, pblVInd, pbrVInd, ptlVInd, ptrVInd;
01119     CoordType fromPoint, toPoint;
01120     FacePointer faceP;
01121     // first pass: make subdivisions
01122     runPos = startPos;
01123     do {
01124       // create temporary data
01125       if (!runPos.F()->IsV()) {
01126         runPos.F()->SetV();
01127         faceSubdivisionsIt = faceSubdivisions.insert(std::make_pair(runPos.F(), FaceSubdivision())).first;
01128         faceSubdivisionsIt->second.firstEdge = runPos.E();
01129         faceSubdivisionsIt->second.firstVertex = runPos.VInd();
01130         if (runPos.F()->IsS())
01131           faceSubdivisionsIt->second.subfaces.resize(n, std::vector<FaceData>(n));
01132         else
01133           faceSubdivisionsIt->second.subfaces.resize(1, std::vector<FaceData>(n));
01134         // assign face pointers
01135         faceSubdivisionsIt->second.subfaces.at(0).at(0).faceP = runPos.F();
01136         for (size_t j = 1; j < n; ++j, ++firstAddedFaceIt)
01137           faceSubdivisionsIt->second.subfaces.at(0).at(j).faceP = &*firstAddedFaceIt;
01138         for (size_t i = 1; i < faceSubdivisionsIt->second.subfaces.size(); ++i)
01139           for (size_t j = 0; j < n; ++j, ++firstAddedFaceIt)
01140             faceSubdivisionsIt->second.subfaces.at(i).at(j).faceP = &*firstAddedFaceIt;
01141         // internal face pointers adj
01142         rightEdge = runPos.F()->Next(runPos.E());
01143         leftEdge = runPos.F()->Prev(runPos.E());
01144         for (size_t i = 0; i < faceSubdivisionsIt->second.subfaces.size(); ++i)
01145           for (size_t j = 0; j < n - 1; ++j) {
01146             faceSubdivisionsIt->second.subfaces.at(i).at(j).ffpAdj[rightEdge] = faceSubdivisionsIt->second.subfaces.at(i).at(j+1).faceP;
01147             faceSubdivisionsIt->second.subfaces.at(i).at(j).ffiAdj[rightEdge] = leftEdge;
01148             faceSubdivisionsIt->second.subfaces.at(i).at(j+1).ffpAdj[leftEdge] = faceSubdivisionsIt->second.subfaces.at(i).at(j).faceP;
01149             faceSubdivisionsIt->second.subfaces.at(i).at(j+1).ffiAdj[leftEdge] = rightEdge;
01150           }
01151         topEdge = runPos.F()->Next(rightEdge);
01152         bottomEdge = runPos.E();
01153         for (size_t i = 0; i < faceSubdivisionsIt->second.subfaces.size() - 1; ++i)
01154           for (size_t j = 0; j < n; ++j) {
01155             faceSubdivisionsIt->second.subfaces.at(i).at(j).ffpAdj[topEdge] = faceSubdivisionsIt->second.subfaces.at(i+1).at(j).faceP;
01156             faceSubdivisionsIt->second.subfaces.at(i).at(j).ffiAdj[topEdge] = bottomEdge;
01157             faceSubdivisionsIt->second.subfaces.at(i+1).at(j).ffpAdj[bottomEdge] = faceSubdivisionsIt->second.subfaces.at(i).at(j).faceP;
01158             faceSubdivisionsIt->second.subfaces.at(i+1).at(j).ffiAdj[bottomEdge] = topEdge;
01159           }
01160         // assign old vertex pointers
01161         blVInd = runPos.VInd();
01162         brVInd = runPos.F()->Next(blVInd);
01163         trVInd = runPos.F()->Next(brVInd);
01164         tlVInd = runPos.F()->Next(trVInd);
01165         faceSubdivisionsIt->second.subfaces.front().front().fvpAdj.at(blVInd) = runPos.F()->V(blVInd);
01166         faceSubdivisionsIt->second.subfaces.front().back().fvpAdj.at(brVInd) = runPos.F()->V(brVInd);
01167         faceSubdivisionsIt->second.subfaces.back().back().fvpAdj.at(trVInd) = runPos.F()->V(trVInd);
01168         faceSubdivisionsIt->second.subfaces.back().front().fvpAdj.at(tlVInd) = runPos.F()->V(tlVInd);
01169         // assign new internal vertex pointers
01170         for (size_t i = 0; i < faceSubdivisionsIt->second.subfaces.size() - 1; ++i)
01171           for (size_t j = 0; j < n - 1; ++j, ++firstAddedVertexIt) {
01172             faceSubdivisionsIt->second.subfaces.at(i).at(j).fvpAdj.at(trVInd) = &*firstAddedVertexIt;
01173             faceSubdivisionsIt->second.subfaces.at(i).at(j+1).fvpAdj.at(tlVInd) = &*firstAddedVertexIt;
01174             faceSubdivisionsIt->second.subfaces.at(i+1).at(j).fvpAdj.at(brVInd) = &*firstAddedVertexIt;
01175             faceSubdivisionsIt->second.subfaces.at(i+1).at(j+1).fvpAdj.at(blVInd) = &*firstAddedVertexIt;
01176           }
01177       }
01178 
01179       runPos.FlipE();
01180       runPos.FlipV();
01181       runPos.FlipE();
01182       runPos.FlipF();
01183     } while (!runPos.IsBorder() && runPos != startPos);
01184 
01185     // update subdivision iterator
01186     if (runPos.IsBorder())
01187       faceSubdivisionsIt = faceSubdivisions.end();
01188 
01189     // second pass: assign edge vertices and subdivisions-to-subdivisions face-face adjacency
01190     runPos = startPos;
01191     do {
01192       // get current and previous subdivision
01193       faceSubdivisionsPrevIt = faceSubdivisionsIt;
01194       faceSubdivisionsIt = faceSubdivisions.find(runPos.F());
01195 
01196       // get original indices
01197       bottomEdge = faceSubdivisionsIt->second.firstEdge;
01198       rightEdge = runPos.F()->Next(bottomEdge);
01199       topEdge = runPos.F()->Next(rightEdge);
01200       leftEdge = runPos.F()->Next(topEdge);
01201       blVInd = faceSubdivisionsIt->second.firstVertex;
01202       brVInd = runPos.F()->Next(blVInd);
01203       trVInd = runPos.F()->Next(brVInd);
01204       tlVInd = runPos.F()->Next(trVInd);
01205       if (faceSubdivisionsPrevIt != faceSubdivisions.end()) {
01206         pbottomEdge = faceSubdivisionsPrevIt->second.firstEdge;
01207         prightEdge = runPos.FFlip()->Next(pbottomEdge);
01208         ptopEdge = runPos.FFlip()->Next(prightEdge);
01209         pleftEdge = runPos.FFlip()->Next(ptopEdge);
01210         pblVInd = faceSubdivisionsPrevIt->second.firstVertex;
01211         pbrVInd = runPos.F()->Next(pblVInd);
01212         ptrVInd = runPos.F()->Next(pbrVInd);
01213         ptlVInd = runPos.F()->Next(ptrVInd);
01214       }
01215 
01216       // assign bottom edge vertices (and vertex adjacency with the previous subdivision) and face-to-face adjacency
01217       if (runPos.E() == bottomEdge) {
01218         // get pre-existing coords
01219         fromPoint = faceSubdivisionsIt->second.subfaces.front().front().fvpAdj.at(blVInd)->P();
01220         toPoint = faceSubdivisionsIt->second.subfaces.front().back().fvpAdj.at(brVInd)->P();
01221         // assign new vertices
01222         for (size_t j = 0; j < n - 1; ++j, ++firstAddedVertexIt) {
01223           firstAddedVertexIt->P() = fromPoint + (toPoint - fromPoint) * (j + 1) / n;
01224           faceSubdivisionsIt->second.subfaces.front().at(j).fvpAdj.at(brVInd) = &*firstAddedVertexIt;
01225           faceSubdivisionsIt->second.subfaces.front().at(j+1).fvpAdj.at(blVInd) = &*firstAddedVertexIt;
01226         }
01227         if (faceSubdivisionsPrevIt != faceSubdivisions.end()) {
01228           if (runPos.F()->FFi(bottomEdge) == ptopEdge) {
01229             // update face-to-vertex adjacency
01230             for (size_t j = 0; j < n - 1; ++j) {
01231               faceSubdivisionsPrevIt->second.subfaces.back().at(j).fvpAdj.at(ptrVInd) = faceSubdivisionsIt->second.subfaces.front().at(j).fvpAdj.at(brVInd);
01232               faceSubdivisionsPrevIt->second.subfaces.back().at(j+1).fvpAdj.at(ptlVInd) = faceSubdivisionsIt->second.subfaces.front().at(j+1).fvpAdj.at(blVInd);
01233             }
01234             // update face-to-face adjacency
01235             for (size_t j = 0; j < n; ++j) {
01236               faceSubdivisionsIt->second.subfaces.front().at(j).ffpAdj.at(bottomEdge) = faceSubdivisionsPrevIt->second.subfaces.back().at(j).faceP;
01237               faceSubdivisionsIt->second.subfaces.front().at(j).ffiAdj.at(bottomEdge) = ptopEdge;
01238               faceSubdivisionsPrevIt->second.subfaces.back().at(j).ffpAdj.at(ptopEdge) = faceSubdivisionsIt->second.subfaces.front().at(j).faceP;
01239               faceSubdivisionsPrevIt->second.subfaces.back().at(j).ffiAdj.at(ptopEdge) = bottomEdge;
01240             }
01241           } else if (runPos.F()->FFi(bottomEdge) == prightEdge) {
01242             // update face-to-vertex adjacency
01243             for (size_t i = 0; i < n - 1; ++i) {
01244               faceSubdivisionsPrevIt->second.subfaces.at(i).back().fvpAdj.at(ptrVInd) = faceSubdivisionsIt->second.subfaces.front().at(n-i-1).fvpAdj.at(blVInd);
01245               faceSubdivisionsPrevIt->second.subfaces.at(i+1).back().fvpAdj.at(pbrVInd) = faceSubdivisionsIt->second.subfaces.front().at(n-i-2).fvpAdj.at(brVInd);
01246             }
01247             // update face-to-face adjacency
01248             for (size_t j = 0; j < n; ++j) {
01249               faceSubdivisionsIt->second.subfaces.front().at(j).ffpAdj.at(bottomEdge) = faceSubdivisionsPrevIt->second.subfaces.at(n-j-1).back().faceP;
01250               faceSubdivisionsIt->second.subfaces.front().at(j).ffiAdj.at(bottomEdge) = prightEdge;
01251               faceSubdivisionsPrevIt->second.subfaces.at(n-j-1).back().ffpAdj.at(prightEdge) = faceSubdivisionsIt->second.subfaces.front().at(j).faceP;
01252               faceSubdivisionsPrevIt->second.subfaces.at(n-j-1).back().ffiAdj.at(prightEdge) = bottomEdge;
01253             }
01254           } else {
01255             // must be pleftEdge
01256             // update face-to-vertex adjacency
01257             for (size_t i = 0; i < n - 1; ++i) {
01258               faceSubdivisionsPrevIt->second.subfaces.at(i).front().fvpAdj.at(ptlVInd) = faceSubdivisionsIt->second.subfaces.front().at(i).fvpAdj.at(brVInd);
01259               faceSubdivisionsPrevIt->second.subfaces.at(i+1).front().fvpAdj.at(pblVInd) = faceSubdivisionsIt->second.subfaces.front().at(i+1).fvpAdj.at(blVInd);
01260             }
01261             // update face-to-face adjacency
01262             for (size_t j = 0; j < n; ++j) {
01263               faceSubdivisionsIt->second.subfaces.front().at(j).ffpAdj.at(bottomEdge) = faceSubdivisionsPrevIt->second.subfaces.at(j).front().faceP;
01264               faceSubdivisionsIt->second.subfaces.front().at(j).ffiAdj.at(bottomEdge) = pleftEdge;
01265               faceSubdivisionsPrevIt->second.subfaces.at(j).front().ffpAdj.at(pleftEdge) = faceSubdivisionsIt->second.subfaces.front().at(j).faceP;
01266               faceSubdivisionsPrevIt->second.subfaces.at(j).front().ffiAdj.at(pleftEdge) = bottomEdge;
01267             }
01268           }
01269         } else {
01270           // must be on border
01271           // update face-to-face adjacency
01272           for (size_t j = 0; j < n; ++j) {
01273             faceSubdivisionsIt->second.subfaces.front().at(j).ffpAdj.at(bottomEdge) = faceSubdivisionsIt->second.subfaces.front().at(j).faceP;
01274             faceSubdivisionsIt->second.subfaces.front().at(j).ffiAdj.at(bottomEdge) = bottomEdge;
01275           }
01276         }
01277       } else if (runPos.E() == leftEdge) {
01278         // get pre-existing coords
01279         fromPoint = faceSubdivisionsIt->second.subfaces.front().front().fvpAdj.at(blVInd)->P();
01280         toPoint = faceSubdivisionsIt->second.subfaces.back().front().fvpAdj.at(tlVInd)->P();
01281         // assign new vertices
01282         for (size_t i = 0; i < n - 1; ++i, ++firstAddedVertexIt) {
01283           firstAddedVertexIt->P() = fromPoint + (toPoint - fromPoint) * (i + 1) / n;
01284           faceSubdivisionsIt->second.subfaces.at(i).front().fvpAdj.at(tlVInd) = &*firstAddedVertexIt;
01285           faceSubdivisionsIt->second.subfaces.at(i+1).front().fvpAdj.at(blVInd) = &*firstAddedVertexIt;
01286         }
01287         // can't be on border
01288         if (runPos.F()->FFi(leftEdge) == ptopEdge) {
01289           // update face-to-vertex adjacency
01290           for (size_t j = 0; j < n - 1; ++j) {
01291             faceSubdivisionsPrevIt->second.subfaces.back().at(j).fvpAdj.at(ptrVInd) = faceSubdivisionsIt->second.subfaces.at(n-j-1).front().fvpAdj.at(blVInd);
01292             faceSubdivisionsPrevIt->second.subfaces.back().at(j+1).fvpAdj.at(ptlVInd) = faceSubdivisionsIt->second.subfaces.at(n-j-2).front().fvpAdj.at(tlVInd);
01293           }
01294           // update face-to-face adjacency
01295           for (size_t i = 0; i < n; ++i) {
01296             faceSubdivisionsIt->second.subfaces.at(i).front().ffpAdj.at(leftEdge) = faceSubdivisionsPrevIt->second.subfaces.back().at(n-i-1).faceP;
01297             faceSubdivisionsIt->second.subfaces.at(i).front().ffiAdj.at(leftEdge) = ptopEdge;
01298             faceSubdivisionsPrevIt->second.subfaces.back().at(n-i-1).ffpAdj.at(ptopEdge) = faceSubdivisionsIt->second.subfaces.at(i).front().faceP;
01299             faceSubdivisionsPrevIt->second.subfaces.back().at(n-i-1).ffiAdj.at(ptopEdge) = leftEdge;
01300           }
01301         } else if (runPos.F()->FFi(leftEdge) == prightEdge) {
01302           // update face-to-vertex adjacency
01303           for (size_t i = 0; i < n - 1; ++i) {
01304             faceSubdivisionsPrevIt->second.subfaces.at(i).back().fvpAdj.at(ptrVInd) = faceSubdivisionsIt->second.subfaces.at(i).front().fvpAdj.at(tlVInd);
01305             faceSubdivisionsPrevIt->second.subfaces.at(i+1).back().fvpAdj.at(pbrVInd) = faceSubdivisionsIt->second.subfaces.at(i+1).front().fvpAdj.at(blVInd);
01306           }
01307           // update face-to-face adjacency
01308           for (size_t i = 0; i < n; ++i) {
01309             faceSubdivisionsIt->second.subfaces.at(i).front().ffpAdj.at(leftEdge) = faceSubdivisionsPrevIt->second.subfaces.at(i).back().faceP;
01310             faceSubdivisionsIt->second.subfaces.at(i).front().ffiAdj.at(leftEdge) = prightEdge;
01311             faceSubdivisionsPrevIt->second.subfaces.at(i).back().ffpAdj.at(prightEdge) = faceSubdivisionsIt->second.subfaces.at(i).front().faceP;
01312             faceSubdivisionsPrevIt->second.subfaces.at(i).back().ffiAdj.at(prightEdge) = leftEdge;
01313           }
01314         } else {
01315           // must be runPos.F()->FFi(leftEdge) == pleftEdge
01316           // update face-to-vertex adjacency
01317           for (size_t i = 0; i < n - 1; ++i) {
01318             faceSubdivisionsPrevIt->second.subfaces.at(i).front().fvpAdj.at(ptlVInd) = faceSubdivisionsIt->second.subfaces.front().at(n-i-1).fvpAdj.at(blVInd);
01319             faceSubdivisionsPrevIt->second.subfaces.at(i+1).front().fvpAdj.at(pblVInd) = faceSubdivisionsIt->second.subfaces.front().at(n-i-2).fvpAdj.at(tlVInd);
01320           }
01321           // update face-to-face adjacency
01322           for (size_t i = 0; i < n; ++i) {
01323             faceSubdivisionsIt->second.subfaces.at(i).front().ffpAdj.at(leftEdge) = faceSubdivisionsPrevIt->second.subfaces.at(n-i-1).front().faceP;
01324             faceSubdivisionsIt->second.subfaces.at(i).front().ffiAdj.at(leftEdge) = pleftEdge;
01325             faceSubdivisionsPrevIt->second.subfaces.at(n-i-1).front().ffpAdj.at(pleftEdge) = faceSubdivisionsIt->second.subfaces.at(i).front().faceP;
01326             faceSubdivisionsPrevIt->second.subfaces.at(n-i-1).front().ffiAdj.at(pleftEdge) = leftEdge;
01327           }
01328         }
01329       } else {
01330         // must be runPos.E() == rightEdge
01331         // get pre-existing coords
01332         fromPoint = faceSubdivisionsIt->second.subfaces.front().back().fvpAdj.at(brVInd)->P();
01333         toPoint = faceSubdivisionsIt->second.subfaces.back().back().fvpAdj.at(trVInd)->P();
01334         // assign new vertices
01335         for (size_t i = 0; i < n - 1; ++i, ++firstAddedVertexIt) {
01336           firstAddedVertexIt->P() = fromPoint + (toPoint - fromPoint) * (i + 1) / n;
01337           faceSubdivisionsIt->second.subfaces.at(i).back().fvpAdj.at(trVInd) = &*firstAddedVertexIt;
01338           faceSubdivisionsIt->second.subfaces.at(i+1).back().fvpAdj.at(brVInd) = &*firstAddedVertexIt;
01339         }
01340         // can't be on border
01341         if (runPos.F()->FFi(rightEdge) == ptopEdge) {
01342           // update face-to-vertex adjacency
01343           for (size_t j = 0; j < n - 1; ++j) {
01344             faceSubdivisionsPrevIt->second.subfaces.back().at(j).fvpAdj.at(ptrVInd) = faceSubdivisionsIt->second.subfaces.at(j).back().fvpAdj.at(trVInd);
01345             faceSubdivisionsPrevIt->second.subfaces.back().at(j+1).fvpAdj.at(ptlVInd) = faceSubdivisionsIt->second.subfaces.at(j+1).back().fvpAdj.at(brVInd);
01346           }
01347           // update face-to-face adjacency
01348           for (size_t i = 0; i < n; ++i) {
01349             faceSubdivisionsIt->second.subfaces.at(i).back().ffpAdj.at(rightEdge) = faceSubdivisionsPrevIt->second.subfaces.back().at(i).faceP;
01350             faceSubdivisionsIt->second.subfaces.at(i).back().ffiAdj.at(rightEdge) = ptopEdge;
01351             faceSubdivisionsPrevIt->second.subfaces.back().at(i).ffpAdj.at(ptopEdge) = faceSubdivisionsIt->second.subfaces.at(i).back().faceP;
01352             faceSubdivisionsPrevIt->second.subfaces.back().at(i).ffiAdj.at(ptopEdge) = rightEdge;
01353           }
01354         } else if (runPos.F()->FFi(rightEdge) == prightEdge) {
01355           // update face-to-vertex adjacency
01356           for (size_t i = 0; i < n - 1; ++i) {
01357             faceSubdivisionsPrevIt->second.subfaces.at(i).back().fvpAdj.at(ptrVInd) = faceSubdivisionsIt->second.subfaces.at(n-i-1).back().fvpAdj.at(brVInd);
01358             faceSubdivisionsPrevIt->second.subfaces.at(i+1).back().fvpAdj.at(pbrVInd) = faceSubdivisionsIt->second.subfaces.at(n-i-2).back().fvpAdj.at(trVInd);
01359           }
01360           // update face-to-face adjacency
01361           for (size_t i = 0; i < n; ++i) {
01362             faceSubdivisionsIt->second.subfaces.at(i).back().ffpAdj.at(rightEdge) = faceSubdivisionsPrevIt->second.subfaces.at(n-i-1).back().faceP;
01363             faceSubdivisionsIt->second.subfaces.at(i).back().ffiAdj.at(rightEdge) = prightEdge;
01364             faceSubdivisionsPrevIt->second.subfaces.at(n-i-1).back().ffpAdj.at(prightEdge) = faceSubdivisionsIt->second.subfaces.at(i).back().faceP;
01365             faceSubdivisionsPrevIt->second.subfaces.at(n-i-1).back().ffiAdj.at(prightEdge) = rightEdge;
01366           }
01367         } else {
01368           // must be runPos.F()->FFi(rightEdge) == pleftEdge
01369           // update face-to-vertex adjacency
01370           for (size_t i = 0; i < n - 1; ++i) {
01371             faceSubdivisionsPrevIt->second.subfaces.at(i).front().fvpAdj.at(ptlVInd) = faceSubdivisionsIt->second.subfaces.at(i).back().fvpAdj.at(trVInd);
01372             faceSubdivisionsPrevIt->second.subfaces.at(i+1).front().fvpAdj.at(pblVInd) = faceSubdivisionsIt->second.subfaces.at(i+1).back().fvpAdj.at(brVInd);
01373           }
01374           // update face-to-face adjacency
01375           for (size_t i = 0; i < n; ++i) {
01376             faceSubdivisionsIt->second.subfaces.at(i).back().ffpAdj.at(rightEdge) = faceSubdivisionsPrevIt->second.subfaces.at(i).front().faceP;
01377             faceSubdivisionsIt->second.subfaces.at(i).back().ffiAdj.at(rightEdge) = pleftEdge;
01378             faceSubdivisionsPrevIt->second.subfaces.at(i).front().ffpAdj.at(pleftEdge) = faceSubdivisionsIt->second.subfaces.at(i).back().faceP;
01379             faceSubdivisionsPrevIt->second.subfaces.at(i).front().ffiAdj.at(pleftEdge) = rightEdge;
01380           }
01381         }
01382       }
01383 
01384       // update subdivision's left and right sides face-to-face adjacency
01385       // go on left edge
01386       runPos.FlipE();
01387       runPos.FlipV();
01388       if (runPos.IsBorder()) {
01389         if (!runPos.F()->IsS()) {
01390           // must be runPos.E() == leftEdge and faceSubdivisionsIt->second.subfaces.size() == 1
01391           faceSubdivisionsIt->second.subfaces.front().front().ffpAdj.at(leftEdge) = faceSubdivisionsIt->second.subfaces.front().front().faceP;
01392           faceSubdivisionsIt->second.subfaces.front().front().ffiAdj.at(leftEdge) = leftEdge;
01393         }
01394       } else if (!runPos.FFlip()->IsV()) {
01395         // must be runPos.E() == leftEdge and faceSubdivisionsIt->second.subfaces.size() == 1
01396         assert(faceSubdivisionsIt->second.subfaces.size() == 1);
01397         faceSubdivisionsIt->second.subfaces.front().front().ffpAdj.at(leftEdge) = runPos.FFlip();
01398         faceSubdivisionsIt->second.subfaces.front().front().ffiAdj.at(leftEdge) = runPos.F()->FFi(leftEdge);
01399         externalFaces.push_back(ExternalFaceData(runPos.FFlip(),
01400                                                  faceSubdivisionsIt->second.subfaces.front().front().faceP,
01401                                                  runPos.F()->FFi(leftEdge),
01402                                                  leftEdge));
01403       } else if (!runPos.FFlip()->IsS() && !runPos.F()->IsS()) {
01404         // must be runPos.E() == leftEdge and faceSubdivisionsIt->second.subfaces.size() == 1
01405         faceSubdivisionsNeighbourIt = faceSubdivisions.find(runPos.FFlip());
01406         // must be faceSubdivisionsNeighbourIt != faceSubdivisions.end() and faceSubdivisionsNeighbourIt->second.subfaces.size() == 1
01407         pbottomEdge = faceSubdivisionsNeighbourIt->second.firstEdge;
01408         prightEdge = runPos.FFlip()->Next(pbottomEdge);
01409         ptopEdge = runPos.FFlip()->Next(prightEdge);
01410         pleftEdge = runPos.FFlip()->Next(ptopEdge);
01411         if (runPos.F()->FFi(leftEdge) == pleftEdge) {
01412           faceSubdivisionsIt->second.subfaces.front().front().ffpAdj.at(leftEdge) = faceSubdivisionsNeighbourIt->second.subfaces.front().front().faceP;
01413           faceSubdivisionsIt->second.subfaces.front().front().ffiAdj.at(leftEdge) = pleftEdge;
01414           faceSubdivisionsNeighbourIt->second.subfaces.front().front().ffpAdj.at(pleftEdge) = faceSubdivisionsIt->second.subfaces.front().front().faceP;
01415           faceSubdivisionsNeighbourIt->second.subfaces.front().front().ffiAdj.at(pleftEdge) = leftEdge;
01416         } else {
01417           // must be runPos.F()->FFi(leftEdge) == prightEdge
01418           faceSubdivisionsIt->second.subfaces.front().front().ffpAdj.at(leftEdge) = faceSubdivisionsNeighbourIt->second.subfaces.front().back().faceP;
01419           faceSubdivisionsIt->second.subfaces.front().front().ffiAdj.at(leftEdge) = prightEdge;
01420           faceSubdivisionsNeighbourIt->second.subfaces.front().back().ffpAdj.at(prightEdge) = faceSubdivisionsIt->second.subfaces.front().front().faceP;
01421           faceSubdivisionsNeighbourIt->second.subfaces.front().back().ffiAdj.at(prightEdge) = leftEdge;
01422         }
01423       }
01424       // go on right edge
01425       runPos.FlipE();
01426       runPos.FlipV();
01427       runPos.FlipE();
01428       if (runPos.IsBorder()) {
01429         if (!runPos.F()->IsS()) {
01430           // must be runPos.E() == rightEdge and faceSubdivisionsIt->second.subfaces.size() == 1
01431           faceSubdivisionsIt->second.subfaces.front().back().ffpAdj.at(rightEdge) = faceSubdivisionsIt->second.subfaces.front().back().faceP;
01432           faceSubdivisionsIt->second.subfaces.front().back().ffiAdj.at(rightEdge) = rightEdge;
01433         }
01434       } else if (!runPos.FFlip()->IsV()) {
01435         // must be runPos.E() == rightEdge and faceSubdivisionsIt->second.subfaces.size() == 1
01436         faceSubdivisionsIt->second.subfaces.front().back().ffpAdj.at(rightEdge) = runPos.FFlip();
01437         faceSubdivisionsIt->second.subfaces.front().back().ffiAdj.at(rightEdge) = runPos.F()->FFi(rightEdge);
01438         externalFaces.push_back(ExternalFaceData(runPos.FFlip(),
01439                                                  faceSubdivisionsIt->second.subfaces.front().back().faceP,
01440                                                  runPos.F()->FFi(rightEdge),
01441                                                  rightEdge));
01442       } else if (!runPos.FFlip()->IsS() && !runPos.F()->IsS()) {
01443         // must be runPos.E() == rightEdge and faceSubdivisionsIt->second.subfaces.size() == 1
01444         faceSubdivisionsNeighbourIt = faceSubdivisions.find(runPos.FFlip());
01445         // must be faceSubdivisionsNeighbourIt != faceSubdivisions.end() and faceSubdivisionsNeighbourIt->second.subfaces.size() == 1
01446         pbottomEdge = faceSubdivisionsNeighbourIt->second.firstEdge;
01447         prightEdge = runPos.FFlip()->Next(pbottomEdge);
01448         ptopEdge = runPos.FFlip()->Next(prightEdge);
01449         pleftEdge = runPos.FFlip()->Next(ptopEdge);
01450         if (runPos.F()->FFi(rightEdge) == pleftEdge) {
01451           faceSubdivisionsIt->second.subfaces.front().back().ffpAdj.at(rightEdge) = faceSubdivisionsNeighbourIt->second.subfaces.front().front().faceP;
01452           faceSubdivisionsIt->second.subfaces.front().back().ffiAdj.at(rightEdge) = pleftEdge;
01453           faceSubdivisionsNeighbourIt->second.subfaces.front().front().ffpAdj.at(pleftEdge) = faceSubdivisionsIt->second.subfaces.front().back().faceP;
01454           faceSubdivisionsNeighbourIt->second.subfaces.front().front().ffiAdj.at(pleftEdge) = rightEdge;
01455         } else {
01456           // must be runPos.F()->FFi(rightEdge) == prightEdge
01457           faceSubdivisionsIt->second.subfaces.front().back().ffpAdj.at(rightEdge) = faceSubdivisionsNeighbourIt->second.subfaces.front().back().faceP;
01458           faceSubdivisionsIt->second.subfaces.front().back().ffiAdj.at(rightEdge) = prightEdge;
01459           faceSubdivisionsNeighbourIt->second.subfaces.front().back().ffpAdj.at(prightEdge) = faceSubdivisionsIt->second.subfaces.front().back().faceP;
01460           faceSubdivisionsNeighbourIt->second.subfaces.front().back().ffiAdj.at(prightEdge) = rightEdge;
01461         }
01462       }
01463 
01464       // go on top edge
01465       runPos.FlipE();
01466       runPos.FlipV();
01467       if (runPos.IsBorder()) {
01468         // assign top edge vertices and face-to-border adjacency
01469         if (runPos.E() == topEdge) {
01470           // get pre-existing coords
01471           fromPoint = faceSubdivisionsIt->second.subfaces.back().front().fvpAdj.at(tlVInd)->P();
01472           toPoint = faceSubdivisionsIt->second.subfaces.back().back().fvpAdj.at(trVInd)->P();
01473           // assign new vertices
01474           for (size_t j = 0; j < n - 1; ++j, ++firstAddedVertexIt) {
01475             firstAddedVertexIt->P() = fromPoint + (toPoint - fromPoint) * (j + 1) / n;
01476             faceSubdivisionsIt->second.subfaces.back().at(j).fvpAdj.at(trVInd) = &*firstAddedVertexIt;
01477             faceSubdivisionsIt->second.subfaces.back().at(j+1).fvpAdj.at(tlVInd) = &*firstAddedVertexIt;
01478           }
01479           // update face-to-face adjacency
01480           for (size_t j = 0; j < n; ++j) {
01481             faceSubdivisionsIt->second.subfaces.back().at(j).ffpAdj.at(topEdge) = faceSubdivisionsIt->second.subfaces.back().at(j).faceP;
01482             faceSubdivisionsIt->second.subfaces.back().at(j).ffiAdj.at(topEdge) = topEdge;
01483           }
01484         } else if (runPos.E() == leftEdge) {
01485           // get pre-existing coords
01486           fromPoint = faceSubdivisionsIt->second.subfaces.front().front().fvpAdj.at(blVInd)->P();
01487           toPoint = faceSubdivisionsIt->second.subfaces.back().front().fvpAdj.at(tlVInd)->P();
01488           // assign new vertices
01489           for (size_t i = 0; i < n - 1; ++i, ++firstAddedVertexIt) {
01490             firstAddedVertexIt->P() = fromPoint + (toPoint - fromPoint) * (i + 1) / n;
01491             faceSubdivisionsIt->second.subfaces.at(i).front().fvpAdj.at(tlVInd) = &*firstAddedVertexIt;
01492             faceSubdivisionsIt->second.subfaces.at(i+1).front().fvpAdj.at(blVInd) = &*firstAddedVertexIt;
01493           }
01494           // update face-to-face adjacency
01495           for (size_t i = 0; i < n; ++i) {
01496             faceSubdivisionsIt->second.subfaces.at(i).front().ffpAdj.at(leftEdge) = faceSubdivisionsIt->second.subfaces.at(i).front().faceP;
01497             faceSubdivisionsIt->second.subfaces.at(i).front().ffiAdj.at(leftEdge) = leftEdge;
01498           }
01499         } else {
01500           // must be runPos.E() == rightEdge
01501           // get pre-existing coords
01502           fromPoint = faceSubdivisionsIt->second.subfaces.front().back().fvpAdj.at(brVInd)->P();
01503           toPoint = faceSubdivisionsIt->second.subfaces.back().back().fvpAdj.at(trVInd)->P();
01504           // assign new vertices
01505           for (size_t i = 0; i < n - 1; ++i, ++firstAddedVertexIt) {
01506             firstAddedVertexIt->P() = fromPoint + (toPoint - fromPoint) * (i + 1) / n;
01507             faceSubdivisionsIt->second.subfaces.at(i).back().fvpAdj.at(trVInd) = &*firstAddedVertexIt;
01508             faceSubdivisionsIt->second.subfaces.at(i+1).back().fvpAdj.at(brVInd) = &*firstAddedVertexIt;
01509           }
01510           // update face-to-face adjacency
01511           for (size_t i = 0; i < n; ++i) {
01512             faceSubdivisionsIt->second.subfaces.at(i).back().ffpAdj.at(rightEdge) = faceSubdivisionsIt->second.subfaces.at(i).back().faceP;
01513             faceSubdivisionsIt->second.subfaces.at(i).back().ffiAdj.at(rightEdge) = rightEdge;
01514           }
01515         }
01516       } else {
01517         // go onto the next face
01518         runPos.FlipF();
01519       }
01520     } while (!runPos.IsBorder() && runPos != startPos);
01521 
01522     // final pass: compute coords of new internal vertices, copy all data into mesh and clear flags
01523     for (faceSubdivisionsIt = faceSubdivisions.begin(); faceSubdivisionsIt != faceSubdivisions.end(); ++faceSubdivisionsIt) {
01524       // clear flags
01525       faceSubdivisionsIt->first->ClearV();
01526       if (faceSubdivisionsIt->first->IsS())
01527         faceSubdivisionsIt->first->ClearS();
01528 
01529       // get vertex indices
01530       blVInd = faceSubdivisionsIt->second.firstVertex;
01531       brVInd = faceSubdivisionsIt->first->Next(blVInd);
01532 
01533       // compute coords on bottom side and internal, horizontally
01534       for (size_t i = 1; i < faceSubdivisionsIt->second.subfaces.size(); ++i) {
01535         fromPoint = faceSubdivisionsIt->second.subfaces.at(i).front().fvpAdj.at(blVInd)->P();
01536         toPoint = faceSubdivisionsIt->second.subfaces.at(i).back().fvpAdj.at(brVInd)->P();
01537         for (size_t j = 1; j < n; ++j)
01538           faceSubdivisionsIt->second.subfaces.at(i).at(j).fvpAdj.at(blVInd)->P() = fromPoint + (toPoint - fromPoint) * j / n;
01539       }
01540 
01541       // finally, copy data into mesh
01542       for (size_t i = 0; i < faceSubdivisionsIt->second.subfaces.size(); ++i)
01543         for (size_t j = 0; j < n; ++j) {
01544           faceP = faceSubdivisionsIt->second.subfaces.at(i).at(j).faceP;
01545           for (size_t k = 0; k < faceSubdivisionsIt->second.subfaces.at(i).at(j).ffpAdj.size(); ++k)
01546             faceP->FFp(k) = faceSubdivisionsIt->second.subfaces.at(i).at(j).ffpAdj.at(k);
01547           for (size_t k = 0; k < faceSubdivisionsIt->second.subfaces.at(i).at(j).ffiAdj.size(); ++k)
01548             faceP->FFi(k) = faceSubdivisionsIt->second.subfaces.at(i).at(j).ffiAdj.at(k);
01549           for (size_t k = 0; k < faceSubdivisionsIt->second.subfaces.at(i).at(j).fvpAdj.size(); ++k)
01550             faceP->V(k) = faceSubdivisionsIt->second.subfaces.at(i).at(j).fvpAdj.at(k);
01551         }
01552     }
01553     // very last step: update external faces adjacency
01554     for (externalFacesIt = externalFaces.begin(); externalFacesIt != externalFaces.end(); ++externalFacesIt) {
01555       externalFacesIt->faceTo->FFp(externalFacesIt->edgeTo) = externalFacesIt->faceFrom;
01556       externalFacesIt->faceTo->FFi(externalFacesIt->edgeTo) = externalFacesIt->edgeFrom;
01557     }
01558     // very very last step: update pos
01559     pos.V() = pos.F()->V(posVInd);
01560   }
01561 
01568   static void SplitPolychord (PolyMeshType &mesh, vcg::face::Pos<FaceType> &pos, const size_t n) {
01569     std::vector<FacePointer *> facesToUpdate;
01570     std::vector<VertexPointer *> verticesToUpdate;
01571     SplitPolychord(mesh, pos, n, facesToUpdate, verticesToUpdate);
01572   }
01573 
01581   static PC_ResultCode CheckPolychordFindStartPosition (const vcg::face::Pos<FaceType> &pos,
01582                                                         vcg::face::Pos<FaceType> &startPos,
01583                                                         const bool checkSing = true) {
01584     assert(!pos.IsNull());
01585     int valence = 0;
01586     bool singSideA = false, singSideB = false;
01587     bool borderSideA = false, borderSideB = false;
01588     bool polyBorderFound = false;
01589     vcg::face::JumpingPos<FaceType> jmpPos;
01590 
01591     startPos = pos;
01592     do {
01593       // check if it is a quad
01594       if (startPos.F()->VN() != 4)
01595         return PC_NOTQUAD;
01596       // check manifoldness
01597       if (IsVertexAdjacentToAnyNonManifoldEdge(startPos))
01598         return PC_NOTMANIF;
01599       startPos.FlipV();
01600       if (IsVertexAdjacentToAnyNonManifoldEdge(startPos))
01601         return PC_NOTMANIF;
01602       startPos.FlipV();
01603 
01604       // check if side A is on border
01605       startPos.FlipE();
01606       if (startPos.IsBorder())
01607         borderSideA = true;
01608       startPos.FlipE();
01609       // check if side B is on border
01610       startPos.FlipV();
01611       startPos.FlipE();
01612       if (startPos.IsBorder())
01613         borderSideB = true;
01614       startPos.FlipE();
01615       startPos.FlipV();
01616 
01617       // check if singularities are not in both sides
01618       if (checkSing) {
01619         // compute the valence of the vertex on side B
01620         startPos.FlipV();
01621         valence = startPos.NumberOfIncidentVertices();
01622         // if the vertex is on border increment its valence by 1 (virtually connect it to a dummy vertex)
01623         jmpPos.Set(startPos.F(), startPos.E(), startPos.V());
01624         if (jmpPos.FindBorder())
01625           ++valence;
01626         if (valence != 4)
01627           singSideB = true;
01628         // a 2-valence internl vertex cause a polychord to touch itself, producing non-2manifoldness
01629         // in that case, a 2-valence vertex is dealt as 2 singularities in both sides
01630         if (valence == 2 && !borderSideB)
01631           singSideA = true;
01632         // compute the valence of the vertex on side A
01633         startPos.FlipV();
01634         valence = startPos.NumberOfIncidentVertices();
01635         // if the vertex is on border increment its valence by 1 (virtually connect it to a dummy vertex)
01636         jmpPos.Set(startPos.F(), startPos.E(), startPos.V());
01637         if (jmpPos.FindBorder())
01638           ++valence;
01639         if (valence != 4)
01640           singSideA = true;
01641         // a 2-valence internal vertex cause a polychord to touch itself, producing non-2manifoldness
01642         // in that case, a 2-valence vertex is dealt as 2 singularities in both sides
01643         if (valence == 2 && !borderSideA)
01644           singSideB = true;
01645       }
01646 
01647       // if the first border has been reached, go on the other direction to find the other border
01648       if (startPos != pos && startPos.IsBorder() && !polyBorderFound) {
01649         startPos = pos;
01650         startPos.FlipF();
01651         polyBorderFound = true;
01652       }
01653 
01654       // if the other border has been reached, return
01655       if (polyBorderFound && startPos.IsBorder())
01656         break;
01657 
01658       // go to the next edge
01659       startPos.FlipE();
01660       startPos.FlipV();
01661       startPos.FlipE();
01662       // check manifoldness
01663       if (IsVertexAdjacentToAnyNonManifoldEdge(startPos))
01664         return PC_NOTMANIF;
01665       startPos.FlipV();
01666       if (IsVertexAdjacentToAnyNonManifoldEdge(startPos))
01667         return PC_NOTMANIF;
01668       startPos.FlipV();
01669       // go to the next face
01670       startPos.FlipF();
01671     } while (startPos != pos);
01672 
01673     // polychord with singularities on both sides can not collapse
01674     if ((singSideA && singSideB) ||
01675         (singSideA && borderSideB) ||
01676         (singSideB && borderSideA))
01677       return PC_SINGBOTH;
01678 
01679     // polychords that are rings and have borders on both sides can not collapse
01680     if (!polyBorderFound && borderSideA && borderSideB)
01681       return PC_SINGBOTH;
01682 
01683     // if there are singularities or borders on the side A, remember to keep coordinates on it
01684     if (singSideA || borderSideA)
01685       return PC_SINGSIDEA;
01686     // if there are singularities or borders on the side B, remember to keep coordinates on it
01687     if (singSideB || borderSideB)
01688       return PC_SINGSIDEB;
01689 
01690     return PC_SUCCESS;
01691   }
01692 
01701   static void VisitPolychord (const PolyMeshType &mesh,
01702                               const vcg::face::Pos<FaceType> &startPos,
01703                               PC_Chords &chords,
01704                               const unsigned long mark,
01705                               const PC_ResultCode q) {
01706     assert(!startPos.IsNull());
01707     vcg::face::Pos<FaceType> tmpPos, runPos = startPos;
01708     std::pair<size_t, unsigned char> face_edge(std::numeric_limits<size_t>::max(), 0);
01709 
01710     // follow the sequence of quads
01711     do {
01712       // check manifoldness
01713       tmpPos = runPos;
01714       do {
01715         if (runPos.F()->VN() != 4)  // non-quads are not visited
01716           return;
01717         if (!tmpPos.IsManifold()) {
01718           // update current coord
01719           face_edge.first = vcg::tri::Index(mesh, tmpPos.F());
01720           face_edge.second = tmpPos.E()%2;
01721           chords.UpdateCoord(chords[face_edge], mark, q);
01722           face_edge.second = (tmpPos.E()+1)%2;
01723           chords.UpdateCoord(chords[face_edge], mark, q);
01724           return;
01725         }
01726         tmpPos.FlipV();
01727         tmpPos.FlipE();
01728       } while (tmpPos != runPos);
01729 
01730       // update current coord
01731       face_edge.first = vcg::tri::Index(mesh, runPos.F());
01732       face_edge.second = runPos.E()%2;
01733       chords.UpdateCoord(chords[face_edge], mark, q);
01734       // if the polychord has to collapse, i.e. q == PC_SUCCESS, also visit the orthogonal coord
01735       if (q == PC_SUCCESS) {
01736         face_edge.second = (runPos.E()+1)%2;
01737         chords.UpdateCoord(chords[face_edge], mark, q);
01738       }
01739 
01740       runPos.FlipE();
01741       runPos.FlipV();
01742       runPos.FlipE();
01743       runPos.FlipF();
01744     } while (runPos != startPos && !runPos.IsBorder() && runPos.F()->VN() == 4);
01745     assert(runPos == startPos || vcg::face::IsBorder(*startPos.F(),startPos.E())
01746            || runPos.F()->VN() != 4 || startPos.FFlip()->VN() != 4);
01747   }
01748 
01754   static bool IsVertexAdjacentToAnyNonManifoldEdge (const vcg::face::Pos<FaceType> &pos) {
01755     assert(!pos.IsNull());
01756     vcg::face::JumpingPos<FaceType> jmpPos;
01757     jmpPos.Set(pos.F(), pos.E(), pos.V());
01758     do {
01759       assert(!jmpPos.FFlip()->IsD());
01760       if (!jmpPos.IsManifold())
01761         return true;
01762       jmpPos.NextFE();
01763     } while (jmpPos != pos);
01764     return false;
01765   }
01766 
01777   static bool IsPolychordSelfIntersecting (const PolyMeshType &mesh,
01778                                            const vcg::face::Pos<FaceType> &startPos,
01779                                            const PC_Chords &chords,
01780                                            const unsigned long mark) {
01781     assert(!startPos.IsNull());
01782     vcg::face::Pos<FaceType> runPos = startPos;
01783     vcg::face::Pos<FaceType> tmpPos;
01784     std::pair<size_t, unsigned char> face_edge(std::numeric_limits<size_t>::max(), 0);
01785     do {
01786       assert(runPos.F()->VN() == 4);
01787       // check if we've already crossed this face
01788       face_edge.first = vcg::tri::Index(mesh, runPos.F());
01789       face_edge.second = (runPos.E()+1)%2;
01790       if (chords[face_edge].mark == mark)
01791         return true;
01792       // if this coord is adjacent to another coord of the same polychord
01793       // i.e., this polychord touches itself without intersecting
01794       // it might cause a wrong collapse, producing holes and non-2manifoldness
01795       tmpPos = runPos;
01796       tmpPos.FlipE();
01797       if (!tmpPos.IsBorder()) {
01798         tmpPos.FlipF();
01799         face_edge.first = vcg::tri::Index(mesh, tmpPos.F());
01800         face_edge.second = (tmpPos.E()+1)%2;
01801         if (chords[face_edge].mark == mark)
01802           return true;
01803         // this should never hapen:
01804         face_edge.second = tmpPos.E()%2;
01805         if (chords[face_edge].mark == mark)
01806           return true;
01807       }
01808       tmpPos = runPos;
01809       tmpPos.FlipV();
01810       tmpPos.FlipE();
01811       if (!tmpPos.IsBorder()) {
01812         tmpPos.FlipF();
01813         face_edge.first = vcg::tri::Index(mesh, tmpPos.F());
01814         face_edge.second = (tmpPos.E()+1)%2;
01815         if (chords[face_edge].mark == mark)
01816           return true;
01817         // this should never hapen:
01818         face_edge.second = tmpPos.E()%2;
01819         if (chords[face_edge].mark == mark)
01820           return true;
01821       }
01822       runPos.FlipE();
01823       runPos.FlipV();
01824       runPos.FlipE();
01825       runPos.FlipF();
01826     } while (runPos != startPos && !runPos.IsBorder());
01827 
01828     return false;
01829   }
01830 
01841   static bool WillPolychordBeManifold(const PolyMeshType &mesh,
01842                                       const vcg::face::Pos<FaceType> &startPos,
01843                                       PC_Chords &chords,
01844                                       const unsigned long mark) {
01845     assert(!startPos.IsNull());
01846     vcg::face::Pos<FaceType> runPos = startPos;
01847     vcg::face::JumpingPos<FaceType> tmpPos;
01848     std::pair<size_t, unsigned char> face_edge1(std::numeric_limits<size_t>::max(), 0);
01849     std::pair<size_t, unsigned char> face_edge2(std::numeric_limits<size_t>::max(), 0);
01850     bool in = true;
01851     unsigned int nTraversal = 0;
01852 
01853     // second step: check
01854     runPos = startPos;
01855     do {
01856       face_edge1.first = vcg::tri::Index(mesh, runPos.F());
01857       face_edge1.second = runPos.E() % 2;
01858       assert(chords[face_edge1].mark == mark);
01859       // check one vertex
01860       runPos.FlipV();
01861       in = true;
01862       nTraversal = 0;
01863       tmpPos.Set(runPos.F(), runPos.E(), runPos.V());
01864       do {
01865         if (tmpPos.IsBorder() && in) {
01866           in = false;
01867           nTraversal++;
01868         }
01869         // go to next edge
01870         tmpPos.NextFE();
01871         // check if this face is already visited
01872         face_edge1.first = vcg::tri::Index(mesh, tmpPos.F());
01873         face_edge1.second = tmpPos.E() % 2;
01874         face_edge2.first = vcg::tri::Index(mesh, tmpPos.F());
01875         face_edge2.second = (tmpPos.E() + 1) % 2;
01876         if (in && chords[face_edge1].mark != mark && chords[face_edge2].mark != mark) {
01877           in = false;
01878           ++nTraversal;
01879         } else if (!in && (chords[face_edge1].mark == mark || chords[face_edge2].mark == mark)) {
01880           in = true;
01881           ++nTraversal;
01882         }
01883       } while (tmpPos != runPos);
01884       assert(in);
01885       assert(nTraversal % 2 == 0);
01886       if (nTraversal > 2)
01887         return false;
01888 
01889       // check other vertex
01890       runPos.FlipV();
01891       in = true;
01892       nTraversal = 0;
01893       tmpPos.Set(runPos.F(), runPos.E(), runPos.V());
01894       do {
01895         if (tmpPos.IsBorder() && in) {
01896           in = false;
01897           ++nTraversal;
01898         }
01899         // go to next edge
01900         tmpPos.NextFE();
01901         // check if this face is already visited
01902         face_edge1.first = vcg::tri::Index(mesh, tmpPos.F());
01903         face_edge1.second = tmpPos.E() % 2;
01904         face_edge2.first = vcg::tri::Index(mesh, tmpPos.F());
01905         face_edge2.second = (tmpPos.E() + 1) % 2;
01906         if (in && chords[face_edge1].mark != mark && chords[face_edge2].mark != mark) {
01907           in = false;
01908           nTraversal++;
01909         } else if (!in && (chords[face_edge1].mark == mark || chords[face_edge2].mark == mark)) {
01910           in = true;
01911           ++nTraversal;
01912         }
01913       } while (tmpPos != runPos);
01914       assert(in);
01915       assert(nTraversal % 2 == 0);
01916       if (nTraversal > 2)
01917         return false;
01918 
01919       runPos.FlipE();
01920       runPos.FlipV();
01921       runPos.FlipE();
01922       runPos.FlipF();
01923     } while (runPos != startPos && !runPos.IsBorder());
01924     if (runPos.IsBorder()) {
01925       // check one vertex
01926       runPos.FlipV();
01927       in = true;
01928       nTraversal = 0;
01929       tmpPos.Set(runPos.F(), runPos.E(), runPos.V());
01930       do {
01931         if (tmpPos.IsBorder() && in) {
01932           in = false;
01933           ++nTraversal;
01934         }
01935         // go to next edge
01936         tmpPos.NextFE();
01937         // check if this face is already visited
01938         face_edge1.first = vcg::tri::Index(mesh, tmpPos.F());
01939         face_edge1.second = tmpPos.E() % 2;
01940         face_edge2.first = vcg::tri::Index(mesh, tmpPos.F());
01941         face_edge2.second = (tmpPos.E() + 1) % 2;
01942         if (in && chords[face_edge1].mark != mark && chords[face_edge2].mark != mark) {
01943           in = false;
01944           ++nTraversal;
01945         } else if (!in && (chords[face_edge1].mark == mark || chords[face_edge2].mark == mark)) {
01946           in = true;
01947           ++nTraversal;
01948         }
01949       } while (tmpPos != runPos);
01950       assert(in);
01951       assert(nTraversal % 2 == 0);
01952       if (nTraversal > 2)
01953         return false;
01954 
01955       // check other vertex
01956       runPos.FlipV();
01957       in = true;
01958       nTraversal = 0;
01959       tmpPos.Set(runPos.F(), runPos.E(), runPos.V());
01960       do {
01961         if (tmpPos.IsBorder() && in) {
01962           in = false;
01963           ++nTraversal;
01964         }
01965         // go to next edge
01966         tmpPos.NextFE();
01967         // check if this face is already visited
01968         face_edge1.first = vcg::tri::Index(mesh, tmpPos.F());
01969         face_edge1.second = tmpPos.E() % 2;
01970         face_edge2.first = vcg::tri::Index(mesh, tmpPos.F());
01971         face_edge2.second = (tmpPos.E() + 1) % 2;
01972         if (in && chords[face_edge1].mark != mark && chords[face_edge2].mark != mark) {
01973           in = false;
01974           ++nTraversal;
01975         } else if (!in && (chords[face_edge1].mark == mark || chords[face_edge2].mark == mark)) {
01976           in = true;
01977           ++nTraversal;
01978         }
01979       } while (tmpPos != runPos);
01980       assert(in);
01981       assert(nTraversal % 2 == 0);
01982       if (nTraversal > 2)
01983         return false;
01984     }
01985 
01986     return true;
01987   }
01988 };
01989 
01990 }
01991 }
01992 
01993 #endif // POLYGON_Polychord_COLLAPSE_H


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