clip.h
Go to the documentation of this file.
00001 /****************************************************************************
00002 * VCGLib                                                            o o     *
00003 * Visual and Computer Graphics Library                            o     o   *
00004 *                                                                _   O  _   *
00005 * Copyright(C) 2004                                                \/)\/    *
00006 * Visual Computing Lab                                            /\/|      *
00007 * ISTI - Italian National Research Council                           |      *
00008 *                                                                    \      *
00009 * All rights reserved.                                                      *
00010 *                                                                           *
00011 * This program is free software; you can redistribute it and/or modify      *
00012 * it under the terms of the GNU General Public License as published by      *
00013 * the Free Software Foundation; either version 2 of the License, or         *
00014 * (at your option) any later version.                                       *
00015 *                                                                           *
00016 * This program is distributed in the hope that it will be useful,           *
00017 * but WITHOUT ANY WARRANTY; without even the implied warranty of            *
00018 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the             *
00019 * GNU General Public License (http://www.gnu.org/licenses/gpl.txt)          *
00020 * for more details.                                                         *
00021 *                                                                           *
00022 ****************************************************************************/
00023 
00024 #ifndef __VCGLIB_TRI_CLIP
00025 #define __VCGLIB_TRI_CLIP
00026 #include <unordered_map>
00027 #include <vcg/complex/complex.h>
00028 
00029 namespace vcg
00030 {
00031 namespace tri
00032 {
00033 
00034   template <typename MESH_TYPE>
00035   class GenericVertexInterpolator
00036   {
00037   public:
00038     typedef typename MESH_TYPE::VertexType VertexType;
00039     typedef GenericVertexInterpolator<MESH_TYPE> ClassType;
00040     typedef typename VertexType::CoordType CoordType;
00041     typedef typename CoordType::ScalarType ScalarType;
00042     GenericVertexInterpolator(MESH_TYPE &_m) : m(_m) {}
00043   private:
00044     MESH_TYPE &m;
00045   public:
00046     inline void operator () (const VertexType & v0, const VertexType & v1, const VertexType & v2, const ScalarType & a, const ScalarType & b, VertexType & r) const
00047     {
00048       // position
00049       r.P() = v0.cP() + (v1.cP() - v0.cP()) * a + (v2.cP() - v0.cP()) * b;
00050 
00051       // normal
00052       if (tri::HasPerVertexNormal(m))
00053       {
00054         r.N() = v0.cN() + (v1.cN() - v0.cN()) * a + (v2.cN() - v0.cN()) * b;
00055       }
00056 
00057       // color
00058       if (tri::HasPerVertexColor(m))
00059       {
00060         vcg::Point4<ScalarType> vc[3];
00061         vc[0].Import(v0.cC());
00062         vc[1].Import(v1.cC());
00063         vc[2].Import(v2.cC());
00064         const vcg::Point4<ScalarType> rc = (vc[0] + (vc[1] - vc[0]) * a + (vc[2] - vc[0]) * b);
00065         r.C()[0] = (typename vcg::Color4b::ScalarType)(rc[0]);
00066         r.C()[1] = (typename vcg::Color4b::ScalarType)(rc[1]);
00067         r.C()[2] = (typename vcg::Color4b::ScalarType)(rc[2]);
00068         r.C()[3] = (typename vcg::Color4b::ScalarType)(rc[3]);
00069       }
00070 
00071       // texcoord
00072       if (tri::HasPerVertexTexCoord(m))
00073       {
00074         const short nt = 1; //typename VertexType::TextureType::N();
00075         for (short i=0; i<nt; ++i)
00076         {
00077           r.T().t(i) = v0.cT().t(i) + (v1.cT().t(i) - v0.cT().t(i)) * a + (v2.cT().t(i) - v0.cT().t(i)) * b;
00078         }
00079       }
00080     }
00081   };
00082 template <typename TRIMESHTYPE>
00083 class TriMeshClipper
00084 {
00085 public:
00086 
00087   typedef TriMeshClipper<TRIMESHTYPE> ClassType;
00088   typedef TRIMESHTYPE TriMeshType;
00089   typedef typename TriMeshType::FaceType FaceType;
00090   typedef typename FaceType::VertexType VertexType;
00091   typedef typename VertexType::CoordType CoordType;
00092   typedef typename CoordType::ScalarType ScalarType;
00093 
00094   /*
00095     static inline void Box(const Box3<ScalarType> & b, VERTEXINTEPOLATOR & vInterp, TriMeshType & m);
00096 
00097     Clip mesh "m" against an axis aligned box (in place version);
00098 
00099     Notes:
00100       1) faces marked as deleted are skipped;
00101       2) faces completely outside box are marked as deleted;
00102       3) faces completely inside box are left unchanged;
00103       4) faces intersecting box's sides are marked as deleted:
00104          they are replaced with proper tesselation; new vertices and faces
00105          are created, so reallocation could occour; previously saved pointers
00106          could not to be valid anymore, thus they should be updated;
00107       5) vInterp functor must implement a n operator with signature
00108              void operator () (const VERTEX & v0, const VERTEX & v1, const VERTEX & v2, const Scalar & a, const Scalar & b, VERTEX & r);
00109          its semantic is to intepolate vertex attribute across triangle; a typical implementation is;
00110            r.P() = v0.P() + a * (v1.P() - v0.P()) + b * (v2.P() - v0.P());  // interpolate position
00111            r.N() = v0.N() + a * (v1.N() - v0.N()) + b * (v2.N() - v0.N());  // interpolate normal
00112            ...    // interpolate other vertex attributes
00113   */
00114   template <class ScalarType>
00115       class VertexClipInfo
00116   {
00117   public:
00118 //                      typedef VertexClipInfo ClassType;
00119 
00120     ScalarType fU;
00121     ScalarType fV;
00122     unsigned int idx;
00123     unsigned int tref;
00124   };
00125   typedef typename std::vector< VertexClipInfo<ScalarType> > VertexClipInfoVec;
00126   class TriangleInfo
00127   {
00128   public:
00129     typedef TriangleInfo ClassType;
00130 
00131     unsigned int v[3];
00132     unsigned int idx;
00133   };
00134 
00135   typedef std::vector<TriangleInfo> TriangleInfoVec;
00136 
00137   class EdgeIsect
00138   {
00139   public:
00140     CoordType p;
00141     unsigned int idx;
00142   };
00143 
00144   template <typename VERTEXINTEPOLATOR>
00145   static inline void Box(const Box3<ScalarType> & b, VERTEXINTEPOLATOR & vInterp, TriMeshType & m)
00146   {
00147     std::vector<unsigned int> facesToDelete;
00148     ClassType::Box(b, vInterp, m, facesToDelete);
00149     for (size_t i=0; i<facesToDelete.size(); ++i)
00150     {
00151       m.face[facesToDelete[i]].SetD();
00152     }
00153   }
00154 
00155   class EdgeIntersections
00156   {
00157   public:
00158     unsigned int n;
00159     EdgeIsect isects[6];
00160 
00161     EdgeIntersections(void)
00162     {
00163       this->n = 0;
00164     }
00165   };
00166 
00167   typedef std::unordered_map<unsigned int, EdgeIntersections> UIntHMap;
00168   typedef typename UIntHMap::iterator UIntHMap_i;
00169   typedef typename UIntHMap::value_type UIntHMap_v;
00170 
00171   typedef std::unordered_map<unsigned int, UIntHMap> EdgeMap;
00172   typedef typename EdgeMap::iterator EdgeMap_i;
00173   typedef typename EdgeMap::value_type EdgeMap_v;
00174 
00175   typedef typename TriMeshType::FaceIterator FaceIterator;
00176 
00177   template <typename VERTEXINTEPOLATOR, typename FACEINDEXCONTAINER>
00178   static inline void Box(const Box3<ScalarType> & b, VERTEXINTEPOLATOR & vInterp, TriMeshType & m, FACEINDEXCONTAINER & facesToDelete)
00179   {
00180     if (m.fn <= 0)
00181     {
00182       return;
00183     }
00184 
00185     EdgeMap edges;
00186     VertexClipInfoVec vInfos;
00187     TriangleInfoVec tInfos;
00188 
00189     CoordType vTriangle[4];
00190     CoordType vClipped[64];
00191 
00192     CoordType pvP0[64];
00193     CoordType pvP1[64];
00194 
00195     unsigned int numDeletedTris = 0;
00196     unsigned int numTriangles = 0;
00197     unsigned int numVertices = 0;
00198 
00199     unsigned int vIdx = (unsigned int)(m.vn);
00200     unsigned int tIdx = (unsigned int)(m.fn);
00201 
00202     ScalarType boxOffsets[6];
00203 
00204     boxOffsets[0] =  b.min[0];
00205     boxOffsets[1] = -b.max[0];
00206     boxOffsets[2] =  b.min[1];
00207     boxOffsets[3] = -b.max[1];
00208     boxOffsets[4] =  b.min[2];
00209     boxOffsets[5] = -b.max[2];
00210 
00211     UIntHMap emptyMap;
00212     EdgeIntersections emptyIsects;
00213 
00214     const ScalarType eps = (ScalarType)(1e-6);
00215 
00216     for (FaceIterator it=m.face.begin(); it!=m.face.end(); ++it)
00217     {
00218       if ((*it).IsD())
00219       {
00220         continue;
00221       }
00222 
00223       unsigned int cc[3];
00224 
00225       cc[0] = ClassType::BoxClipCode(boxOffsets, (*it).V(0)->P());
00226       cc[1] = ClassType::BoxClipCode(boxOffsets, (*it).V(1)->P());
00227       cc[2] = ClassType::BoxClipCode(boxOffsets, (*it).V(2)->P());
00228 
00229       if ((cc[0] | cc[1] | cc[2]) == 0)
00230       {
00231         continue;
00232       }
00233 
00234       const unsigned int refT = (unsigned int)(std::distance(m.face.begin(), it));
00235 
00236       if ((cc[0] & cc[1] & cc[2]) != 0)
00237       {
00238         facesToDelete.push_back(refT);
00239         (*it).SetD();
00240         numDeletedTris++;
00241         continue;
00242       }
00243 
00244       facesToDelete.push_back(refT);
00245 
00246       vTriangle[0] = (*it).V(0)->P();
00247       vTriangle[1] = (*it).V(1)->P();
00248       vTriangle[2] = (*it).V(2)->P();
00249       vTriangle[3] = (*it).V(0)->P();
00250 
00251       unsigned int n, n0, n1;
00252 
00253       ClipPolygonLine(0, b.min[0], vTriangle,  4, pvP1,     n1);
00254       ClipPolygonLine(1, b.max[0], pvP1,      n1, pvP0,     n0);
00255 
00256       ClipPolygonLine(2, b.min[1], pvP0,      n0, pvP1,     n1);
00257       ClipPolygonLine(3, b.max[1], pvP1,      n1, pvP0,     n0);
00258 
00259       ClipPolygonLine(4, b.min[2], pvP0,      n0, pvP1,     n1);
00260       ClipPolygonLine(5, b.max[2], pvP1,      n1, vClipped,  n);
00261 
00262       assert(n < 64);
00263 
00264       unsigned int firstV, lastV;
00265 
00266       if (n > 2)
00267       {
00268         if (vClipped[0] == vClipped[n - 1])
00269         {
00270           n--;
00271         }
00272 
00273         const CoordType vU = vTriangle[1] - vTriangle[0];
00274         const CoordType vV = vTriangle[2] - vTriangle[0];
00275 
00276         const ScalarType tArea = (vU ^ vV).SquaredNorm();
00277         if (tArea < eps)
00278         {
00279           continue;
00280         }
00281 
00282         unsigned int tvidx[3];
00283         tvidx[0] = (*it).V(0) - &(*(m.vert.begin()));
00284         tvidx[1] = (*it).V(1) - &(*(m.vert.begin()));
00285         tvidx[2] = (*it).V(2) - &(*(m.vert.begin()));
00286 
00287         numTriangles += n - 2;
00288 
00289 //                              size_t vBegin = vInfos.size();
00290 
00291         VertexClipInfo<ScalarType> vnfo;
00292         TriangleInfo tnfo;
00293 
00294         unsigned int vmin[3];
00295         unsigned int vmax[3];
00296 
00297         if (tvidx[0] < tvidx[1])
00298         {
00299           vmin[0] = tvidx[0];
00300           vmax[0] = tvidx[1];
00301         }
00302         else
00303         {
00304           vmin[0] = tvidx[1];
00305           vmax[0] = tvidx[0];
00306         }
00307 
00308         if (tvidx[0] < tvidx[2])
00309         {
00310           vmin[1] = tvidx[0];
00311           vmax[1] = tvidx[2];
00312         }
00313         else
00314         {
00315           vmin[1] = tvidx[2];
00316           vmax[1] = tvidx[0];
00317         }
00318 
00319         if (tvidx[1] < tvidx[2])
00320         {
00321           vmin[2] = tvidx[1];
00322           vmax[2] = tvidx[2];
00323         }
00324         else
00325         {
00326           vmin[2] = tvidx[2];
00327           vmax[2] = tvidx[1];
00328         }
00329 
00330         for (unsigned int i=0; i<n; ++i)
00331         {
00332           vnfo.tref = refT;
00333 
00334           const CoordType vP = vClipped[i] - vTriangle[0];
00335 
00336           ScalarType tAreaU = (vU ^ vP).SquaredNorm();
00337           ScalarType tAreaV = (vP ^ vV).SquaredNorm();
00338 
00339           vnfo.fU = (ScalarType)(sqrt(tAreaU / tArea));
00340           vnfo.fV = (ScalarType)(sqrt(tAreaV / tArea));
00341 
00342           if (vClipped[i] == vTriangle[0])
00343           {
00344             vnfo.idx = tvidx[0];
00345           }
00346           else if (vClipped[i] == vTriangle[1])
00347           {
00348             vnfo.idx = tvidx[1];
00349           }
00350           else if (vClipped[i] == vTriangle[2])
00351           {
00352             vnfo.idx = tvidx[2];
00353           }
00354           else if (vnfo.fV < eps)
00355           {
00356             std::pair<EdgeMap_i, bool> mi = edges.insert(std::make_pair(vmin[1], emptyMap));
00357             std::pair<UIntHMap_i, bool> hi = (*(mi.first)).second.insert(std::make_pair(vmax[1], emptyIsects));
00358             bool found = false;
00359             for (unsigned int s=0; s<(*(hi.first)).second.n; ++s)
00360             {
00361               if (vClipped[i] == (*(hi.first)).second.isects[s].p)
00362               {
00363                 found = true;
00364                 vnfo.idx = (*(hi.first)).second.isects[s].idx;
00365                 break;
00366               }
00367             }
00368             if (!found)
00369             {
00370               vnfo.idx = vIdx++;
00371               numVertices++;
00372               vInfos.push_back(vnfo);
00373 
00374               (*(hi.first)).second.isects[(*(hi.first)).second.n].p = vClipped[i];
00375               (*(hi.first)).second.isects[(*(hi.first)).second.n].idx = vnfo.idx;
00376               (*(hi.first)).second.n++;
00377             }
00378           }
00379           else if (vnfo.fU < eps)
00380           {
00381             std::pair<EdgeMap_i, bool> mi = edges.insert(std::make_pair(vmin[0], emptyMap));
00382             std::pair<UIntHMap_i, bool> hi = (*(mi.first)).second.insert(std::make_pair(vmax[0], emptyIsects));
00383             bool found = false;
00384             for (unsigned int s=0; s<(*(hi.first)).second.n; ++s)
00385             {
00386               if (vClipped[i] == (*(hi.first)).second.isects[s].p)
00387               {
00388                 found = true;
00389                 vnfo.idx = (*(hi.first)).second.isects[s].idx;
00390                 break;
00391               }
00392             }
00393             if (!found)
00394             {
00395               vnfo.idx = vIdx++;
00396               numVertices++;
00397               vInfos.push_back(vnfo);
00398 
00399               (*(hi.first)).second.isects[(*(hi.first)).second.n].p = vClipped[i];
00400               (*(hi.first)).second.isects[(*(hi.first)).second.n].idx = vnfo.idx;
00401               (*(hi.first)).second.n++;
00402             }
00403           }
00404           else if ((vnfo.fU + vnfo.fV) >= ((ScalarType)(1.0 - 1e-5)))
00405           {
00406             std::pair<EdgeMap_i, bool> mi = edges.insert(std::make_pair(vmin[2], emptyMap));
00407             std::pair<UIntHMap_i, bool> hi = (*(mi.first)).second.insert(std::make_pair(vmax[2], emptyIsects));
00408             bool found = false;
00409             for (unsigned int s=0; s<(*(hi.first)).second.n; ++s)
00410             {
00411               if (vClipped[i] == (*(hi.first)).second.isects[s].p)
00412               {
00413                 found = true;
00414                 vnfo.idx = (*(hi.first)).second.isects[s].idx;
00415                 break;
00416               }
00417             }
00418             if (!found)
00419             {
00420               vnfo.idx = vIdx++;
00421               numVertices++;
00422               vInfos.push_back(vnfo);
00423 
00424               (*(hi.first)).second.isects[(*(hi.first)).second.n].p = vClipped[i];
00425               (*(hi.first)).second.isects[(*(hi.first)).second.n].idx = vnfo.idx;
00426               (*(hi.first)).second.n++;
00427             }
00428           }
00429           else
00430           {
00431             vnfo.idx = vIdx++;
00432             numVertices++;
00433             vInfos.push_back(vnfo);
00434           }
00435 
00436           if (i == 0)
00437           {
00438             firstV = vnfo.idx;
00439           }
00440 
00441           if (i > 1)
00442           {
00443             tnfo.idx = tIdx++;
00444             tnfo.v[0] = firstV;
00445             tnfo.v[1] = lastV;
00446             tnfo.v[2] = vnfo.idx;
00447 
00448             tInfos.push_back(tnfo);
00449           }
00450 
00451           lastV = vnfo.idx;
00452         }
00453       }
00454     }
00455 
00456     if (numTriangles == 0)
00457     {
00458       return;
00459     }
00460 
00461     const unsigned int vSize = (unsigned int)(m.vn);
00462     const unsigned int tSize = (unsigned int)(m.fn);
00463 
00464     typedef Allocator<TriMeshType> TriMeshAllocatorType;
00465 
00466     TriMeshAllocatorType::AddVertices(m, numVertices);
00467     TriMeshAllocatorType::AddFaces(m, numTriangles);
00468 
00469     unsigned int j = vSize;
00470     for (size_t i=0; i<vInfos.size(); ++i)
00471     {
00472       if (vInfos[i].idx >= vSize)
00473       {
00474         const unsigned int tref = vInfos[i].tref;
00475         vInterp(*(m.face[tref].V(0)), *(m.face[tref].V(1)), *(m.face[tref].V(2)), vInfos[i].fV, vInfos[i].fU, m.vert[j]);
00476         j++;
00477       }
00478     }
00479 
00480     j = tSize;
00481     for (size_t i=0; i<tInfos.size(); ++i)
00482     {
00483       m.face[j].V(0) = &(m.vert[tInfos[i].v[0]]);
00484       m.face[j].V(1) = &(m.vert[tInfos[i].v[1]]);
00485       m.face[j].V(2) = &(m.vert[tInfos[i].v[2]]);
00486       j++;
00487     }
00488   }
00489 
00490 
00491   /*
00492     static inline void Box(const Box3<ScalarType> & b, VERTEXINTEPOLATOR & vInterp, const TriMeshType & m, TriMeshType & r);
00493 
00494     Clip mesh "m" against an axis aligned box and put resulting data in mesh "r" (out of place version);
00495 
00496     Notes:
00497       1) input mesh is not modified;
00498       2) faces marked as deleted are skipped;
00499       3) vInterp functor must implement a n operator with signature
00500              void operator () (const VERTEX & v0, const VERTEX & v1, const VERTEX & v2, const Scalar & a, const Scalar & b, VERTEX & r);
00501          its semantic is to intepolate vertex attribute across triangle; a typical implementation is;
00502            r.P() = v0.P() + a * (v1.P() - v0.P()) + b * (v2.P() - v0.P());  // interpolate position
00503            r.N() = v0.N() + a * (v1.N() - v0.N()) + b * (v2.N() - v0.N());  // interpolate normal
00504            ...    // interpolate other vertex attributes
00505   */
00506 
00507   template <typename VERTEXINTEPOLATOR>
00508   static inline void Box(const Box3<ScalarType> & b, VERTEXINTEPOLATOR & vInterp, const TriMeshType & m, TriMeshType & r)
00509   {
00510     r.Clear();
00511 
00512     if (m.fn <= 0)
00513     {
00514       return;
00515     }
00516 
00517     class VertexClipInfo
00518     {
00519     public:
00520       typedef VertexClipInfo ClassType;
00521 
00522       ScalarType fU;
00523       ScalarType fV;
00524       unsigned int idx;
00525       unsigned int tref;
00526     };
00527 
00528     typedef std::vector<VertexClipInfo> VertexClipInfoVec;
00529 
00530     class TriangleInfo
00531     {
00532     public:
00533       typedef TriangleInfo ClassType;
00534 
00535       unsigned int v[3];
00536       unsigned int idx;
00537     };
00538 
00539     typedef std::vector<TriangleInfo> TriangleInfoVec;
00540 
00541     class EdgeIsect
00542     {
00543     public:
00544       CoordType p;
00545       unsigned int idx;
00546     };
00547 
00548     class EdgeIntersections
00549     {
00550     public:
00551       unsigned int n;
00552       EdgeIsect isects[6];
00553 
00554       EdgeIntersections(void)
00555       {
00556         this->n = 0;
00557       }
00558     };
00559 
00560     typedef std::unordered_map<unsigned int, EdgeIntersections> UIntHMap;
00561     typedef typename UIntHMap::iterator UIntHMap_i;
00562     typedef typename UIntHMap::value_type UIntHMap_v;
00563 
00564     typedef std::unordered_map<unsigned int, UIntHMap> EdgeMap;
00565     typedef typename EdgeMap::iterator EdgeMap_i;
00566     typedef typename EdgeMap::value_type EdgeMap_v;
00567 
00568     typedef std::unordered_map<unsigned int, unsigned int> UIHMap;
00569     typedef typename UIHMap::iterator UIHMap_i;
00570 
00571     typedef typename TriMeshType::ConstFaceIterator ConstFaceIterator;
00572 
00573     UIHMap origVertsMap;
00574     EdgeMap edges;
00575     VertexClipInfoVec vInfos;
00576     TriangleInfoVec tInfos;
00577 
00578     CoordType vTriangle[4];
00579     CoordType vClipped[64];
00580 
00581     CoordType pvP0[64];
00582     CoordType pvP1[64];
00583 
00584     unsigned int numDeletedTris = 0;
00585     unsigned int numTriangles = 0;
00586     unsigned int numVertices = 0;
00587 
00588     unsigned int vIdx = 0;
00589     unsigned int tIdx = 0;
00590 
00591     ScalarType boxOffsets[6];
00592 
00593     boxOffsets[0] =  b.min[0];
00594     boxOffsets[1] = -b.max[0];
00595     boxOffsets[2] =  b.min[1];
00596     boxOffsets[3] = -b.max[1];
00597     boxOffsets[4] =  b.min[2];
00598     boxOffsets[5] = -b.max[2];
00599 
00600     UIntHMap emptyMap;
00601     EdgeIntersections emptyIsects;
00602 
00603     const ScalarType eps = (ScalarType)(1e-6);
00604 
00605     for (ConstFaceIterator it=m.face.begin(); it!=m.face.end(); ++it)
00606     {
00607       if ((*it).IsD())
00608       {
00609         continue;
00610       }
00611 
00612       unsigned int cc[3];
00613 
00614       cc[0] = ClassType::BoxClipCode(boxOffsets, (*it).V(0)->P());
00615       cc[1] = ClassType::BoxClipCode(boxOffsets, (*it).V(1)->P());
00616       cc[2] = ClassType::BoxClipCode(boxOffsets, (*it).V(2)->P());
00617 
00618       if ((cc[0] | cc[1] | cc[2]) == 0)
00619       {
00620         TriangleInfo tnfo;
00621         VertexClipInfo vnfo;
00622 
00623         tnfo.idx = tIdx++;
00624 
00625         for (int i=0; i<3; ++i)
00626         {
00627           const unsigned int v = (*it).V(i) - &(*(m.vert.begin()));
00628           std::pair<UIHMap_i, bool> hi = origVertsMap.insert(std::make_pair(v, vIdx));
00629 
00630           if (hi.second)
00631           {
00632             vnfo.idx = v;
00633             vInfos.push_back(vnfo);
00634             tnfo.v[i] = vIdx++;
00635           }
00636           else
00637           {
00638             tnfo.v[i] = (*(hi.first)).second;
00639           }
00640         }
00641 
00642         tInfos.push_back(tnfo);
00643 
00644         continue;
00645       }
00646 
00647       if ((cc[0] & cc[1] & cc[2]) != 0)
00648       {
00649         numDeletedTris++;
00650         continue;
00651       }
00652 
00653       vTriangle[0] = (*it).V(0)->P();
00654       vTriangle[1] = (*it).V(1)->P();
00655       vTriangle[2] = (*it).V(2)->P();
00656       vTriangle[3] = (*it).V(0)->P();
00657 
00658       unsigned int n, n0, n1;
00659 
00660       ClipPolygonLine(0, b.min[0], vTriangle,  4, pvP1,     n1);
00661       ClipPolygonLine(1, b.max[0], pvP1,      n1, pvP0,     n0);
00662 
00663       ClipPolygonLine(2, b.min[1], pvP0,      n0, pvP1,     n1);
00664       ClipPolygonLine(3, b.max[1], pvP1,      n1, pvP0,     n0);
00665 
00666       ClipPolygonLine(4, b.min[2], pvP0,      n0, pvP1,     n1);
00667       ClipPolygonLine(5, b.max[2], pvP1,      n1, vClipped,  n);
00668 
00669       assert(n < 64);
00670 
00671       unsigned int firstV, lastV;
00672 
00673 
00674       if (n > 2)
00675       {
00676         if (vClipped[0] == vClipped[n - 1])
00677         {
00678           n--;
00679         }
00680 
00681         const CoordType vU = vTriangle[1] - vTriangle[0];
00682         const CoordType vV = vTriangle[2] - vTriangle[0];
00683 
00684         const ScalarType tArea = (vU ^ vV).SquaredNorm();
00685         if (tArea < eps)
00686         {
00687           continue;
00688         }
00689 
00690         unsigned int tvidx[3];
00691         tvidx[0] = (*it).V(0) - &(*(m.vert.begin()));
00692         tvidx[1] = (*it).V(1) - &(*(m.vert.begin()));
00693         tvidx[2] = (*it).V(2) - &(*(m.vert.begin()));
00694 
00695         unsigned int refT = (unsigned int)(std::distance(m.face.begin(), it));
00696 
00697         numTriangles += n - 2;
00698 
00699         VertexClipInfo vnfo;
00700         TriangleInfo tnfo;
00701 
00702         unsigned int vmin[3];
00703         unsigned int vmax[3];
00704 
00705         if (tvidx[0] < tvidx[1])
00706         {
00707           vmin[0] = tvidx[0];
00708           vmax[0] = tvidx[1];
00709         }
00710         else
00711         {
00712           vmin[0] = tvidx[1];
00713           vmax[0] = tvidx[0];
00714         }
00715 
00716         if (tvidx[0] < tvidx[2])
00717         {
00718           vmin[1] = tvidx[0];
00719           vmax[1] = tvidx[2];
00720         }
00721         else
00722         {
00723           vmin[1] = tvidx[2];
00724           vmax[1] = tvidx[0];
00725         }
00726 
00727         if (tvidx[1] < tvidx[2])
00728         {
00729           vmin[2] = tvidx[1];
00730           vmax[2] = tvidx[2];
00731         }
00732         else
00733         {
00734           vmin[2] = tvidx[2];
00735           vmax[2] = tvidx[1];
00736         }
00737 
00738         for (unsigned int i=0; i<n; ++i)
00739         {
00740           vnfo.tref = refT;
00741 
00742           const CoordType vP = vClipped[i] - vTriangle[0];
00743 
00744           ScalarType tAreaU = (vU ^ vP).SquaredNorm();
00745           ScalarType tAreaV = (vP ^ vV).SquaredNorm();
00746 
00747           vnfo.fU = (ScalarType)(sqrt(tAreaU / tArea));
00748           vnfo.fV = (ScalarType)(sqrt(tAreaV / tArea));
00749 
00750           unsigned int currVIdx;
00751 
00752           if (vClipped[i] == vTriangle[0])
00753           {
00754             std::pair<UIHMap_i, bool> hi = origVertsMap.insert(std::make_pair(tvidx[0], vIdx));
00755             if (hi.second)
00756             {
00757               vnfo.idx = tvidx[0];
00758               vInfos.push_back(vnfo);
00759               currVIdx = vIdx++;
00760             }
00761             else
00762             {
00763               currVIdx = (*(hi.first)).second;
00764             }
00765           }
00766           else if (vClipped[i] == vTriangle[1])
00767           {
00768             std::pair<UIHMap_i, bool> hi = origVertsMap.insert(std::make_pair(tvidx[1], vIdx));
00769             if (hi.second)
00770             {
00771               vnfo.idx = tvidx[1];
00772               vInfos.push_back(vnfo);
00773               currVIdx = vIdx++;
00774             }
00775             else
00776             {
00777               currVIdx = (*(hi.first)).second;
00778             }
00779           }
00780           else if (vClipped[i] == vTriangle[2])
00781           {
00782             std::pair<UIHMap_i, bool> hi = origVertsMap.insert(std::make_pair(tvidx[2], vIdx));
00783             if (hi.second)
00784             {
00785               vnfo.idx = tvidx[2];
00786               vInfos.push_back(vnfo);
00787               currVIdx = vIdx++;
00788             }
00789             else
00790             {
00791               currVIdx = (*(hi.first)).second;
00792             }
00793           }
00794           else if (vnfo.fV < eps)
00795           {
00796             std::pair<EdgeMap_i, bool> mi = edges.insert(std::make_pair(vmin[1], emptyMap));
00797             std::pair<UIntHMap_i, bool> hi = (*(mi.first)).second.insert(std::make_pair(vmax[1], emptyIsects));
00798             bool found = false;
00799             for (unsigned int s=0; s<(*(hi.first)).second.n; ++s)
00800             {
00801               if (vClipped[i] == (*(hi.first)).second.isects[s].p)
00802               {
00803                 found = true;
00804                 vnfo.idx = (unsigned int)(-1);
00805                 currVIdx = (*(hi.first)).second.isects[s].idx;
00806                 break;
00807               }
00808             }
00809             if (!found)
00810             {
00811               (*(hi.first)).second.isects[(*(hi.first)).second.n].p = vClipped[i];
00812               (*(hi.first)).second.isects[(*(hi.first)).second.n].idx = vIdx;
00813               (*(hi.first)).second.n++;
00814 
00815               vnfo.idx = (unsigned int)(-1);
00816               numVertices++;
00817               vInfos.push_back(vnfo);
00818               currVIdx = vIdx++;
00819             }
00820           }
00821           else if (vnfo.fU < eps)
00822           {
00823             std::pair<EdgeMap_i, bool> mi = edges.insert(std::make_pair(vmin[0], emptyMap));
00824             std::pair<UIntHMap_i, bool> hi = (*(mi.first)).second.insert(std::make_pair(vmax[0], emptyIsects));
00825             bool found = false;
00826             for (unsigned int s=0; s<(*(hi.first)).second.n; ++s)
00827             {
00828               if (vClipped[i] == (*(hi.first)).second.isects[s].p)
00829               {
00830                 found = true;
00831                 vnfo.idx = (unsigned int)(-1);
00832                 currVIdx = (*(hi.first)).second.isects[s].idx;
00833                 break;
00834               }
00835             }
00836             if (!found)
00837             {
00838               (*(hi.first)).second.isects[(*(hi.first)).second.n].p = vClipped[i];
00839               (*(hi.first)).second.isects[(*(hi.first)).second.n].idx = vIdx;
00840               (*(hi.first)).second.n++;
00841 
00842               vnfo.idx = (unsigned int)(-1);
00843               numVertices++;
00844               vInfos.push_back(vnfo);
00845               currVIdx = vIdx++;
00846             }
00847           }
00848           else if ((vnfo.fU + vnfo.fV) >= ((ScalarType)(1.0 - 1e-5)))
00849           {
00850             std::pair<EdgeMap_i, bool> mi = edges.insert(std::make_pair(vmin[2], emptyMap));
00851             std::pair<UIntHMap_i, bool> hi = (*(mi.first)).second.insert(std::make_pair(vmax[2], emptyIsects));
00852             bool found = false;
00853             for (unsigned int s=0; s<(*(hi.first)).second.n; ++s)
00854             {
00855               if (vClipped[i] == (*(hi.first)).second.isects[s].p)
00856               {
00857                 found = true;
00858                 vnfo.idx = (unsigned int)(-1);
00859                 currVIdx = (*(hi.first)).second.isects[s].idx;
00860                 break;
00861               }
00862             }
00863             if (!found)
00864             {
00865               (*(hi.first)).second.isects[(*(hi.first)).second.n].p = vClipped[i];
00866               (*(hi.first)).second.isects[(*(hi.first)).second.n].idx = vIdx;
00867               (*(hi.first)).second.n++;
00868 
00869               vnfo.idx = (unsigned int)(-1);
00870               numVertices++;
00871               vInfos.push_back(vnfo);
00872               currVIdx = vIdx++;
00873             }
00874           }
00875           else
00876           {
00877             vnfo.idx = (unsigned int)(-1);
00878             numVertices++;
00879             vInfos.push_back(vnfo);
00880             currVIdx = vIdx++;
00881           }
00882 
00883           if (i == 0)
00884           {
00885             firstV = currVIdx;
00886           }
00887 
00888           if (i > 1)
00889           {
00890             tnfo.idx = tIdx++;
00891             tnfo.v[0] = firstV;
00892             tnfo.v[1] = lastV;
00893             tnfo.v[2] = currVIdx;
00894 
00895             tInfos.push_back(tnfo);
00896           }
00897 
00898           lastV = currVIdx;
00899         }
00900       }
00901     }
00902 
00903     if (tInfos.empty())
00904     {
00905       return;
00906     }
00907 
00908     typedef Allocator<TriMeshType> TriMeshAllocatorType;
00909 
00910     TriMeshAllocatorType::AddVertices(r, (int)(vInfos.size()));
00911     TriMeshAllocatorType::AddFaces(r, (int)(tInfos.size()));
00912 
00913     for (size_t i=0; i<vInfos.size(); ++i)
00914     {
00915       if (vInfos[i].idx != ((unsigned int)(-1)))
00916       {
00917         r.vert[i] = m.vert[vInfos[i].idx];
00918       }
00919       else
00920       {
00921         const unsigned int tref = vInfos[i].tref;
00922         vInterp(*(m.face[tref].V(0)), *(m.face[tref].V(1)), *(m.face[tref].V(2)), vInfos[i].fV, vInfos[i].fU, r.vert[i]);
00923       }
00924     }
00925 
00926     for (size_t i=0; i<tInfos.size(); ++i)
00927     {
00928       r.face[i].V(0) = &(r.vert[tInfos[i].v[0]]);
00929       r.face[i].V(1) = &(r.vert[tInfos[i].v[1]]);
00930       r.face[i].V(2) = &(r.vert[tInfos[i].v[2]]);
00931     }
00932   }
00933 
00934 protected:
00935 
00936   static inline unsigned int BoxClipCode(const ScalarType * offsets, const CoordType & p)
00937   {
00938     //const ScalarType eps = (ScalarType)(-1e-5);
00939     const ScalarType eps = (ScalarType)(0);
00940     unsigned int code = 0;
00941 
00942     code |= ((( p[0] - offsets[0]) < eps) ? (1 << 0) : (0));
00943     code |= (((-p[0] - offsets[1]) < eps) ? (1 << 1) : (0));
00944     code |= ((( p[1] - offsets[2]) < eps) ? (1 << 2) : (0));
00945     code |= (((-p[1] - offsets[3]) < eps) ? (1 << 3) : (0));
00946     code |= ((( p[2] - offsets[4]) < eps) ? (1 << 4) : (0));
00947     code |= (((-p[2] - offsets[5]) < eps) ? (1 << 5) : (0));
00948 
00949     return (code);
00950   }
00951 
00952   static inline unsigned int InRegion(int mode, const ScalarType & value, const CoordType & p_in)
00953   {
00954     //const ScalarType eps = (ScalarType)(-1e-5);
00955     const ScalarType eps = (ScalarType)(0);
00956     unsigned int flag = 0;
00957 
00958     switch(mode)
00959     {
00960       case 0:
00961         flag = p_in[0] + eps < value;
00962         break;
00963       case 1:
00964         flag = p_in[0] > value + eps;
00965         break;
00966       case 2:
00967         flag = p_in[1] + eps < value;
00968         break;
00969       case 3:
00970         flag = p_in[1] > value + eps;
00971         break;
00972       case 4:
00973         flag = p_in[2] + eps < value;
00974         break;
00975       case 5:
00976         flag = p_in[2] > value + eps;
00977         break;
00978       default:
00979         break;
00980     }
00981 
00982     return (flag);
00983   }
00984 
00985   static inline void CrossPoint(int mode, const ScalarType & value, const CoordType & SP, const CoordType & PP, CoordType & p_out)
00986   {
00987     switch(mode)
00988     {
00989       case 0:
00990       case 1:
00991         p_out[0] = value;
00992         if ((PP[0] - SP[0]) == ((ScalarType)(0)))
00993         {
00994           p_out[1] = PP[1];
00995           p_out[2] = PP[2];
00996         }
00997         else
00998         {
00999           p_out[1] = SP[1] + (value - SP[0]) * (PP[1] - SP[1]) / (PP[0] - SP[0]);
01000           p_out[2] = SP[2] + (value - SP[0]) * (PP[2] - SP[2]) / (PP[0] - SP[0]);
01001         }
01002         break;
01003       case 2:
01004       case 3:
01005         p_out[1] = value;
01006         if ((PP[1] - SP[1]) == ((ScalarType)(0)))
01007         {
01008           p_out[0] = PP[0];
01009           p_out[2] = PP[2];
01010         }
01011         else
01012         {
01013           p_out[0] = SP[0] + (value - SP[1]) * (PP[0] - SP[0]) / (PP[1] - SP[1]);
01014           p_out[2] = SP[2] + (value - SP[1]) * (PP[2] - SP[2]) / (PP[1] - SP[1]);
01015         }
01016         break;
01017       case 4:
01018       case 5:
01019         p_out[2] = value;
01020         if ((PP[2] - SP[2]) == ((ScalarType)(0)))
01021         {
01022           p_out[0] = PP[0];
01023           p_out[1] = PP[1];
01024         }
01025         else
01026         {
01027           p_out[0] = SP[0] + (value - SP[2]) * (PP[0] - SP[0]) / (PP[2] - SP[2]);
01028           p_out[1] = SP[1] + (value - SP[2]) * (PP[1] - SP[1]) / (PP[2] - SP[2]);
01029         }
01030         break;
01031       default:
01032         break;
01033     }
01034   }
01035 
01036   static inline void ClipPolygonLine(int mode, const ScalarType & value, CoordType * P_in, unsigned int n_in, CoordType * P_out, unsigned int & n_out)
01037   {
01038     unsigned int ps;
01039     CoordType * SP;
01040     CoordType * PP;
01041 
01042     n_out = 0;
01043     SP = &P_in[n_in-1];
01044 
01045     if (ClassType::InRegion(mode, value, *SP))
01046     {
01047       ps = 0;
01048     }
01049     else
01050     {
01051       ps = 2;
01052     }
01053 
01054     for(unsigned int i=0; i<n_in; ++i)
01055     {
01056       PP = &(P_in[i]);
01057       ps = (ps >> 1) | ((ClassType::InRegion(mode, value, *PP)) ? (0) : (2));
01058 
01059       switch(ps)
01060       {
01061         case 0:
01062           break;
01063         case 1:
01064           ClassType::CrossPoint(mode, value, *SP, *PP, P_out[n_out]);
01065           n_out++;
01066           break;
01067         case 2:
01068           ClassType::CrossPoint(mode, value, *SP, *PP, P_out[n_out]);
01069           n_out++;
01070           P_out[n_out] = *PP;
01071           n_out++;
01072           break;
01073         case 3:
01074           P_out[n_out] = *PP;
01075           n_out++;
01076           break;
01077         default:
01078           break;
01079       }
01080 
01081       SP = PP;
01082     }
01083   }
01084 
01085 };
01086 
01087 } // end namespace tri
01088 } // end namespace vcg
01089 
01090 #endif // __VCGLIB_TRI_CLIP


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