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 
00041 #include <pcl/PCLPointCloud2.h>
00042 #include <pcl/io/pcd_io.h>
00043 #include <pcl/io/vtk_io.h>
00044 #include <pcl/console/print.h>
00045 #include <pcl/console/parse.h>
00046 #include <pcl/console/time.h>
00047 #include <pcl/surface/poisson.h>
00048 
00049 using namespace pcl;
00050 using namespace pcl::io;
00051 using namespace pcl::console;
00052 
00053 int default_depth = 8;
00054 int default_solver_divide = 8;
00055 int default_iso_divide = 8;
00056 float default_point_weight = 4.0f;
00057 
00058 void
00059 printHelp (int, char **argv)
00060 {
00061   print_error ("Syntax is: %s input.pcd output.vtk <options>\n", argv[0]);
00062   print_info ("  where options are:\n");
00063   print_info ("                     -depth X          = set the maximum depth of the tree that will be used for surface reconstruction (default: ");
00064   print_value ("%d", default_depth); print_info (")\n");
00065   print_info ("                     -solver_divide X  = set the the depth at which a block Gauss-Seidel solver is used to solve the Laplacian equation (default: ");
00066   print_value ("%d", default_solver_divide); print_info (")\n");
00067   print_info ("                     -iso_divide X     = Set the depth at which a block iso-surface extractor should be used to extract the iso-surface (default: ");
00068   print_value ("%d", default_iso_divide); print_info (")\n");
00069   print_info ("                     -point_weight X   = Specifies the importance that interpolation of the point samples is given in the formulation of the screened Poisson equation. The results of the original (unscreened) Poisson Reconstruction can be obtained by setting this value to 0. (default: ");
00070   print_value ("%f", default_point_weight); print_info (")\n");
00071 }
00072 
00073 bool
00074 loadCloud (const std::string &filename, pcl::PCLPointCloud2 &cloud)
00075 {
00076   TicToc tt;
00077   print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00078 
00079   tt.tic ();
00080   if (loadPCDFile (filename, cloud) < 0)
00081     return (false);
00082   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00083   print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00084 
00085   return (true);
00086 }
00087 
00088 void
00089 compute (const pcl::PCLPointCloud2::ConstPtr &input, PolygonMesh &output,
00090          int depth, int solver_divide, int iso_divide, float point_weight)
00091 {
00092   PointCloud<PointNormal>::Ptr xyz_cloud (new pcl::PointCloud<PointNormal> ());
00093   fromPCLPointCloud2 (*input, *xyz_cloud);
00094 
00095   print_info ("Using parameters: depth %d, solverDivide %d, isoDivide %d\n", depth, solver_divide, iso_divide);
00096 
00097         Poisson<PointNormal> poisson;
00098         poisson.setDepth (depth);
00099         poisson.setSolverDivide (solver_divide);
00100         poisson.setIsoDivide (iso_divide);
00101   poisson.setPointWeight (point_weight);
00102   poisson.setInputCloud (xyz_cloud);
00103 
00104   TicToc tt;
00105   tt.tic ();
00106   print_highlight ("Computing ...");
00107   poisson.reconstruct (output);
00108 
00109   print_info ("[Done, "); print_value ("%g", tt.toc ()); print_info (" ms]\n");
00110 }
00111 
00112 void
00113 saveCloud (const std::string &filename, const PolygonMesh &output)
00114 {
00115   TicToc tt;
00116   tt.tic ();
00117 
00118   print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00119   saveVTKFile (filename, output);
00120 
00121   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms]\n");
00122 }
00123 
00124 
00125 int
00126 main (int argc, char** argv)
00127 {
00128   print_info ("Compute the surface reconstruction of a point cloud using the Poisson surface reconstruction (pcl::surface::Poisson). For more information, use: %s -h\n", argv[0]);
00129 
00130   if (argc < 3)
00131   {
00132     printHelp (argc, argv);
00133     return (-1);
00134   }
00135 
00136   
00137   std::vector<int> pcd_file_indices;
00138   pcd_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00139   if (pcd_file_indices.size () != 1)
00140   {
00141     print_error ("Need one input PCD file and one output VTK file to continue.\n");
00142     return (-1);
00143   }
00144 
00145   std::vector<int> vtk_file_indices = parse_file_extension_argument (argc, argv, ".vtk");
00146   if (vtk_file_indices.size () != 1)
00147   {
00148     print_error ("Need one output VTK file to continue.\n");
00149     return (-1);
00150   }
00151 
00152   
00153   int depth = default_depth;
00154   parse_argument (argc, argv, "-depth", depth);
00155   print_info ("Using a depth of: "); print_value ("%d\n", depth);
00156 
00157   int solver_divide = default_solver_divide;
00158   parse_argument (argc, argv, "-solver_divide", solver_divide);
00159   print_info ("Setting solver_divide to: "); print_value ("%d\n", solver_divide);
00160 
00161   int iso_divide = default_iso_divide;
00162   parse_argument (argc, argv, "-iso_divide", iso_divide);
00163   print_info ("Setting iso_divide to: "); print_value ("%d\n", iso_divide);
00164 
00165   float point_weight = default_point_weight;
00166   parse_argument (argc, argv, "-point_weight", point_weight);
00167   print_info ("Setting point_weight to: "); print_value ("%f\n", point_weight);
00168 
00169   
00170   pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
00171   if (!loadCloud (argv[pcd_file_indices[0]], *cloud))
00172     return (-1);
00173 
00174   
00175   PolygonMesh output;
00176   compute (cloud, output, depth, solver_divide, iso_divide, point_weight);
00177 
00178   
00179   saveCloud (argv[vtk_file_indices[0]], output);
00180 }
00181