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 #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
00109 typename PointCloud<PointIn>::Ptr xyz (new PointCloud<PointIn>);
00110 fromROSMsg (*input, *xyz);
00111
00112
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
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
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
00183 std::string feature_name = default_feature_name;
00184 parse_argument (argc, argv, "-feature", feature_name);
00185
00186
00187 sensor_msgs::PointCloud2::Ptr cloud (new sensor_msgs::PointCloud2);
00188 if (!loadCloud (argv[p_file_indices[0]], *cloud))
00189 return (-1);
00190
00191
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
00204 saveCloud (argv[p_file_indices[1]], output);
00205 }