extract_feature.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  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  *
00037  */
00038 
00039 #include <sensor_msgs/PointCloud2.h>
00040 #include <pcl/point_types.h>
00041 #include <pcl/io/pcd_io.h>
00042 #include <pcl/console/print.h>
00043 #include <pcl/console/parse.h>
00044 #include <pcl/console/time.h>
00045 
00046 #include <pcl/features/normal_3d.h>
00047 #include <pcl/features/fpfh.h>
00048 #include <pcl/features/pfh.h>
00049 #include <pcl/features/vfh.h>
00050 
00051 
00052 using namespace pcl;
00053 using namespace pcl::io;
00054 using namespace pcl::console;
00055 
00056 std::string default_feature_name = "FPFHEstimation";
00057 int    default_n_k = 0;
00058 double default_n_radius = 0.0;
00059 int    default_f_k = 0;
00060 double default_f_radius = 0.0;
00061 
00062 void
00063 printHelp (int, char **argv)
00064 {
00065   print_error ("Syntax is: %s input.pcd output.pcd <options>\n", argv[0]);
00066   print_info ("  where options are:\n");
00067   print_info ("                     -feature X = the feature descriptor algorithm to be used (default: ");
00068   print_value ("%s", default_feature_name.c_str ()); print_info (")\n");
00069   print_info ("                     -n_radius X = use a radius of Xm around each point to determine the neighborhood in normal estimation (default: ");
00070   print_value ("%f", default_n_radius); print_info (")\n");
00071   print_info ("                     -n_k X      = use a fixed number of X-nearest neighbors around each point in normal estimation (default: ");
00072   print_value ("%f", default_n_k); print_info (")\n");
00073   print_info ("                     -f_radius X = use a radius of Xm around each point to determine the neighborhood in feature extraction (default: ");
00074   print_value ("%f", default_f_radius); print_info (")\n");
00075   print_info ("                     -f_k X      = use a fixed number of X-nearest neighbors around each point in feature extraction(default: ");
00076   print_value ("%f", default_f_k); print_info (")\n");
00077 }
00078 
00079 bool
00080 loadCloud (const std::string &filename, sensor_msgs::PointCloud2 &cloud)
00081 {
00082   TicToc tt;
00083   print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00084 
00085   tt.tic ();
00086   if (loadPCDFile (filename, cloud) < 0)
00087     return (false);
00088   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00089   print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00090 
00091   return (true);
00092 }
00093 
00094 template <typename FeatureAlgorithm, typename PointIn, typename NormalT, typename PointOut>
00095 void
00096 computeFeatureViaNormals (const sensor_msgs::PointCloud2::ConstPtr &input, sensor_msgs::PointCloud2 &output,
00097          int argc, char** argv, bool set_search_flag = true)
00098 {
00099   int n_k = default_n_k;
00100   int f_k = default_f_k;
00101   double n_radius = default_n_radius;
00102   double f_radius = default_f_radius;
00103   parse_argument (argc, argv, "-n_k", n_k);
00104   parse_argument (argc, argv, "-n_radius", n_radius);
00105   parse_argument (argc, argv, "-f_k", f_k);
00106   parse_argument (argc, argv, "-f_radius", f_radius);
00107 
00108   // Convert data to PointCloud<PointIn>
00109   typename PointCloud<PointIn>::Ptr xyz (new PointCloud<PointIn>);
00110   fromROSMsg (*input, *xyz);
00111 
00112   // Estimate
00113   TicToc tt;
00114   tt.tic ();
00115 
00116   print_highlight (stderr, "Computing ");
00117 
00118   NormalEstimation<PointIn, NormalT> ne;
00119   ne.setInputCloud (xyz);
00120   ne.setSearchMethod (typename pcl::search::KdTree<PointIn>::Ptr (new pcl::search::KdTree<PointIn>));
00121   ne.setKSearch (n_k);
00122   ne.setRadiusSearch (n_radius);
00123 
00124   typename PointCloud<NormalT>::Ptr normals = typename PointCloud<NormalT>::Ptr (new PointCloud<NormalT>);
00125   ne.compute (*normals);
00126 
00127   FeatureAlgorithm feature_est;
00128   feature_est.setInputCloud (xyz);
00129   feature_est.setInputNormals (normals);
00130 
00131   feature_est.setSearchMethod (typename pcl::search::KdTree<PointIn>::Ptr (new pcl::search::KdTree<PointIn>));
00132 
00133   PointCloud<PointOut> output_features;
00134 
00135   if (set_search_flag) {
00136     feature_est.setKSearch (f_k);
00137     feature_est.setRadiusSearch (f_radius);
00138   }
00139 
00140   feature_est.compute (output_features);
00141 
00142   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00143 
00144   // Convert data back
00145   toROSMsg (output_features, output);
00146 }
00147 
00148 void
00149 saveCloud (const std::string &filename, const sensor_msgs::PointCloud2 &output)
00150 {
00151   TicToc tt;
00152   tt.tic ();
00153 
00154   print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00155 
00156   pcl::io::savePCDFile (filename, output);
00157 
00158   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00159 }
00160 
00161 /* ---[ */
00162 int
00163 main (int argc, char** argv)
00164 {
00165   print_info ("Extract features from a point cloud. For more information, use: %s -h\n", argv[0]);
00166 
00167   if (argc < 3)
00168   {
00169     printHelp (argc, argv);
00170     return (-1);
00171   }
00172 
00173   // Parse the command line arguments for .pcd files
00174   std::vector<int> p_file_indices;
00175   p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00176   if (p_file_indices.size () != 2)
00177   {
00178     print_error ("Need one input PCD file and one output PCD file to continue.\n");
00179     return (-1);
00180   }
00181 
00182   // Command line parsing
00183   std::string feature_name = default_feature_name;
00184   parse_argument (argc, argv, "-feature", feature_name);
00185 
00186   // Load the first file
00187   sensor_msgs::PointCloud2::Ptr cloud (new sensor_msgs::PointCloud2);
00188   if (!loadCloud (argv[p_file_indices[0]], *cloud))
00189     return (-1);
00190 
00191   // Perform the feature estimation
00192   sensor_msgs::PointCloud2 output;
00193   if (feature_name == "PFHEstimation") 
00194     computeFeatureViaNormals< PFHEstimation<PointXYZ, Normal, PFHSignature125>, PointXYZ, Normal, PFHSignature125>
00195       (cloud, output, argc, argv);
00196   else if (feature_name == "FPFHEstimation")
00197     computeFeatureViaNormals< FPFHEstimation<PointXYZ, Normal, FPFHSignature33>, PointXYZ, Normal, FPFHSignature33>
00198       (cloud, output, argc, argv);
00199   else if (feature_name == "VFHEstimation")
00200     computeFeatureViaNormals< VFHEstimation<PointXYZ, Normal, VFHSignature308>, PointXYZ, Normal, VFHSignature308>
00201     (cloud, output, argc, argv, false);
00202 
00203   // Save into the second file
00204   saveCloud (argv[p_file_indices[1]], output);
00205 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:57