test_feature_estimation.cpp
Go to the documentation of this file.
00001 #include "feature_estimation.h"
00002 
00003 #include <vector>
00004 #include <string>
00005 #include <pcl/console/parse.h>
00006 #include <pcl/io/pcd_io.h>
00007 #include <pcl/visualization/pcl_visualizer.h>
00008 #include <pcl/visualization/histogram_visualizer.h>
00009 
00010 int 
00011 main (int argc, char ** argv)
00012 {
00013   if (argc < 2) 
00014   {
00015     pcl::console::print_info ("Syntax is: %s input.pcd <options>\n", argv[0]);
00016     pcl::console::print_info ("  where options are:\n");
00017     pcl::console::print_info ("    -n radius  ...................................... Estimate surface normals\n");
00018     pcl::console::print_info ("    -k min_scale,nr_octaves,nr_scales,min_contrast... Detect keypoints\n");
00019     pcl::console::print_info ("    -l radius ....................................... Compute local descriptors\n");
00020     pcl::console::print_info ("    -s output_name (without .pcd extension).......... Save outputs\n");
00021     pcl::console::print_info ("Note: \n");
00022     pcl::console::print_info ("  Each of the first four options depends on the options above it.\n");
00023     pcl::console::print_info ("  Saving (-s) will output individual files for each option used (-n,-k,-f,-g).\n");
00024     return (1);
00025   }
00026   
00027 
00028   // Load the input file
00029   PointCloudPtr cloud (new PointCloud);
00030   pcl::io::loadPCDFile (argv[1], *cloud);
00031   pcl::console::print_info ("Loaded %s (%zu points)\n", argv[1], cloud->size ());
00032   
00033   // Estimate surface normals
00034   SurfaceNormalsPtr normals;
00035   double surface_radius;
00036   bool estimate_surface_normals = pcl::console::parse_argument (argc, argv, "-n", surface_radius) > 0;
00037   
00038   if (estimate_surface_normals)
00039   {  
00040     normals = estimateSurfaceNormals (cloud, surface_radius);
00041     pcl::console::print_info ("Estimated surface normals\n");
00042   }
00043   
00044   // Detect keypoints
00045   PointCloudPtr keypoints;
00046   std::string params_string;
00047   bool detect_keypoints = pcl::console::parse_argument (argc, argv, "-k", params_string) > 0;
00048   if (detect_keypoints)
00049   {
00050     assert (normals);
00051     std::vector<std::string> tokens;
00052     boost::split (tokens, params_string, boost::is_any_of (","), boost::token_compress_on);
00053     assert (tokens.size () == 4);    
00054     float min_scale = atof(tokens[0].c_str ());
00055     int nr_octaves = atoi(tokens[1].c_str ());
00056     int nr_scales = atoi(tokens[2].c_str ());
00057     float min_contrast = atof(tokens[3].c_str ());
00058     keypoints = detectKeypoints (cloud, normals, min_scale, nr_octaves, nr_scales, min_contrast);
00059     pcl::console::print_info ("Detected %zu keypoints\n", keypoints->size ());
00060   }
00061   
00062   // Compute local descriptors
00063   LocalDescriptorsPtr local_descriptors;
00064   double feature_radius;
00065   bool compute_local_descriptors = pcl::console::parse_argument (argc, argv, "-l", feature_radius) > 0;
00066   if (compute_local_descriptors)
00067   {
00068     assert (normals && keypoints);
00069     local_descriptors = computeLocalDescriptors (cloud, normals, keypoints, feature_radius);
00070     pcl::console::print_info ("Computed local descriptors\n");
00071   }
00072 
00073   // Compute global descriptor
00074   GlobalDescriptorsPtr global_descriptor;
00075   if (normals)
00076   {
00077     global_descriptor = computeGlobalDescriptor (cloud, normals);
00078     pcl::console::print_info ("Computed global descriptor\n");
00079   }
00080 
00081   // Save output
00082   std::string base_filename, output_filename;
00083   bool save_cloud = pcl::console::parse_argument (argc, argv, "-s", base_filename) > 0;
00084   if (save_cloud)
00085   {
00086     if (normals)
00087     {
00088       output_filename = base_filename;
00089       output_filename.append ("_normals.pcd");
00090       pcl::io::savePCDFile (output_filename, *normals);
00091       pcl::console::print_info ("Saved surface normals as %s\n", output_filename.c_str ());
00092     }
00093     if (keypoints)
00094     {
00095       output_filename = base_filename;
00096       output_filename.append ("_keypoints.pcd");
00097       pcl::io::savePCDFile (output_filename, *keypoints);
00098       pcl::console::print_info ("Saved keypoints as %s\n", output_filename.c_str ());
00099     }
00100     if (local_descriptors)
00101     {
00102       output_filename = base_filename;
00103       output_filename.append ("_localdesc.pcd");
00104       pcl::io::savePCDFile (output_filename, *local_descriptors);
00105       pcl::console::print_info ("Saved local descriptors as %s\n", output_filename.c_str ());
00106     }
00107     if (global_descriptor)
00108     {
00109       output_filename = base_filename;
00110       output_filename.append ("_globaldesc.pcd");
00111       pcl::io::savePCDFile (output_filename, *global_descriptor);
00112       pcl::console::print_info ("Saved global descriptor as %s\n", output_filename.c_str ());
00113     }
00114   }
00115   // Or visualize the result
00116   else
00117   {
00118     pcl::console::print_info ("Starting visualizer... Close window to exit\n");
00119     pcl::visualization::PCLVisualizer vis;
00120     pcl::visualization::PCLHistogramVisualizer hist_vis;
00121     vis.addPointCloud (cloud);
00122     if (normals)
00123     {
00124       vis.addPointCloudNormals<PointT,NormalT> (cloud, normals, 4, 0.02, "normals");
00125     }
00126     if (keypoints)
00127     {
00128       pcl::visualization::PointCloudColorHandlerCustom<PointT> red (keypoints, 255, 0, 0);
00129       vis.addPointCloud (keypoints, red, "keypoints");
00130       vis.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "keypoints");
00131     }
00132     if (global_descriptor)
00133     {
00134       hist_vis.addFeatureHistogram (*global_descriptor, 308, "Global descriptor");
00135     }
00136     vis.resetCamera ();
00137     vis.spin ();
00138   }
00139 
00140   return (0);
00141 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:18:16