Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/io/vtk_io.h>
00042 #include <pcl/console/print.h>
00043 #include <pcl/console/parse.h>
00044 #include <pcl/console/time.h>
00045 #include <pcl/surface/gp3.h>
00046 
00047 using namespace pcl;
00048 using namespace pcl::io;
00049 using namespace pcl::console;
00050 
00051 double default_mu = 0.0;
00052 double default_radius = 0.0;
00053 
00054 void
00055 printHelp (int, char **argv)
00056 {
00057   print_error ("Syntax is: %s input.pcd output.vtk <options>\n", argv[0]);
00058   print_info ("  where options are:\n");
00059   print_info ("                     -radius X = use a radius of Xm around each point to determine the neighborhood (default: "); 
00060   print_value ("%f", default_radius); print_info (")\n");
00061   print_info ("                     -mu X     = set the multipler of the nearest neighbor distance to obtain the final search radius (default: "); 
00062   print_value ("%f", default_mu); print_info (")\n");
00063 }
00064 
00065 bool
00066 loadCloud (const std::string &filename, PointCloud<PointNormal> &cloud)
00067 {
00068   TicToc tt;
00069   print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00070 
00071   tt.tic ();
00072   if (loadPCDFile<PointNormal> (filename, cloud) < 0)
00073     return (false);
00074   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00075   print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00076 
00077   return (true);
00078 }
00079 
00080 void
00081 compute (const PointCloud<PointNormal>::Ptr &input, pcl::PolygonMesh &output,
00082          double mu, double radius)
00083 {
00084   
00085   TicToc tt;
00086   tt.tic ();
00087   
00088   print_highlight (stderr, "Computing ");
00089 
00090   PointCloud<PointNormal>::Ptr cloud (new PointCloud<PointNormal> ());
00091   for (size_t i = 0; i < input->size (); ++i)
00092     if (pcl_isfinite (input->points[i].x))
00093       cloud->push_back (input->points[i]);
00094 
00095   cloud->width = static_cast<uint32_t> (cloud->size ());
00096   cloud->height = 1;
00097   cloud->is_dense = true;
00098 
00099   GreedyProjectionTriangulation<PointNormal> gpt;
00100   gpt.setSearchMethod (pcl::search::KdTree<pcl::PointNormal>::Ptr (new pcl::search::KdTree<pcl::PointNormal>));
00101   gpt.setInputCloud (cloud);
00102   gpt.setSearchRadius (radius);
00103   gpt.setMu (mu);
00104 
00105   gpt.reconstruct (output);
00106 
00107   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%zu", output.polygons.size ()); print_info (" polygons]\n");
00108 }
00109 
00110 void
00111 saveCloud (const std::string &filename, const pcl::PolygonMesh &output)
00112 {
00113   TicToc tt;
00114   tt.tic ();
00115 
00116   print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00117   saveVTKFile (filename, output);
00118 
00119   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%zu", output.polygons.size ()); print_info (" polygons]\n");
00120 }
00121 
00122 
00123 int
00124 main (int argc, char** argv)
00125 {
00126   print_info ("Perform surface triangulation using pcl::GreedyProjectionTriangulation. For more information, use: %s -h\n", argv[0]);
00127 
00128   if (argc < 3)
00129   {
00130     printHelp (argc, argv);
00131     return (-1);
00132   }
00133 
00134   
00135   std::vector<int> pcd_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00136   if (pcd_file_indices.size () != 1)
00137   {
00138     print_error ("Need one input PCD file to continue.\n");
00139     return (-1);
00140   }
00141   std::vector<int> vtk_file_indices = parse_file_extension_argument (argc, argv, ".vtk");
00142   if (vtk_file_indices.size () != 1)
00143   {
00144     print_error ("Need one output VTK file to continue.\n");
00145     return (-1);
00146   }
00147 
00148   
00149   double mu = default_mu;
00150   double radius = default_radius;
00151   parse_argument (argc, argv, "-mu", mu);
00152   parse_argument (argc, argv, "-radius", radius);
00153 
00154   
00155   PointCloud<PointNormal>::Ptr cloud (new PointCloud<PointNormal>);
00156   if (!loadCloud (argv[pcd_file_indices[0]], *cloud)) 
00157     return (-1);
00158 
00159   
00160   pcl::PolygonMesh output;
00161   compute (cloud, output, mu, radius);
00162 
00163   
00164   saveCloud (argv[vtk_file_indices[0]], output);
00165 }
00166