convex_hull.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-2015                                           \/)\/    *
00006 * Visual Computing Lab                                            /\/|      *
00007 * ISTI - Italian National Research Council                           |      *
00008 *                                                                    \      *
00009 * All rights reserved.                                                      *
00010 *                                                                           *
00011 * This program is free software; you can redistribute it and/or modify      *
00012 * it under the terms of the GNU General Public License as published by      *
00013 * the Free Software Foundation; either version 2 of the License, or         *
00014 * (at your option) any later version.                                       *
00015 *                                                                           *
00016 * This program is distributed in the hope that it will be useful,           *
00017 * but WITHOUT ANY WARRANTY; without even the implied warranty of            *
00018 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the             *
00019 * GNU General Public License (http://www.gnu.org/licenses/gpl.txt)          *
00020 * for more details.                                                         *
00021 *                                                                           *
00022 ****************************************************************************/
00023 #ifndef VCG_TRI_CONVEX_HULL_H
00024 #define VCG_TRI_CONVEX_HULL_H
00025 
00026 #include <queue>
00027 #include <unordered_map>
00028 #include <algorithm>
00029 #include <vcg/complex/allocate.h>
00030 #include <vcg/complex/algorithms/clean.h>
00031 
00032 namespace vcg
00033 {
00034 
00035 namespace tri
00036 {
00037 
00038 template <class InputMesh, class CHMesh>
00039 class ConvexHull
00040 {
00041 
00042 public:
00043 
00044   typedef typename InputMesh::ScalarType                ScalarType;
00045   typedef typename InputMesh::CoordType         CoordType;
00046   typedef typename InputMesh::VertexPointer     InputVertexPointer;
00047   typedef typename InputMesh::VertexIterator    InputVertexIterator;
00048   typedef typename CHMesh::VertexIterator               CHVertexIterator;
00049   typedef typename CHMesh::VertexPointer                CHVertexPointer;
00050   typedef typename CHMesh::FaceIterator         CHFaceIterator;
00051   typedef typename CHMesh::FacePointer          CHFacePointer;
00052 
00053 private:
00054 
00055   typedef std::pair<InputVertexPointer, ScalarType> Pair;
00056 
00057 
00058   // Initialize the convex hull with the biggest tetraedron created using the vertices of the input mesh
00059   static void InitConvexHull(InputMesh& mesh, CHMesh& convexHull)
00060   {
00061   typename CHMesh:: template PerVertexAttributeHandle<size_t> indexInputVertex = Allocator<CHMesh>::template GetPerVertexAttribute<size_t>(convexHull, std::string("indexInput"));
00062   InputVertexPointer v[3];
00063     //Find the 6 points with min/max coordinate values
00064     InputVertexIterator vi = mesh.vert.begin();
00065     std::vector<InputVertexPointer> minMax(6, &(*vi));
00066     for (; vi != mesh.vert.end(); vi++)
00067     {
00068       if ((*vi).P().X() < (*minMax[0]).P().X())
00069         minMax[0] = &(*vi);
00070       if ((*vi).P().Y() < (*minMax[1]).P().Y())
00071         minMax[1] = &(*vi);
00072       if ((*vi).P().Z() < (*minMax[2]).P().Z())
00073         minMax[2] = &(*vi);
00074       if ((*vi).P().X() > (*minMax[3]).P().X())
00075         minMax[3] = &(*vi);
00076       if ((*vi).P().Y() > (*minMax[4]).P().Y())
00077         minMax[4] = &(*vi);
00078       if ((*vi).P().Z() > (*minMax[5]).P().Z())
00079         minMax[5] = &(*vi);
00080     }
00081     //Find the farthest two points
00082     ScalarType maxDist = 0;
00083     for (int i = 0; i < 6; i++)
00084     {
00085       for (int j = i + 1; j < 6; j++)
00086       {
00087         float dist = (minMax[i]->P() - minMax[j]->P()).SquaredNorm();
00088         if (dist > maxDist)
00089         {
00090           maxDist = dist;
00091           v[0] = minMax[i];
00092           v[1] = minMax[j];
00093         }
00094       }
00095     }
00096     //Find the third point to create the base of the tetrahedron
00097     vcg::Line3<ScalarType> line(v[0]->P(), (v[0]->P() - v[1]->P()));
00098     maxDist = 0;
00099     for (vi = mesh.vert.begin(); vi != mesh.vert.end(); vi++)
00100     {
00101       ScalarType dist = vcg::Distance(line, (*vi).P());
00102       if (dist > maxDist)
00103       {
00104         maxDist = dist;
00105         v[2] = &(*vi);
00106       }
00107     }
00108     //Create face in the convex hull
00109     CHVertexIterator chVi = vcg::tri::Allocator<CHMesh>::AddVertices(convexHull, 3);
00110     for (int i = 0; i < 3; i++)
00111     {
00112       (*chVi).P().Import(v[i]->P());
00113     v[i]->SetV();
00114       indexInputVertex[chVi] = vcg::tri::Index(mesh, v[i]);
00115       chVi++;
00116     }
00117     CHFaceIterator fi = vcg::tri::Allocator<CHMesh>::AddFace(convexHull, 0, 1, 2);
00118     (*fi).N() = vcg::NormalizedTriangleNormal(*fi);
00119 
00120     //Find the fourth point to create the tetrahedron
00121     InputVertexPointer v4;
00122     float distance = 0;
00123     float absDist = -1;
00124     for (vi = mesh.vert.begin(); vi != mesh.vert.end(); vi++)
00125     {
00126       float tempDist = ((*vi).P() - (*fi).P(0)).dot((*fi).N());
00127       if (fabs(tempDist) > absDist)
00128       {
00129         distance = tempDist;
00130         v4 = &(*vi);
00131         absDist = fabs(distance);
00132       }
00133     }
00134 
00135     //Flip the previous face if the fourth point is above the face
00136     if (distance > 0)
00137     {
00138       (*fi).N() = -(*fi).N();
00139       CHVertexPointer tempV = (*fi).V(1);
00140       (*fi).V(1) = (*fi).V(2);
00141       (*fi).V(2) = tempV;
00142     }
00143 
00144     //Create the other 3 faces of the tetrahedron
00145     chVi = vcg::tri::Allocator<CHMesh>::AddVertices(convexHull, 1);
00146     (*chVi).P().Import(v4->P());
00147     indexInputVertex[chVi] = vcg::tri::Index(mesh, v4);
00148     v4->SetV();
00149     fi = vcg::tri::Allocator<CHMesh>::AddFace(convexHull, &convexHull.vert[3], convexHull.face[0].V0(1), convexHull.face[0].V0(0));
00150     (*fi).N() = vcg::NormalizedTriangleNormal(*fi);
00151     fi = vcg::tri::Allocator<CHMesh>::AddFace(convexHull, &convexHull.vert[3], convexHull.face[0].V1(1), convexHull.face[0].V1(0));
00152     (*fi).N() = vcg::NormalizedTriangleNormal(*fi);
00153     fi = vcg::tri::Allocator<CHMesh>::AddFace(convexHull, &convexHull.vert[3], convexHull.face[0].V2(1), convexHull.face[0].V2(0));
00154     (*fi).N() = vcg::NormalizedTriangleNormal(*fi);
00155     vcg::tri::UpdateTopology<CHMesh>::FaceFace(convexHull);
00156   }
00157 
00158 
00159 public:
00160 
00161 
00170   static bool ComputeConvexHull(InputMesh& mesh, CHMesh& convexHull)
00171   {
00172     vcg::tri::RequireFFAdjacency(convexHull);
00173     vcg::tri::RequirePerFaceNormal(convexHull);
00174     vcg::tri::Allocator<InputMesh>::CompactVertexVector(mesh);
00175     typename CHMesh:: template PerVertexAttributeHandle<size_t> indexInputVertex = Allocator<CHMesh>::template GetPerVertexAttribute<size_t>(convexHull, std::string("indexInput"));
00176     if (mesh.vert.size() < 4)
00177       return false;
00178     vcg::tri::UpdateFlags<InputMesh>::VertexClearV(mesh);
00179     InitConvexHull(mesh, convexHull);
00180 
00181     //Build list of visible vertices for each convex hull face and find the furthest vertex for each face
00182     std::vector<std::vector<InputVertexPointer>> listVertexPerFace(convexHull.face.size());
00183     std::vector<Pair> furthestVexterPerFace(convexHull.face.size(), std::make_pair((InputVertexPointer)NULL, 0.0f));
00184     for (size_t i = 0; i < mesh.vert.size(); i++)
00185     {
00186     if (!mesh.vert[i].IsV())
00187     {
00188       for (size_t j = 0; j < convexHull.face.size(); j++)
00189       {
00190         ScalarType dist = (mesh.vert[i].P() - convexHull.face[j].P(0)).dot(convexHull.face[j].N());
00191         if (dist > 0)
00192         {
00193           listVertexPerFace[j].push_back(&mesh.vert[i]);
00194           if (dist > furthestVexterPerFace[j].second)
00195           {
00196             furthestVexterPerFace[j].second = dist;
00197             furthestVexterPerFace[j].first = &mesh.vert[i];
00198           }
00199         }
00200       }
00201     }
00202     }
00203 
00204     for (size_t i = 0; i < listVertexPerFace.size(); i++)
00205     {
00206       if (listVertexPerFace[i].size() > 0)
00207       {
00208         //Find faces to remove and face on the border where to connect the new fan faces
00209         InputVertexPointer vertex = furthestVexterPerFace[i].first;
00210         std::queue<int> queue;
00211         std::vector<int> visFace;
00212         std::vector<int> borderFace;
00213         visFace.push_back(i);
00214         queue.push(i);
00215         while (queue.size() > 0)
00216         {
00217           CHFacePointer fp = &convexHull.face[queue.front()];
00218           queue.pop();
00219           fp->SetV();
00220           for (int ii = 0; ii < 3; ii++)
00221           {
00222             CHFacePointer nextF = fp->FFp(ii);
00223             if (!nextF->IsV())
00224             {
00225               int indexF = vcg::tri::Index(convexHull, nextF);
00226               ScalarType dist = (vertex->P() - nextF->P(0)).dot(nextF->N());
00227               if (dist < 0)
00228               {
00229                 borderFace.push_back(indexF);
00230                 fp->SetB(ii);
00231                 nextF->SetB(fp->FFi(ii));
00232               }
00233               else
00234               {
00235                 visFace.push_back(indexF);
00236                 queue.push(indexF);
00237               }
00238             }
00239           }
00240         }
00241         if (borderFace.size() > 0)
00242         {
00243           CHVertexIterator vi = vcg::tri::Allocator<CHMesh>::AddVertices(convexHull, 1);
00244           (*vi).P().Import((*vertex).P());
00245       vertex->SetV();
00246           indexInputVertex[vi] = vcg::tri::Index(mesh, vertex);
00247         }
00248 
00249         //Add a new face for each border
00250         std::unordered_map< CHVertexPointer, std::pair<int, char> > fanMap;
00251         for (size_t jj = 0; jj < borderFace.size(); jj++)
00252         {
00253           int indexFace = borderFace[jj];
00254           CHFacePointer f = &convexHull.face[indexFace];
00255           for (int j = 0; j < 3; j++)
00256           {
00257             if (f->IsB(j))
00258             {
00259               f->ClearB(j);
00260               //Add new face
00261               CHFaceIterator fi = vcg::tri::Allocator<CHMesh>::AddFace(convexHull, &convexHull.vert.back(), f->V1(j), f->V0(j));
00262               (*fi).N() = vcg::NormalizedTriangleNormal(*fi);
00263               f = &convexHull.face[indexFace];
00264               int newFace = vcg::tri::Index(convexHull, *fi);
00265               //Update convex hull FF topology
00266               CHVertexPointer vp[] = { f->V1(j), f->V0(j) };
00267               for (int ii = 0; ii < 2; ii++)
00268               {
00269                 int indexE = ii * 2;
00270                 typename std::unordered_map< CHVertexPointer, std::pair<int, char> >::iterator vIter = fanMap.find(vp[ii]);
00271                 if (vIter != fanMap.end())
00272                 {
00273                   CHFacePointer f2 = &convexHull.face[(*vIter).second.first];
00274                   char edgeIndex = (*vIter).second.second;
00275                   f2->FFp(edgeIndex) = &convexHull.face.back();
00276                   f2->FFi(edgeIndex) = indexE;
00277                   fi->FFp(indexE) = f2;
00278                   fi->FFi(indexE) = edgeIndex;
00279                 }
00280                 else
00281                 {
00282                   fanMap[vp[ii]] = std::make_pair(newFace, indexE);
00283                 }
00284               }
00285               //Build the visibility list for the new face
00286               std::vector<InputVertexPointer> tempVect;
00287               int indices[2] = { indexFace, int(vcg::tri::Index(convexHull, f->FFp(j)) )};
00288               std::vector<InputVertexPointer> vertexToTest(listVertexPerFace[indices[0]].size() + listVertexPerFace[indices[1]].size());
00289               typename std::vector<InputVertexPointer>::iterator tempIt = std::set_union(listVertexPerFace[indices[0]].begin(), listVertexPerFace[indices[0]].end(), listVertexPerFace[indices[1]].begin(), listVertexPerFace[indices[1]].end(), vertexToTest.begin());
00290               vertexToTest.resize(tempIt - vertexToTest.begin());
00291 
00292               Pair newInfo = std::make_pair((InputVertexPointer)NULL , 0.0f);
00293               for (size_t ii = 0; ii < vertexToTest.size(); ii++)
00294               {
00295                 if (!(*vertexToTest[ii]).IsV())
00296                 {
00297                   float dist = ((*vertexToTest[ii]).P() - (*fi).P(0)).dot((*fi).N());
00298                   if (dist > 0)
00299                   {
00300                     tempVect.push_back(vertexToTest[ii]);
00301                     if (dist > newInfo.second)
00302                     {
00303                       newInfo.second = dist;
00304                       newInfo.first = vertexToTest[ii];
00305                     }
00306                   }
00307                 }
00308               }
00309               listVertexPerFace.push_back(tempVect);
00310               furthestVexterPerFace.push_back(newInfo);
00311               //Update topology of the new face
00312               CHFacePointer ffp = f->FFp(j);
00313               int ffi = f->FFi(j);
00314               ffp->FFp(ffi) = ffp;
00315               ffp->FFi(ffi) = ffi;
00316               f->FFp(j) = &convexHull.face.back();
00317               f->FFi(j) = 1;
00318               fi->FFp(1) = f;
00319               fi->FFi(1) = j;
00320             }
00321           }
00322         }
00323         //Delete the faces inside the updated convex hull
00324         for (size_t j = 0; j < visFace.size(); j++)
00325         {
00326           if (!convexHull.face[visFace[j]].IsD())
00327           {
00328             std::vector<InputVertexPointer> emptyVec;
00329             vcg::tri::Allocator<CHMesh>::DeleteFace(convexHull, convexHull.face[visFace[j]]);
00330             listVertexPerFace[visFace[j]].swap(emptyVec);
00331           }
00332         }
00333       }
00334     }
00335 
00336   tri::UpdateTopology<CHMesh>::ClearFaceFace(convexHull);
00337     vcg::tri::Allocator<CHMesh>::CompactFaceVector(convexHull);
00338     vcg::tri::Clean<CHMesh>::RemoveUnreferencedVertex(convexHull);
00339     return true;
00340   }
00361  static void ComputePointVisibility(InputMesh& m, CHMesh& visible, CoordType viewpoint, ScalarType logR=2)
00362  {
00363    visible.Clear();
00364    tri::RequireCompactness(m);
00365    InputMesh flipM;
00366 
00367    printf("Input mesh m %i %i\n",m.vn,m.fn);
00368 
00369    tri::Allocator<InputMesh>::AddVertices(flipM,m.vn);
00370    ScalarType maxDist=0;
00371    InputVertexIterator ci=flipM.vert.begin();
00372    for(InputVertexIterator vi=m.vert.begin();vi!=m.vert.end();++vi)
00373    {
00374      ci->P()=vi->P()-viewpoint;
00375      maxDist = std::max(maxDist,Norm(ci->P()));
00376      ++ci;
00377    }
00378    ScalarType R = maxDist*pow(10,logR);
00379    printf("Using R = %f logR = %f maxdist=%f \n",R,logR,maxDist);
00380    for(InputVertexIterator vi=flipM.vert.begin();vi!=flipM.vert.end();++vi)
00381    {
00382      ScalarType d = Norm(vi->P());
00383      vi->P() = vi->P() + vi->P()*ScalarType(2.0*(R - d)/d);
00384    }
00385 
00386    tri::Allocator<InputMesh>::AddVertex(flipM,CoordType(0,0,0));
00387    assert(m.vn+1 == flipM.vn);
00388 
00389    ComputeConvexHull(flipM,visible);
00390    assert(flipM.vert[m.vn].P()==Point3f(0,0,0));
00391    int vpInd=-1; // Index of the viewpoint in the ConvexHull mesh
00392    int selCnt=0;
00393    typename CHMesh:: template PerVertexAttributeHandle<size_t> indexInputVertex = Allocator<InputMesh>::template GetPerVertexAttribute<size_t>(visible, std::string("indexInput"));
00394    for(int i=0;i<visible.vn;++i)
00395    {
00396      size_t ind = indexInputVertex[i];
00397      if(ind==m.vn) vpInd = i;
00398      else
00399      {
00400        visible.vert[i].P() = m.vert[ind].P();
00401        m.vert[ind].SetS();
00402        m.vert[ind].C() = Color4b::LightBlue;
00403        selCnt++;
00404      }
00405    }
00406    printf("Selected %i visible points\n",selCnt);
00407 
00408    assert(vpInd != -1);
00409    // Final pass delete all the faces of the convex hull incident in the viewpoint
00410    for(int i=0;i<visible.fn;++i)
00411    {
00412      if( (Index(visible,visible.face[i].V(0)) == vpInd) ||
00413          (Index(visible,visible.face[i].V(1)) == vpInd) ||
00414          (Index(visible,visible.face[i].V(2)) == vpInd) )
00415        tri::Allocator<CHMesh>::DeleteFace(visible,visible.face[i]);
00416    }
00417 
00418    tri::Allocator<CHMesh>::CompactEveryVector(visible);
00419    tri::Clean<CHMesh>::FlipMesh(visible);
00420 
00421  }
00422 };
00423 
00424 } // end namespace tri
00425 
00426 } // end namespace vcg
00427 
00428 #endif //VCG_TRI_CONVEX_HULL_H


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