normal_estimation.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *  
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  *
00039  */
00040 
00041 #include <pcl/PCLPointCloud2.h>
00042 #include <pcl/io/pcd_io.h>
00043 #include <pcl/features/normal_3d.h>
00044 #include <pcl/features/integral_image_normal.h>
00045 #include <pcl/console/print.h>
00046 #include <pcl/console/parse.h>
00047 #include <pcl/console/time.h>
00048 
00049 using namespace std;
00050 using namespace pcl;
00051 using namespace pcl::io;
00052 using namespace pcl::console;
00053 
00054 int    default_k = 0;
00055 double default_radius = 0.0;
00056 
00057 void
00058 printHelp (int, char **argv)
00059 {
00060   print_error ("Syntax is: %s input.pcd output.pcd <options> [optional_arguments]\n", argv[0]);
00061   print_info ("  where options are:\n");
00062   print_info ("                     -radius X = use a radius of Xm around each point to determine the neighborhood (default: "); 
00063   print_value ("%f", default_radius); print_info (")\n");
00064   print_info ("                     -k X      = use a fixed number of X-nearest neighbors around each point (default: "); 
00065   print_value ("%f", default_k); print_info (")\n");
00066   print_info (" For organized datasets, an IntegralImageNormalEstimation approach will be used, with the RADIUS given value as SMOOTHING SIZE.\n");
00067   print_info ("\nOptional arguments are:\n");
00068   print_info ("                     -input_dir X  = batch process all PCD files found in input_dir\n");
00069   print_info ("                     -output_dir X = save the processed files from input_dir in this directory\n");
00070 }
00071 
00072 bool
00073 loadCloud (const string &filename, pcl::PCLPointCloud2 &cloud,
00074            Eigen::Vector4f &translation, Eigen::Quaternionf &orientation)
00075 {
00076   if (loadPCDFile (filename, cloud, translation, orientation) < 0)
00077     return (false);
00078 
00079   return (true);
00080 }
00081 
00082 void
00083 compute (const pcl::PCLPointCloud2::ConstPtr &input, pcl::PCLPointCloud2 &output,
00084          int k, double radius)
00085 {
00086   // Convert data to PointCloud<T>
00087   PointCloud<PointXYZ>::Ptr xyz (new PointCloud<PointXYZ>);
00088   fromPCLPointCloud2 (*input, *xyz);
00089 
00090   TicToc tt;
00091   tt.tic ();
00092  
00093   PointCloud<Normal> normals;
00094 
00095   // Try our luck with organized integral image based normal estimation
00096   if (xyz->isOrganized ())
00097   {
00098     IntegralImageNormalEstimation<PointXYZ, Normal> ne;
00099     ne.setInputCloud (xyz);
00100     ne.setNormalEstimationMethod (IntegralImageNormalEstimation<PointXYZ, Normal>::COVARIANCE_MATRIX);
00101     ne.setNormalSmoothingSize (float (radius));
00102     ne.setDepthDependentSmoothing (true);
00103     ne.compute (normals);
00104   }
00105   else
00106   {
00107     NormalEstimation<PointXYZ, Normal> ne;
00108     ne.setInputCloud (xyz);
00109     ne.setSearchMethod (search::KdTree<PointXYZ>::Ptr (new search::KdTree<PointXYZ>));
00110     ne.setKSearch (k);
00111     ne.setRadiusSearch (radius);
00112     ne.compute (normals);
00113   }
00114 
00115   print_highlight ("Computed normals in "); print_value ("%g", tt.toc ()); print_info (" ms for "); print_value ("%d", normals.width * normals.height); print_info (" points.\n");
00116 
00117   // Convert data back
00118   pcl::PCLPointCloud2 output_normals;
00119   toPCLPointCloud2 (normals, output_normals);
00120   concatenateFields (*input, output_normals, output);
00121 }
00122 
00123 void
00124 saveCloud (const string &filename, const pcl::PCLPointCloud2 &output,
00125            const Eigen::Vector4f &translation, const Eigen::Quaternionf &orientation)
00126 {
00127   PCDWriter w;
00128   w.writeBinaryCompressed (filename, output, translation, orientation);
00129 }
00130 
00131 int
00132 batchProcess (const vector<string> &pcd_files, string &output_dir, int k, double radius)
00133 {
00134 #if _OPENMP
00135 #pragma omp parallel for
00136 #endif
00137   for (int i = 0; i < int (pcd_files.size ()); ++i)
00138   {
00139     // Load the first file
00140     Eigen::Vector4f translation;
00141     Eigen::Quaternionf rotation;
00142     pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
00143     if (!loadCloud (pcd_files[i], *cloud, translation, rotation)) 
00144       continue;
00145 
00146     // Perform the feature estimation
00147     pcl::PCLPointCloud2 output;
00148     compute (cloud, output, k, radius);
00149 
00150     // Prepare output file name
00151     string filename = pcd_files[i];
00152     boost::trim (filename);
00153     vector<string> st;
00154     boost::split (st, filename, boost::is_any_of ("/\\"), boost::token_compress_on);
00155     
00156     // Save into the second file
00157     stringstream ss;
00158     ss << output_dir << "/" << st.at (st.size () - 1);
00159     saveCloud (ss.str (), output, translation, rotation);
00160   }
00161   return (0);
00162 }
00163 
00164 /* ---[ */
00165 int
00166 main (int argc, char** argv)
00167 {
00168   print_info ("Estimate surface normals using NormalEstimation. For more information, use: %s -h\n", argv[0]);
00169 
00170   if (argc < 3)
00171   {
00172     printHelp (argc, argv);
00173     return (-1);
00174   }
00175 
00176   bool batch_mode = false;
00177 
00178   // Command line parsing
00179   int k = default_k;
00180   double radius = default_radius;
00181   parse_argument (argc, argv, "-k", k);
00182   parse_argument (argc, argv, "-radius", radius);
00183   string input_dir, output_dir;
00184   if (parse_argument (argc, argv, "-input_dir", input_dir) != -1)
00185   {
00186     PCL_INFO ("Input directory given as %s. Batch process mode on.\n", input_dir.c_str ());
00187     if (parse_argument (argc, argv, "-output_dir", output_dir) == -1)
00188     {
00189       PCL_ERROR ("Need an output directory! Please use -output_dir to continue.\n");
00190       return (-1);
00191     }
00192 
00193     // Both input dir and output dir given, switch into batch processing mode
00194     batch_mode = true;
00195   }
00196 
00197   if (!batch_mode)
00198   {
00199     // Parse the command line arguments for .pcd files
00200     vector<int> p_file_indices;
00201     p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00202     if (p_file_indices.size () != 2)
00203     {
00204       print_error ("Need one input PCD file and one output PCD file to continue.\n");
00205       return (-1);
00206     }
00207 
00208     print_info ("Estimating normals with a radius/k/smoothing size of: "); 
00209     print_value ("%d / %f / %f\n", k, radius, radius); 
00210 
00211     // Load the first file
00212     Eigen::Vector4f translation;
00213     Eigen::Quaternionf rotation;
00214     pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
00215     if (!loadCloud (argv[p_file_indices[0]], *cloud, translation, rotation)) 
00216       return (-1);
00217 
00218     // Perform the feature estimation
00219     pcl::PCLPointCloud2 output;
00220     compute (cloud, output, k, radius);
00221 
00222     // Save into the second file
00223     saveCloud (argv[p_file_indices[1]], output, translation, rotation);
00224   }
00225   else
00226   {
00227     if (input_dir != "" && boost::filesystem::exists (input_dir))
00228     {
00229       vector<string> pcd_files;
00230       boost::filesystem::directory_iterator end_itr;
00231       for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
00232       {
00233         // Only add PCD files
00234         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
00235         {
00236           pcd_files.push_back (itr->path ().string ());
00237           PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ());
00238         }
00239       }
00240       batchProcess (pcd_files, output_dir, k, radius);
00241     }
00242     else
00243     {
00244       PCL_ERROR ("Batch processing mode enabled, but invalid input directory (%s) given!\n", input_dir.c_str ());
00245       return (-1);
00246     }
00247   }
00248 }
00249 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:53