metro.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                                                \/)\/    *
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   History
00025 
00026 $Log: not supported by cvs2svn $
00027 Revision 1.23  2007/05/04 16:50:23  ganovelli
00028 added plus types version (#ifdef _PLUS_TYPES_ to use it ).
00029 
00030 Revision 1.22  2006/10/25 12:40:19  fiorin
00031 Added possibility to use Octree as search structure:
00032 
00033 Revision 1.21  2006/05/03 21:22:39  cignoni
00034 added missing Include
00035 
00036 Revision 1.20  2006/04/20 08:30:24  cignoni
00037 small GCC compiling issues
00038 
00039 Revision 1.19  2006/03/27 04:17:07  cignoni
00040 moved to generic export.h
00041 
00042 Revision 1.18  2006/01/10 13:20:40  cignoni
00043 Changed ply::PlyMask to io::Mask
00044 
00045 Revision 1.17  2005/10/02 23:11:00  cignoni
00046 Version 4.06, Added possibility of using three different search structures UG Hash and AABB
00047 
00048 Revision 1.16  2005/09/16 11:52:14  cignoni
00049 removed wrong %v in vertex number printing
00050 
00051 Revision 1.15  2005/04/04 10:36:36  cignoni
00052 Release 4.05
00053 Added saving of Error Histogram
00054 
00055 Revision 1.14  2005/01/26 22:45:34  cignoni
00056 Release 4.04
00057 final updates for gcc compiling issues
00058 
00059 Revision 1.13  2005/01/24 15:46:48  cignoni
00060 Release 4.04
00061 Moved to the library core the code for computing min distance froma a point to a mesh using a uniform grid.
00062 Slightly faster.
00063 
00064 Revision 1.12  2005/01/03 11:28:52  cignoni
00065 Release 4.03
00066 Better ply compatibility, and improved error reporting
00067 
00068 Revision 1.11  2004/11/29 09:07:04  cignoni
00069 Release 4.02
00070 removed bug in printing Hausdorf distance,
00071 removed bug in command line parsing,
00072 upgraded import mesh library to support off format
00073 
00074 Revision 1.10  2004/09/21 23:52:50  cignoni
00075 Release 4.01
00076 
00077 Revision 1.9  2004/09/20 16:29:08  ponchio
00078 Minimal changes.
00079 
00080 Revision 1.8  2004/09/20 15:17:28  cignoni
00081 Removed bug in displays msec and better usage messages
00082 
00083 Revision 1.7  2004/09/09 22:59:15  cignoni
00084 Removed many small warnings
00085 
00086 Revision 1.6  2004/07/15 00:15:16  cignoni
00087 inflate -> offset
00088 
00089 Revision 1.5  2004/06/24 09:08:31  cignoni
00090 Official Release of Metro 4.00
00091 
00092 Revision 1.4  2004/05/14 13:53:12  ganovelli
00093 GPL  added
00094 
00095 ****************************************************************************/
00096 
00097 // -----------------------------------------------------------------------------------------------
00098 
00099 // standard libraries
00100 #include <time.h>
00101 
00102 
00103 #include <vcg/math/histogram.h>
00104 #include <vcg/complex/complex.h>
00105 #include <vcg/simplex/face/component_ep.h>
00106 #include <wrap/io_trimesh/import.h>
00107 #include <wrap/io_trimesh/export.h>
00108 #include <vcg/complex/algorithms/update/component_ep.h>
00109 #include <vcg/complex/algorithms/update/bounding.h>
00110 #include "sampling.h"
00111 
00112 using namespace std;
00113 // project definitions.
00114 // error messages
00115 
00116 #define MSG_ERR_MESH_LOAD               "error loading the input meshes.\n"
00117 #define MSG_ERR_INVALID_OPTION          "unable to parse option '%s'\n"
00118 #define MSG_ERR_FILE_OPEN               "unable to open the output file.'n"
00119 #define MSG_ERR_UNKNOWN_FORMAT          "unknown file format '%s'.\n"
00120 
00121 // global constants
00122 #define NO_SAMPLES_PER_FACE             10
00123 #define N_SAMPLES_EDGE_TO_FACE_RATIO    0.1
00124 #define BBOX_FACTOR                     0.1
00125 #define INFLATE_PERCENTAGE                          0.02
00126 #define MIN_SIZE                                            125         /* 125 = 5^3 */
00127 #define N_HIST_BINS                     256
00128 #define PRINT_EVERY_N_ELEMENTS          1000
00129 
00130 
00131 class CFace;
00132 class CVertex;
00133 struct UsedTypes:public vcg::UsedTypes< vcg::Use<CFace>::AsFaceType, vcg::Use<CVertex>::AsVertexType>{};
00134 class CVertex   : public vcg::Vertex<UsedTypes,vcg::vertex::Coord3d,vcg::vertex::Qualityf,vcg::vertex::Normal3d,vcg::vertex::Color4b,vcg::vertex::BitFlags> {};
00135 class CFace     : public vcg::Face< UsedTypes,vcg::face::VertexRef, vcg::face::Normal3d, vcg::face::EdgePlane,vcg::face::Color4b,vcg::face::Mark,vcg::face::BitFlags> {};
00136 class CMesh     : public vcg::tri::TriMesh< std::vector<CVertex>, std::vector<CFace> > {};
00137 
00138 
00139 // -----------------------------------------------------------------------------------------------
00140 
00141 using namespace vcg;
00142 
00143 
00145 bool NumberOfSamples                = false;
00146 bool SamplesPerAreaUnit             = false;
00147 bool CleaningFlag=false;
00148 // -----------------------------------------------------------------------------------------------
00149 
00150 void Usage()
00151 {
00152   printf("\nUsage:  "\
00153                                         "metro file1 file2 [opt]\n"\
00154                                         "Where opt can be:\n"\
00155                                         "  -v         disable vertex sampling\n"\
00156                                         "  -e         disable edge sampling\n"\
00157                                         "  -f         disable face sampling\n"\
00158                                         "  -u         ignore unreferred vertices\n"\
00159                                         "  -sx        set the face sampling mode\n"\
00160                                         "             where x can be:\n"\
00161                                         "              -s0  montecarlo sampling\n"\
00162                                         "              -s1  subdivision sampling\n"\
00163                                         "              -s2  similar triangles sampling (Default)\n"\
00164                                         "  -n#        set the required number of samples (overrides -A)\n"\
00165                                         "  -a#        set the required number of samples per area unit (overrides -N)\n"\
00166                                         "  -c         save a mesh with error as per-vertex colour and quality\n"\
00167                                         "  -C # #     Set the min/max values used for color mapping\n"\
00168                                         "  -L         Remove duplicated and unreferenced vertices before processing\n"\
00169                                         "  -h         write files with histograms of error distribution\n"\
00170                                         "  -G         Use a static Uniform Grid as Search Structure (default)\n"\
00171                                                                                                                                                                 "  -O         Use an octree as a Search Structure\n"\
00172                                         "  -A         Use an AxisAligned Bounding Box Tree as Search Structure\n"\
00173                                         "  -H         Use an Hashed Uniform Grid as Search Structure\n"\
00174                                         "\n"
00175                                         "Default options are to sample vertexes, edge and faces by taking \n"
00176                                         "a number of samples that is approx. 10x the face number.\n"
00177                                         );
00178   exit(-1);
00179 }
00180 
00181 
00182 // simple aux function that compute the name for the file containing the stored computations
00183 std::string SaveFileName(const std::string &filename)
00184 {
00185  int pos=filename.find_last_of('.',filename.length());
00186  std::string fileout=filename.substr(0,pos)+"_metro.ply";
00187  return fileout;
00188 }
00189 
00190 
00191 // Open Mesh
00192 void OpenMesh(const char *filename, CMesh &m)
00193 {
00194   int err = tri::io::Importer<CMesh>::Open(m,filename);
00195   if(err) {
00196       printf("Error in reading %s: '%s'\n",filename,tri::io::Importer<CMesh>::ErrorMsg(err));
00197       if(tri::io::Importer<CMesh>::ErrorCritical(err)) exit(-1);
00198     }
00199   printf("read mesh `%s'\n", filename);
00200   if(CleaningFlag){
00201       int dup = tri::Clean<CMesh>::RemoveDuplicateVertex(m);
00202       int unref =  tri::Clean<CMesh>::RemoveUnreferencedVertex(m);
00203       printf("Removed %i duplicate and %i unreferenced vertices from mesh %s\n",dup,unref,filename);
00204   }
00205 }
00206 
00207 
00208 int main(int argc, char**argv)
00209 {
00210     CMesh                 S1, S2;
00211     float                ColorMin=0, ColorMax=0;
00212     double                dist1_max, dist2_max;
00213     unsigned long         n_samples_target, elapsed_time;
00214     double                                                              n_samples_per_area_unit;
00215     int                   flags;
00216 
00217     // print program info
00218     printf("-------------------------------\n"
00219            "         Metro V.4.07 \n"
00220            "     http://vcg.isti.cnr.it\n"
00221            "   release date: "__DATE__"\n"
00222            "-------------------------------\n\n");
00223 
00224     if(argc <= 2)    Usage();
00225     // default parameters
00226     flags = SamplingFlags::VERTEX_SAMPLING |
00227           SamplingFlags::EDGE_SAMPLING |
00228           SamplingFlags::FACE_SAMPLING |
00229           SamplingFlags::SIMILAR_SAMPLING;
00230 
00231     // parse command line.
00232           for(int i=3; i < argc;)
00233     {
00234       if(argv[i][0]=='-')
00235         switch(argv[i][1])
00236       {
00237         case 'h' : flags |= SamplingFlags::HIST; break;
00238         case 'v' : flags &= ~SamplingFlags::VERTEX_SAMPLING; break;
00239         case 'e' : flags &= ~SamplingFlags::EDGE_SAMPLING; break;
00240         case 'f' : flags &= ~SamplingFlags::FACE_SAMPLING; break;
00241         case 'u' : flags |= SamplingFlags::INCLUDE_UNREFERENCED_VERTICES; break;
00242         case 's'   :
00243           switch(argv[i][2])
00244           {
00245             case '0':  flags = (flags | SamplingFlags::MONTECARLO_SAMPLING  ) & (~ SamplingFlags::NO_SAMPLING );break;
00246             case '1':  flags = (flags | SamplingFlags::SUBDIVISION_SAMPLING ) & (~ SamplingFlags::NO_SAMPLING );break;
00247             case '2':  flags = (flags | SamplingFlags::SIMILAR_SAMPLING     ) & (~ SamplingFlags::NO_SAMPLING );break;
00248             default  :  printf(MSG_ERR_INVALID_OPTION, argv[i]);
00249               exit(0);
00250           }
00251           break;
00252         case 'n':  NumberOfSamples       = true;     n_samples_target        = (unsigned long) atoi(&(argv[i][2]));          break;
00253         case 'a':  SamplesPerAreaUnit    = true;     n_samples_per_area_unit = (unsigned long) atoi(&(argv[i][2])); break;
00254         case 'c':  flags |= SamplingFlags::SAVE_ERROR;   break;
00255         case 'L':  CleaningFlag=true; break;
00256         case 'C':  ColorMin=float(atof(argv[i+1])); ColorMax=float(atof(argv[i+2])); i+=2; break;
00257         case 'A':  flags |= SamplingFlags::USE_AABB_TREE;   printf("Using AABB Tree as search structure\n");           break;
00258         case 'G':  flags |= SamplingFlags::USE_STATIC_GRID; printf("Using static uniform grid as search structure\n"); break;
00259         case 'H':  flags |= SamplingFlags::USE_HASH_GRID;   printf("Using hashed uniform grid as search structure\n"); break;
00260                                 case 'O':  flags |= SamplingFlags::USE_OCTREE;      printf("Using octree as search structure\n");              break;
00261         default  :  printf(MSG_ERR_INVALID_OPTION, argv[i]);
00262           exit(0);
00263       }
00264       i++;
00265     }
00266 
00267                 if(!(flags & SamplingFlags::USE_HASH_GRID) && !(flags & SamplingFlags::USE_AABB_TREE) && !(flags & SamplingFlags::USE_OCTREE))
00268        flags |= SamplingFlags::USE_STATIC_GRID;
00269 
00270     // load input meshes.
00271     OpenMesh(argv[1],S1);
00272     OpenMesh(argv[2],S2);
00273 
00274     string S1NewName=SaveFileName(argv[1]);
00275     string S2NewName=SaveFileName(argv[2]);
00276 
00277     if(!NumberOfSamples && !SamplesPerAreaUnit)
00278     {
00279         NumberOfSamples = true;
00280         n_samples_target = 10 * max(S1.fn,S2.fn);// take 10 samples per face
00281     }
00282 
00283     // compute face information
00284         tri::UpdateComponentEP<CMesh>::Set(S1);
00285         tri::UpdateComponentEP<CMesh>::Set(S2);
00286 
00287         // set bounding boxes for S1 and S2
00288                 tri::UpdateBounding<CMesh>::Box(S1);
00289                 tri::UpdateBounding<CMesh>::Box(S2);
00290 
00291     // set Bounding Box.
00292                 Box3<CMesh::ScalarType>    bbox, tmp_bbox_M1=S1.bbox, tmp_bbox_M2=S2.bbox;
00293     bbox.Add(S1.bbox);
00294     bbox.Add(S2.bbox);
00295                 bbox.Offset(bbox.Diag()*0.02);
00296           S1.bbox = bbox;
00297           S2.bbox = bbox;
00298 
00299     // initialize time info.
00300     int t0=clock();
00301 
00302     Sampling<CMesh> ForwardSampling(S1,S2);
00303     Sampling<CMesh> BackwardSampling(S2,S1);
00304 
00305     // print mesh info.
00306     printf("Mesh info:\n");
00307     printf(" M1: '%s'\n\tvertices  %7i\n\tfaces     %7i\n\tarea      %12.4f\n", argv[1], S1.vn, S1.fn, ForwardSampling.GetArea());
00308     printf("\tbbox (%7.4f %7.4f %7.4f)-(%7.4f %7.4f %7.4f)\n", tmp_bbox_M1.min[0], tmp_bbox_M1.min[1], tmp_bbox_M1.min[2], tmp_bbox_M1.max[0], tmp_bbox_M1.max[1], tmp_bbox_M1.max[2]);
00309     printf("\tbbox diagonal %f\n", (float)tmp_bbox_M1.Diag());
00310     printf(" M2: '%s'\n\tvertices  %7i\n\tfaces     %7i\n\tarea      %12.4f\n", argv[2], S2.vn, S2.fn, BackwardSampling.GetArea());
00311     printf("\tbbox (%7.4f %7.4f %7.4f)-(%7.4f %7.4f %7.4f)\n", tmp_bbox_M2.min[0], tmp_bbox_M2.min[1], tmp_bbox_M2.min[2], tmp_bbox_M2.max[0], tmp_bbox_M2.max[1], tmp_bbox_M2.max[2]);
00312     printf("\tbbox diagonal %f\n", (float)tmp_bbox_M2.Diag());
00313 
00314     // Forward distance.
00315     printf("\nForward distance (M1 -> M2):\n");
00316     ForwardSampling.SetFlags(flags);
00317     if(NumberOfSamples)
00318     {
00319         ForwardSampling.SetSamplesTarget(n_samples_target);
00320         n_samples_per_area_unit = ForwardSampling.GetNSamplesPerAreaUnit();
00321     }
00322     else
00323     {
00324         ForwardSampling.SetSamplesPerAreaUnit(n_samples_per_area_unit);
00325         n_samples_target = ForwardSampling.GetNSamplesTarget();
00326     }
00327     printf("target # samples      : %lu\ntarget # samples/area : %f\n", n_samples_target, n_samples_per_area_unit);
00328     ForwardSampling.Hausdorff();
00329     dist1_max  = ForwardSampling.GetDistMax();
00330     printf("\ndistances:\n  max  : %f (%f  wrt bounding box diagonal)\n", (float)dist1_max, (float)dist1_max/bbox.Diag());
00331     printf("  mean : %f\n", ForwardSampling.GetDistMean());
00332     printf("  RMS  : %f\n", ForwardSampling.GetDistRMS());
00333     printf("# vertex samples %9lu\n", ForwardSampling.GetNVertexSamples());
00334     printf("# edge samples   %9lu\n", ForwardSampling.GetNEdgeSamples());
00335     printf("# area samples   %9lu\n", ForwardSampling.GetNAreaSamples());
00336     printf("# total samples  %9lu\n", ForwardSampling.GetNSamples());
00337     printf("# samples per area unit: %f\n\n", ForwardSampling.GetNSamplesPerAreaUnit());
00338 
00339     // Backward distance.
00340     printf("\nBackward distance (M2 -> M1):\n");
00341     BackwardSampling.SetFlags(flags);
00342     if(NumberOfSamples)
00343     {
00344         BackwardSampling.SetSamplesTarget(n_samples_target);
00345         n_samples_per_area_unit = BackwardSampling.GetNSamplesPerAreaUnit();
00346     }
00347     else
00348     {
00349         BackwardSampling.SetSamplesPerAreaUnit(n_samples_per_area_unit);
00350         n_samples_target = BackwardSampling.GetNSamplesTarget();
00351     }
00352     printf("target # samples      : %lu\ntarget # samples/area : %f\n", n_samples_target, n_samples_per_area_unit);
00353     BackwardSampling.Hausdorff();
00354     dist2_max  = BackwardSampling.GetDistMax();
00355     printf("\ndistances:\n  max  : %f (%f  wrt bounding box diagonal)\n", (float)dist2_max, (float)dist2_max/bbox.Diag());
00356     printf("  mean : %f\n", BackwardSampling.GetDistMean());
00357     printf("  RMS  : %f\n", BackwardSampling.GetDistRMS());
00358     printf("# vertex samples %9lu\n", BackwardSampling.GetNVertexSamples());
00359     printf("# edge samples   %9lu\n", BackwardSampling.GetNEdgeSamples());
00360     printf("# area samples   %9lu\n", BackwardSampling.GetNAreaSamples());
00361     printf("# total samples  %9lu\n", BackwardSampling.GetNSamples());
00362     printf("# samples per area unit: %f\n\n", BackwardSampling.GetNSamplesPerAreaUnit());
00363 
00364     // compute time info.
00365     elapsed_time = clock() - t0;
00366     int n_total_sample=ForwardSampling.GetNSamples()+BackwardSampling.GetNSamples();
00367     double mesh_dist_max  = max(dist1_max , dist2_max);
00368 
00369     printf("\nHausdorff distance: %f (%f  wrt bounding box diagonal)\n",(float)mesh_dist_max,(float)mesh_dist_max/bbox.Diag());
00370     printf("  Computation time  : %d ms\n",(int)(1000.0*elapsed_time/CLOCKS_PER_SEC));
00371     printf("  # samples/second  : %f\n\n", (float)n_total_sample/((float)elapsed_time/CLOCKS_PER_SEC));
00372 
00373     // save error files.
00374     if(flags & SamplingFlags::SAVE_ERROR)
00375     {
00376       vcg::tri::io::PlyInfo p;
00377       p.mask|=vcg::tri::io::Mask::IOM_VERTCOLOR | vcg::tri::io::Mask::IOM_VERTQUALITY /* | vcg::ply::PLYMask::PM_VERTQUALITY*/ ;
00378       //p.mask|=vcg::ply::PLYMask::PM_VERTCOLOR|vcg::ply::PLYMask::PM_VERTQUALITY;
00379       if(ColorMax!=0 || ColorMin != 0){
00380         vcg::tri::UpdateColor<CMesh>::PerVertexQualityRamp(S1,ColorMin,ColorMax);
00381         vcg::tri::UpdateColor<CMesh>::PerVertexQualityRamp(S2,ColorMin,ColorMax);
00382       }
00383       tri::io::ExporterPLY<CMesh>::Save( S1,S1NewName.c_str(),true,p);
00384       tri::io::ExporterPLY<CMesh>::Save( S2,S2NewName.c_str(),true,p);
00385     }
00386 
00387     // save error files.
00388     if(flags & SamplingFlags::HIST)
00389     {
00390       ForwardSampling.GetHist().FileWrite("forward_result.csv");
00391       BackwardSampling.GetHist().FileWrite("backward_result.csv");
00392     }
00393    return 0;
00394 }
00395 
00396 // -----------------------------------------------------------------------------------------------


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