fpfh_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-2012, 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  * $Id: fpfh_estimation.cpp 1032 2011-05-18 22:43:27Z marton $
00037  *
00038  */
00039 
00040 #include <sensor_msgs/PointCloud2.h>
00041 #include <pcl/io/pcd_io.h>
00042 #include <pcl/features/fpfh.h>
00043 #include <pcl/console/print.h>
00044 #include <pcl/console/parse.h>
00045 #include <pcl/console/time.h>
00046 
00047 using namespace pcl;
00048 using namespace pcl::io;
00049 using namespace pcl::console;
00050 
00051 int    default_k = 0;
00052 double default_radius = 0.0;
00053 
00054 Eigen::Vector4f    translation;
00055 Eigen::Quaternionf orientation;
00056 
00057 void
00058 printHelp (int, char **argv)
00059 {
00060   print_error ("Syntax is: %s input.pcd output.pcd <options>\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 ("%d", default_k); print_info (")\n");
00066 }
00067 
00068 bool
00069 loadCloud (const std::string &filename, sensor_msgs::PointCloud2 &cloud)
00070 {
00071   TicToc tt;
00072   print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00073 
00074   tt.tic ();
00075   if (loadPCDFile (filename, cloud, translation, orientation) < 0)
00076     return (false);
00077   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00078   print_info ("Available dimensions: "); print_value ("%s\n", getFieldsList (cloud).c_str ());
00079 
00080   // Check if the dataset has normals
00081   if (getFieldIndex (cloud, "normal_x") == -1)
00082   {
00083     print_error ("The input dataset does not contain normal information!\n");
00084     return (false);
00085   }
00086   return (true);
00087 }
00088 
00089 void
00090 compute (const sensor_msgs::PointCloud2::ConstPtr &input, sensor_msgs::PointCloud2 &output,
00091          int k, double radius)
00092 {
00093   // Convert data to PointCloud<T>
00094   PointCloud<PointNormal>::Ptr xyznormals (new PointCloud<PointNormal>);
00095   fromROSMsg (*input, *xyznormals);
00096 
00097   // Estimate
00098   TicToc tt;
00099   tt.tic ();
00100   
00101   print_highlight (stderr, "Computing ");
00102 
00103   FPFHEstimation<PointNormal, PointNormal, FPFHSignature33> ne;
00104   ne.setInputCloud (xyznormals);
00105   ne.setInputNormals (xyznormals);
00106   ne.setSearchMethod (search::KdTree<PointNormal>::Ptr (new search::KdTree<PointNormal>));
00107   ne.setKSearch (k);
00108   ne.setRadiusSearch (radius);
00109   
00110   PointCloud<FPFHSignature33> fpfhs;
00111   ne.compute (fpfhs);
00112 
00113   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", fpfhs.width * fpfhs.height); print_info (" points]\n");
00114 
00115   // Convert data back
00116   sensor_msgs::PointCloud2 output_fpfhs;
00117   toROSMsg (fpfhs, output_fpfhs);
00118   concatenateFields (*input, output_fpfhs, output);
00119 }
00120 
00121 void
00122 saveCloud (const std::string &filename, const sensor_msgs::PointCloud2 &output)
00123 {
00124   TicToc tt;
00125   tt.tic ();
00126 
00127   print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00128   
00129   io::savePCDFile (filename, output, translation, orientation, true);
00130   
00131   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00132 }
00133 
00134 /* ---[ */
00135 int
00136 main (int argc, char** argv)
00137 {
00138   print_info ("Estimate FPFH (33) descriptors using pcl::FPFHEstimation. For more information, use: %s -h\n", argv[0]);
00139   bool help = false;
00140   parse_argument (argc, argv, "-h", help);
00141   if (argc < 3 || help)
00142   {
00143     printHelp (argc, argv);
00144     return (-1);
00145   }
00146 
00147   // Parse the command line arguments for .pcd files
00148   std::vector<int> p_file_indices;
00149   p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00150   if (p_file_indices.size () != 2)
00151   {
00152     print_error ("Need one input PCD file and one output PCD file to continue.\n");
00153     return (-1);
00154   }
00155 
00156   // Command line parsing
00157   int k = default_k;
00158   double radius = default_radius;
00159   parse_argument (argc, argv, "-k", k);
00160   parse_argument (argc, argv, "-radius", radius);
00161 
00162   // Load the first file
00163   sensor_msgs::PointCloud2::Ptr cloud (new sensor_msgs::PointCloud2);
00164   if (!loadCloud (argv[p_file_indices[0]], *cloud)) 
00165     return (-1);
00166 
00167   // Perform the feature estimation
00168   sensor_msgs::PointCloud2 output;
00169   compute (cloud, output, k, radius);
00170 
00171   // Save into the second file
00172   saveCloud (argv[p_file_indices[1]], output);
00173 }
00174 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:13