poisson_reconstruction.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: poisson_reconstruction.cpp 5124 2012-03-16 03:09:41Z rusu $
00035  *
00036  */
00037 
00038 #include <sensor_msgs/PointCloud2.h>
00039 #include <pcl/io/pcd_io.h>
00040 #include <pcl/io/vtk_io.h>
00041 #include <pcl/surface/poisson.h>
00042 #include <pcl/console/print.h>
00043 #include <pcl/console/parse.h>
00044 #include <pcl/console/time.h>
00045 
00046 using namespace pcl;
00047 using namespace pcl::io;
00048 using namespace pcl::console;
00049 
00050 #include <fstream>
00051 using namespace std;
00052 
00053 float default_leaf_size = 0.01f;
00054 float default_iso_level = 0.0f;
00055 int   default_use_dot = 1;
00056 
00057 void
00058 printHelp (int, char **argv)
00059 {
00060   print_error ("Syntax is: %s input.pcd output.vtk <options>\n", argv[0]);
00061   print_info ("  where options are:\n");
00062   print_info ("                     -leaf X    = the voxel size (default: ");
00063   print_value ("%f", default_leaf_size); print_info (")\n");
00064   print_info ("                     -iso X     = the iso level (default: ");
00065   print_value ("%f", default_iso_level); print_info (")\n");
00066   print_info ("                     -dot X     = use the voxelization algorithm combined with a dot product (i.e. MarchingCubesGreedy vs. MarchingCubesGreedyDot) (default: ");
00067   print_value ("%d", default_use_dot); print_info (")\n");
00068 }
00069 
00070 bool
00071 loadCloud (const std::string &filename, sensor_msgs::PointCloud2 &cloud)
00072 {
00073   TicToc tt;
00074   print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00075 
00076   tt.tic ();
00077   if (loadPCDFile (filename, cloud) < 0)
00078     return (false);
00079   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00080   print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00081 
00082   return (true);
00083 }
00084 
00085 void
00086 compute (const sensor_msgs::PointCloud2::ConstPtr &input, PolygonMesh &output,
00087          float /*leaf_size*/, float /*iso_level*/, int /*use_dot*/)
00088 {
00089   PointCloud<PointNormal>::Ptr xyz_cloud (new pcl::PointCloud<PointNormal> ());
00090   fromROSMsg (*input, *xyz_cloud);
00091 
00092         /* PointCloud<PointNormal>::Ptr cloud_clean (new pcl::PointCloud<PointNormal> ());
00093   for (int i = 0; i < xyz_cloud->size (); ++i)
00094     if (pcl_isfinite (xyz_cloud->points[i].x))
00095     {
00096       cloud_clean->push_back (xyz_cloud->points[i]);
00097     }
00098   cloud_clean->width = cloud_clean->size ();
00099   cloud_clean->height = 1;
00100 
00101         io::savePCDFileASCII ("cloud_clean.pcd", *cloud_clean);
00102         */
00103   Poisson<PointNormal> poisson;
00104   poisson.setDepth (10);
00105   poisson.setSolverDivide (8);
00106   poisson.setInputCloud (xyz_cloud);
00107 
00108 
00109   TicToc tt;
00110   tt.tic ();
00111 
00112   print_highlight ("Computing ");
00113   poisson.reconstruct (output);
00114 
00115   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms]\n");
00116 }
00117 
00118 void
00119 saveCloud (const std::string &filename, const PolygonMesh &output)
00120 {
00121   TicToc tt;
00122   tt.tic ();
00123 
00124   print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00125   saveVTKFile (filename, output);
00126 
00127   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms]\n");
00128 }
00129 
00130 /* ---[ */
00131 int
00132 main (int argc, char** argv)
00133 {
00134   print_info ("Compute the surface reconstruction of a point cloud using the marching cubes algorithm (pcl::surface::MarchingCubesGreedy or pcl::surface::MarchingCubesGreedyDot. For more information, use: %s -h\n", argv[0]);
00135 
00136   if (argc < 3)
00137   {
00138     printHelp (argc, argv);
00139     return (-1);
00140   }
00141 
00142   // Parse the command line arguments for .pcd files
00143   std::vector<int> pcd_file_indices;
00144   pcd_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00145   if (pcd_file_indices.size () != 1)
00146   {
00147     print_error ("Need one input PCD file and one output PCD file to continue.\n");
00148     return (-1);
00149   }
00150 
00151   std::vector<int> vtk_file_indices = parse_file_extension_argument (argc, argv, ".vtk");
00152   if (vtk_file_indices.size () != 1)
00153   {
00154     print_error ("Need one output VTK file to continue.\n");
00155     return (-1);
00156   }
00157 
00158 
00159   // Command line parsing
00160   float leaf_size = default_leaf_size;
00161   parse_argument (argc, argv, "-leaf", leaf_size);
00162   print_info ("Using a leaf size of: "); print_value ("%f\n", leaf_size);
00163 
00164   float  iso_level = default_iso_level;
00165   parse_argument (argc, argv, "-iso", iso_level);
00166   print_info ("Setting an iso level of: "); print_value ("%f\n", iso_level);
00167 
00168   int use_dot = default_use_dot;
00169   parse_argument (argc, argv, "-dot", use_dot);
00170   if (use_dot)
00171     print_info ("Selected algorithm: MarchingCubesGreedyDot\n");
00172   else
00173     print_info ("Selected algorithm: MarchingCubesGreedy\n");
00174 
00175   // Load the first file
00176   sensor_msgs::PointCloud2::Ptr cloud (new sensor_msgs::PointCloud2);
00177   if (!loadCloud (argv[pcd_file_indices[0]], *cloud))
00178     return (-1);
00179 
00180   // Apply the marching cubes algorithm
00181   PolygonMesh output;
00182   compute (cloud, output, leaf_size, iso_level, use_dot);
00183 
00184   // Save into the second file
00185   saveCloud (argv[vtk_file_indices[0]], output);
00186 }
00187 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:21