trimesh_edge.cpp
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-2012                                           \/)\/    *
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 // This sample require gl.
00025 #ifndef GLU_VERSIONS
00026 #ifdef __APPLE__
00027 #include <OpenGL/gl.h>
00028 #else
00029 #ifdef _WIN32
00030   #include <windows.h>
00031 #endif
00032 #include <GL/gl.h>
00033 #endif
00034 #endif
00035 
00036 #include<vcg/complex/complex.h>
00037 #include<vcg/complex/append.h>
00038 
00039 // input output
00040 #include<wrap/io_trimesh/import.h>
00041 #include<wrap/io_trimesh/export.h>
00042 
00043 // topology computation
00044 #include<vcg/complex/algorithms/update/topology.h>
00045 #include<vcg/complex/algorithms/update/bounding.h>
00046 #include<vcg/complex/algorithms/update/normal.h>
00047 #include <vcg/complex/algorithms/update/position.h>
00048 #include <vcg/complex/algorithms/update/quality.h>
00049 #include <vcg/complex/algorithms/stat.h>
00050 
00051 #include <vcg/complex/algorithms/intersection.h>
00052 #include <vcg/complex/algorithms/refine.h>
00053 #include <wrap/gl/glu_tessellator_cap.h>
00054 
00055 using namespace vcg;
00056 using namespace std;
00057 
00058 class MyEdge;
00059 class MyFace;
00060 class MyVertex;
00061 struct MyUsedTypes : public UsedTypes<  Use<MyVertex>   ::AsVertexType,
00062                                         Use<MyEdge>     ::AsEdgeType,
00063                                         Use<MyFace>     ::AsFaceType>{};
00064 
00065 class MyVertex  : public Vertex<MyUsedTypes, vertex::Coord3f, vertex::Normal3f, vertex::Qualityf,vertex::BitFlags  >{};
00066 class MyFace    : public Face< MyUsedTypes, face::FFAdj,  face::VertexRef, face::BitFlags >{};
00067 class MyEdge    : public Edge<MyUsedTypes, edge::VertexRef,edge::BitFlags,edge::EEAdj>{};
00068 class MyMesh    : public tri::TriMesh< vector<MyVertex>, vector<MyFace> , vector<MyEdge>  > {};
00069 
00070 
00071 
00072 void CapHole(MyMesh &m, MyMesh &capMesh, bool reverseFlag)
00073 {
00074   capMesh.Clear();
00075   std::vector< std::vector<Point3f> > outlines;
00076   std::vector<Point3f> outline;
00077 
00078   tri::Allocator<MyMesh>::CompactVertexVector(m);
00079   tri::Allocator<MyMesh>::CompactFaceVector(m);
00080   tri::UpdateFlags<MyMesh>::FaceClearV(m);
00081   tri::UpdateFlags<MyMesh>::VertexClearV(m);
00082   tri::UpdateTopology<MyMesh>::FaceFace(m);
00083   int nv=0;
00084 
00085   for(size_t i=0;i<m.face.size();i++)
00086   {
00087     for (int j=0;j<3;j++)
00088     if (!m.face[i].IsV() && face::IsBorder(m.face[i],j))
00089     {
00090       MyFace* startB=&(m.face[i]);
00091       vcg::face::Pos<MyFace> p(startB,j);
00092       assert(p.IsBorder());
00093       do
00094       {
00095         assert(p.IsManifold());
00096         p.F()->SetV();
00097         outline.push_back(p.V()->P());
00098         p.NextB();
00099         nv++;
00100       }
00101       while(!p.F()->IsV());
00102       if (reverseFlag)
00103         std::reverse(outline.begin(),outline.end());
00104 
00105       outlines.push_back(outline);
00106       outline.clear();
00107     }
00108   }
00109   if (nv<2) return;
00110   MyMesh::VertexIterator vi=vcg::tri::Allocator<MyMesh>::AddVertices(capMesh,nv);
00111   for (size_t i=0;i<outlines.size();i++)
00112   {
00113     for(size_t j=0;j<outlines[i].size();++j,++vi)
00114       (&*vi)->P()=outlines[i][j];
00115   }
00116 
00117   std::vector<int> indices;
00118   glu_tesselator::tesselate(outlines, indices);
00119 
00120   std::vector<Point3f> points;
00121   glu_tesselator::unroll(outlines, points);
00122   MyMesh::FaceIterator fi=tri::Allocator<MyMesh>::AddFaces(capMesh,nv-2);
00123   for (size_t i=0; i<indices.size(); i+=3,++fi)
00124   {
00125     (*&fi)->V(0)=&capMesh.vert[ indices[i+0] ];
00126     (*&fi)->V(1)=&capMesh.vert[ indices[i+1] ];
00127     (*&fi)->V(2)=&capMesh.vert[ indices[i+2] ];
00128   }
00129   tri::Clean<MyMesh>::RemoveDuplicateVertex(capMesh);
00130   tri::UpdateBounding<MyMesh>::Box(capMesh);
00131 }
00132 
00133 
00134 
00135 
00136 bool SplitMesh(MyMesh &m,             
00137                MyMesh &A, MyMesh &B,  
00138                Plane3f plane)
00139 {
00140   tri::Append<MyMesh,MyMesh>::Mesh(A,m);
00141   tri::UpdateQuality<MyMesh>::VertexFromPlane(A, plane);
00142   tri::QualityMidPointFunctor<MyMesh> slicingfunc(0.0f);
00143   tri::QualityEdgePredicate<MyMesh> slicingpred(0.0f);
00144   tri::UpdateTopology<MyMesh>::FaceFace(A);
00145   // The Actual Slicing
00146   tri::RefineE<MyMesh, tri::QualityMidPointFunctor<MyMesh>, tri::QualityEdgePredicate<MyMesh> > (A, slicingfunc, slicingpred, false);
00147 
00148   tri::Append<MyMesh,MyMesh>::Mesh(B,A);
00149 
00150   tri::UpdateSelection<MyMesh>::VertexFromQualityRange(A,-std::numeric_limits<float>::max(),0);
00151   tri::UpdateSelection<MyMesh>::FaceFromVertexStrict(A);
00152   for(MyMesh::FaceIterator fi=A.face.begin();fi!=A.face.end();++fi)
00153       if(!(*fi).IsD() && (*fi).IsS() ) tri::Allocator<MyMesh>::DeleteFace(A,*fi);
00154   tri::Clean<MyMesh>::RemoveUnreferencedVertex(A);
00155 
00156   tri::UpdateSelection<MyMesh>::VertexFromQualityRange(B,0,std::numeric_limits<float>::max());
00157   tri::UpdateSelection<MyMesh>::FaceFromVertexStrict(B);
00158   for(MyMesh::FaceIterator fi=B.face.begin();fi!=B.face.end();++fi)
00159       if(!(*fi).IsD() && (*fi).IsS() ) tri::Allocator<MyMesh>::DeleteFace(B,*fi);
00160   tri::Clean<MyMesh>::RemoveUnreferencedVertex(B);
00161 
00162   tri::UpdateTopology<MyMesh>::FaceFace(m);
00163 
00164   MyMesh Cap;
00165   CapHole(A,Cap,0);
00166   tri::Append<MyMesh,MyMesh>::Mesh(A,Cap);
00167 
00168   CapHole(B,Cap,0);
00169   tri::Append<MyMesh,MyMesh>::Mesh(B,Cap);
00170 
00171   tri::Clean<MyMesh>::RemoveDuplicateVertex(A);
00172   tri::Clean<MyMesh>::RemoveDuplicateVertex(B);
00173   return true;
00174 }
00175 
00176 void GetRandPlane(Box3f &bb, Plane3f &plane)
00177 {
00178   Point3f planeCenter = bb.Center();
00179   Point3f planeDir = Point3f(-0.5f+float(rand())/RAND_MAX,-0.5f+float(rand())/RAND_MAX,-0.5f+float(rand())/RAND_MAX);
00180   planeDir.Normalize();
00181 
00182   plane.Init(planeCenter+planeDir*0.3f*bb.Diag()*float(rand())/RAND_MAX,planeDir);
00183 }
00184 
00185 int main( int argc, char **argv )
00186 {
00187   if(argc<2)
00188   {
00189     printf("Usage trimesh_base <meshfilename.ply>\n");
00190     return -1;
00191   }
00192 
00193   MyMesh m, // The loaded mesh
00194          em, // the 2D polyline representing the section
00195          slice, // the planar mesh resulting from the triangulation of the above
00196          sliced; // the 3D mesh resulting by the actual slicing of m into two capped sub pieces
00197 
00198   if(tri::io::ImporterPLY<MyMesh>::Open(m,argv[1])!=0)
00199   {
00200     printf("Error reading file  %s\n",argv[1]);
00201     exit(0);
00202   }
00203   tri::UpdateBounding<MyMesh>::Box(m);
00204   printf("Input mesh  vn:%i fn:%i\n",m.VN(),m.FN());
00205   srand(time(0));
00206 
00207   Plane3f slicingPlane;
00208   GetRandPlane(m.bbox,slicingPlane);
00209   printf("slicing dir %5.2f %5.2f %5.2f\n",slicingPlane.Direction()[0],slicingPlane.Direction()[1],slicingPlane.Direction()[2]);
00210   vcg::IntersectionPlaneMesh<MyMesh, MyMesh, float>(m, slicingPlane, em );
00211   tri::Clean<MyMesh>::RemoveDuplicateVertex(em);
00212   vcg::tri::CapEdgeMesh(em,slice);
00213   printf("Slice  mesh has %i vert and %i faces\n", slice.VN(), slice.FN() );
00214 
00215   MyMesh A,B;
00216   SplitMesh(m,A,B,slicingPlane);
00217   tri::UpdatePosition<MyMesh>::Translate(A, slicingPlane.Direction()*m.bbox.Diag()/80.0);
00218   tri::UpdatePosition<MyMesh>::Translate(B,-slicingPlane.Direction()*m.bbox.Diag()/80.0);
00219   tri::Append<MyMesh,MyMesh>::Mesh(sliced,A);
00220   tri::Append<MyMesh,MyMesh>::Mesh(sliced,B);
00221   printf("Sliced mesh has %i vert and %i faces\n", sliced.VN(), sliced.FN() );
00222 
00223   tri::io::ExporterPLY<MyMesh>::Save(slice,"slice.ply",false);
00224   tri::io::ExporterPLY<MyMesh>::Save(sliced,"sliced.ply",false);
00225 
00226   return 0;
00227 }


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