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 #include <pcl/PCLPointCloud2.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, pcl::PCLPointCloud2 &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   
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 pcl::PCLPointCloud2::ConstPtr &input, pcl::PCLPointCloud2 &output,
00091          int k, double radius)
00092 {
00093   
00094   PointCloud<PointNormal>::Ptr xyznormals (new PointCloud<PointNormal>);
00095   fromPCLPointCloud2 (*input, *xyznormals);
00096 
00097   
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   
00116   pcl::PCLPointCloud2 output_fpfhs;
00117   toPCLPointCloud2 (fpfhs, output_fpfhs);
00118   concatenateFields (*input, output_fpfhs, output);
00119 }
00120 
00121 void
00122 saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &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   
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   
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   
00163   pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
00164   if (!loadCloud (argv[p_file_indices[0]], *cloud)) 
00165     return (-1);
00166 
00167   
00168   pcl::PCLPointCloud2 output;
00169   compute (cloud, output, k, radius);
00170 
00171   
00172   saveCloud (argv[p_file_indices[1]], output);
00173 }
00174