trimesh_voronoisampling.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-2009                                           \/)\/    *
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 #include<vcg/complex/complex.h>
00025 #include<vcg/complex/algorithms/create/platonic.h>
00026 #include<wrap/io_trimesh/import_ply.h>
00027 #include<wrap/io_trimesh/export_off.h>
00028 #include<wrap/io_trimesh/export_ply.h>
00029 #include<wrap/io_trimesh/export_dxf.h>
00030 #include<vcg/complex/algorithms/point_sampling.h>
00031 #include<vcg/complex/algorithms/voronoi_processing.h>
00032 
00033 
00034 using namespace vcg;
00035 using namespace std;
00036 
00037 class MyEdge;
00038 class MyFace;
00039 class MyVertex;
00040 struct MyUsedTypes : public UsedTypes<  Use<MyVertex>   ::AsVertexType,
00041                                         Use<MyEdge>     ::AsEdgeType,
00042                                         Use<MyFace>     ::AsFaceType>{};
00043 
00044 class MyVertex  : public Vertex<MyUsedTypes,  vertex::Coord3f, vertex::Normal3f, vertex::VFAdj, vertex::Qualityf, vertex::Color4b, vertex::BitFlags  >{};
00045 class MyFace    : public Face< MyUsedTypes,   face::VertexRef, face::Normal3f, face::BitFlags, face::Mark, face::VFAdj, face::FFAdj > {};
00046 class MyEdge    : public Edge< MyUsedTypes, edge::VertexRef, edge::BitFlags>{};
00047 class MyMesh    : public tri::TriMesh< vector<MyVertex>, vector<MyEdge>, vector<MyFace>   > {};
00048 
00049 class EmEdge;
00050 class EmFace;
00051 class EmVertex;
00052 struct EmUsedTypes : public UsedTypes<  Use<EmVertex>   ::AsVertexType,
00053                                         Use<EmEdge>     ::AsEdgeType,
00054                                         Use<EmFace>     ::AsFaceType>{};
00055 
00056 class EmVertex  : public Vertex<EmUsedTypes,  vertex::Coord3f, vertex::Normal3f, vertex::VFAdj , vertex::Qualityf, vertex::Color4b, vertex::BitFlags  >{};
00057 class EmFace    : public Face< EmUsedTypes,   face::VertexRef, face::BitFlags, face::VFAdj > {};
00058 class EmEdge    : public Edge< EmUsedTypes, edge::VertexRef> {};
00059 class EmMesh    : public tri::TriMesh< vector<EmVertex>, vector<EmEdge>, vector<EmFace>   > {};
00060 
00061 
00062 int main( int argc, char **argv )
00063 {
00064   MyMesh baseMesh;
00065   if(argc < 4 )
00066   {
00067     printf("Usage trimesh_voronoisampling mesh sampleNum iterNum\n");
00068      return -1;
00069   }
00070   int sampleNum = atoi(argv[2]);
00071   int iterNum   = atoi(argv[3]);
00072 
00073   bool fixCornerFlag=true;
00074   bool uniformEdgeSamplingFlag = true;
00075 
00076   printf("Reading %s and sampling %i points with %i iteration\n",argv[1],sampleNum,iterNum);
00077   int ret= tri::io::ImporterPLY<MyMesh>::Open(baseMesh,argv[1]);
00078   if(ret!=0)
00079   {
00080     printf("Unable to open %s for '%s'\n",argv[1],tri::io::ImporterPLY<MyMesh>::ErrorMsg(ret));
00081     return -1;
00082   }
00083 
00084   tri::VoronoiProcessingParameter vpp;
00085 
00086   tri::Clean<MyMesh>::RemoveUnreferencedVertex(baseMesh);
00087   tri::Allocator<MyMesh>::CompactEveryVector(baseMesh);
00088   tri::UpdateTopology<MyMesh>::VertexFace(baseMesh);
00089 
00090   tri::SurfaceSampling<MyMesh,tri::TrivialSampler<MyMesh> >::PoissonDiskParam pp;
00091   float radius = tri::SurfaceSampling<MyMesh,tri::TrivialSampler<MyMesh> >::ComputePoissonDiskRadius(baseMesh,sampleNum);
00092   tri::VoronoiProcessing<MyMesh>::PreprocessForVoronoi(baseMesh,radius,vpp);
00093 
00094   tri::UpdateFlags<MyMesh>::FaceBorderFromVF(baseMesh);
00095   tri::UpdateFlags<MyMesh>::VertexBorderFromFaceBorder(baseMesh);
00096 
00097 
00098   // -- Build a sampling with just corners (Poisson filtered)
00099   MyMesh poissonCornerMesh;
00100   std::vector<Point3f> sampleVec;
00101   tri::TrivialSampler<MyMesh> mps(sampleVec);
00102   tri::SurfaceSampling<MyMesh,tri::TrivialSampler<MyMesh> >::VertexBorderCorner(baseMesh,mps,math::ToRad(150.f));
00103   tri::BuildMeshFromCoordVector(poissonCornerMesh,sampleVec);
00104   tri::io::ExporterPLY<MyMesh>::Save(poissonCornerMesh,"cornerMesh.ply");
00105   sampleVec.clear();
00106   MyMesh borderMesh,poissonBorderMesh;
00107 
00108 
00109   if(uniformEdgeSamplingFlag)
00110   {
00111 
00112   }
00113   else
00114   {
00115     if(fixCornerFlag)
00116     {
00117       tri::SurfaceSampling<MyMesh,tri::TrivialSampler<MyMesh> >::PoissonDiskPruning(mps, poissonCornerMesh, radius, pp);
00118       tri::BuildMeshFromCoordVector(poissonCornerMesh,sampleVec);
00119       tri::io::ExporterPLY<MyMesh>::Save(poissonCornerMesh,"poissonCornerMesh.ply");
00120       // Now save the corner as Fixed Seeds for later...
00121       std::vector<MyVertex *> fixedSeedVec;
00122       tri::VoronoiProcessing<MyMesh>::SeedToVertexConversion(baseMesh,sampleVec,fixedSeedVec);
00123       tri::VoronoiProcessing<MyMesh, tri::EuclideanDistance<MyMesh> >::FixVertexVector(baseMesh,fixedSeedVec);
00124       vpp.preserveFixedSeed=true;
00125     }
00126 
00127   // -- Build a sampling with points on the border
00128   sampleVec.clear();
00129   tri::SurfaceSampling<MyMesh,tri::TrivialSampler<MyMesh> >::VertexBorder(baseMesh,mps);
00130   tri::BuildMeshFromCoordVector(borderMesh,sampleVec);
00131   tri::io::ExporterPLY<MyMesh>::Save(borderMesh,"borderMesh.ply");
00132 
00133   // -- and then prune the border sampling with poisson strategy using the precomputed corner vertexes.
00134   pp.preGenMesh = &poissonCornerMesh;
00135   pp.preGenFlag=true;
00136   sampleVec.clear();
00137   tri::SurfaceSampling<MyMesh,tri::TrivialSampler<MyMesh> >::PoissonDiskPruning(mps, borderMesh, radius*0.8f, pp);
00138   tri::BuildMeshFromCoordVector(poissonBorderMesh,sampleVec);
00139   }
00140 
00141   tri::io::ExporterPLY<MyMesh>::Save(poissonBorderMesh,"PoissonEdgeMesh.ply");
00142 
00143   // -- Build the montercarlo sampling of the surface
00144   MyMesh MontecarloSurfaceMesh;
00145   sampleVec.clear();
00146   tri::SurfaceSampling<MyMesh,tri::TrivialSampler<MyMesh> >::Montecarlo(baseMesh,mps,50000);
00147   tri::BuildMeshFromCoordVector(MontecarloSurfaceMesh,sampleVec);
00148   tri::io::ExporterPLY<MyMesh>::Save(MontecarloSurfaceMesh,"MontecarloSurfaceMesh.ply");
00149 
00150   // -- Prune the montecarlo sampling with poisson strategy using the precomputed vertexes on the border.
00151   pp.preGenMesh = &poissonBorderMesh;
00152   sampleVec.clear();
00153   tri::SurfaceSampling<MyMesh,tri::TrivialSampler<MyMesh> >::PoissonDiskPruning(mps, MontecarloSurfaceMesh, radius, pp);
00154   MyMesh PoissonMesh;
00155   tri::BuildMeshFromCoordVector(PoissonMesh,sampleVec);
00156   tri::io::ExporterPLY<MyMesh>::Save(PoissonMesh,"PoissonMesh.ply");
00157 
00158   std::vector<MyVertex *> seedVec;
00159   tri::VoronoiProcessing<MyMesh>::SeedToVertexConversion(baseMesh,sampleVec,seedVec);
00160 
00161   // Select all the vertexes on the border to define a constrained domain.
00162   // In our case we select the border vertexes to make sure that the seeds on the border
00163   // relax themselves remaining on the border
00164   for(size_t i=0;i<baseMesh.vert.size();++i){
00165     if(baseMesh.vert[i].IsB())
00166         baseMesh.vert[i].SetS();
00167   }
00168 
00169 //  vpp.deleteUnreachedRegionFlag=true;
00170   vpp.deleteUnreachedRegionFlag=false;
00171   vpp.triangulateRegion = false;
00172   vpp.geodesicRelaxFlag=false;
00173   vpp.constrainSelectedSeed=true;
00174 
00175   tri::EuclideanDistance<MyMesh> dd;
00176   int t0=clock();
00177   // And now, at last, the relaxing procedure!
00178   int actualIter = tri::VoronoiProcessing<MyMesh, tri::EuclideanDistance<MyMesh> >::VoronoiRelaxing(baseMesh, seedVec, iterNum, dd, vpp);
00179   int t1=clock();
00180 
00181   MyMesh voroMesh, voroPoly, delaMesh;
00182   // Get the result in some pleasant form converting it to a real voronoi diagram.
00183   if(tri::VoronoiProcessing<MyMesh>::CheckVoronoiTopology(baseMesh,seedVec))
00184      tri::VoronoiProcessing<MyMesh>::ConvertVoronoiDiagramToMesh(baseMesh,voroMesh,voroPoly,seedVec, vpp);
00185   else
00186     printf("WARNING some voronoi region are not disk like; the resulting delaunay triangulation is not manifold.\n");
00187 
00188   tri::io::ExporterPLY<MyMesh>::Save(baseMesh,"base.ply",tri::io::Mask::IOM_VERTCOLOR + tri::io::Mask::IOM_VERTQUALITY );
00189   tri::io::ExporterPLY<MyMesh>::Save(voroMesh,"voroMesh.ply",tri::io::Mask::IOM_VERTCOLOR + tri::io::Mask::IOM_FLAGS );
00190   tri::io::ExporterPLY<MyMesh>::Save(voroPoly,"voroPoly.ply",tri::io::Mask::IOM_VERTCOLOR| tri::io::Mask::IOM_EDGEINDEX ,false);
00191 
00192   tri::VoronoiProcessing<MyMesh>::ConvertDelaunayTriangulationToMesh(baseMesh,delaMesh, seedVec);
00193   tri::io::ExporterPLY<MyMesh>::Save(delaMesh,"delaMesh.ply",tri::io::Mask::IOM_VERTCOLOR + tri::io::Mask::IOM_VERTQUALITY );
00194   tri::VoronoiProcessing<MyMesh>::RelaxRefineTriangulationSpring(baseMesh,delaMesh,2,10);
00195   tri::io::ExporterPLY<MyMesh>::Save(delaMesh,"delaMeshRef.ply",tri::io::Mask::IOM_VERTCOLOR + tri::io::Mask::IOM_VERTQUALITY );
00196 
00197 
00198 //  tri::io::ImporterPLY<MyMesh>::Open(baseMesh,argv[1]);
00199 //  tri::UpdateTopology<MyMesh>::VertexFace(baseMesh);
00200 //  tri::PoissonSampling<MyMesh>(baseMesh,pointVec,sampleNum,radius,radiusVariance);
00201 //  tri::VoronoiProcessing<MyMesh>::SeedToVertexConversion(baseMesh,pointVec,seedVec);
00202 //  tri::IsotropicDistance<MyMesh> id(baseMesh,radiusVariance);
00203 //  tri::VoronoiProcessing<MyMesh, tri::IsotropicDistance<MyMesh> >::VoronoiRelaxing(baseMesh, seedVec, iterNum,id,vpp);
00204 //  tri::VoronoiProcessing<MyMesh, tri::IsotropicDistance<MyMesh> >::ConvertVoronoiDiagramToMesh(baseMesh,outMesh,polyMesh,seedVec, id, vpp);
00205 
00206 //  tri::io::ExporterPLY<MyMesh>::Save(outMesh,"outW.ply",tri::io::Mask::IOM_VERTCOLOR );
00207 //  tri::io::ExporterPLY<MyMesh>::Save(polyMesh,"polyW.ply",tri::io::Mask::IOM_VERTCOLOR | tri::io::Mask::IOM_EDGEINDEX,false);
00208 //  tri::io::ExporterDXF<MyMesh>::Save(polyMesh,"outW.dxf");
00209   printf("Completed! %i (%i) iterations in %f sec for %lu seeds \n",actualIter, iterNum,float(t1-t0)/CLOCKS_PER_SEC,seedVec.size());
00210   return 0;
00211 }


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