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 #include <sensor_msgs/PointCloud2.h>
00039 #include <pcl/io/pcd_io.h>
00040 #include <pcl/features/spin_image.h>
00041 #include <pcl/console/print.h>
00042 #include <pcl/console/parse.h>
00043 #include <pcl/console/time.h>
00044
00045 using namespace pcl;
00046 using namespace pcl::io;
00047 using namespace pcl::console;
00048
00049 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::Histogram<153>,
00050 (float[153], histogram, spinimage)
00051 )
00052
00053 int default_image_width = 8;
00054 double default_support_angle = 0.5;
00055 int default_min_neigh = 1;
00056 double default_radius = 0.0;
00057
00058 Eigen::Vector4f translation;
00059 Eigen::Quaternionf orientation;
00060
00061 void
00062 printHelp (int, char **argv)
00063 {
00064 print_error ("Syntax is: %s input.pcd output.pcd <options>\n", argv[0]);
00065 print_info (" where options are:\n");
00066 print_info (" -radius X = use a radius of Xm around each point to determine the neighborhood (default: ");
00067 print_value ("%f", default_radius); print_info (")\n");
00068 print_info (" -width X = resolution (width) of a spin-image (default: ");
00069 print_value ("%d", default_image_width); print_info (")\n");
00070 print_info (" -suppangle X = min cosine of support angle for filtering points by normals (default: ");
00071 print_value ("%f", default_support_angle); print_info (")\n");
00072 print_info (" -neigh X = min number of neighbours to compute a spin-image (default: ");
00073 print_value ("%d", default_min_neigh); print_info (")\n");
00074
00075 print_info (" -radial = toggles radial structure of a spin-image (default: false)\n");
00076 print_info (" -angular = toggles angular domain of a spin-image (default: false)\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, translation, orientation) < 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", getFieldsList (cloud).c_str ());
00090
00091
00092 if (getFieldIndex (cloud, "normal_x") == -1)
00093 {
00094 print_error ("The input dataset does not contain normal information!\n");
00095 return (false);
00096 }
00097 return (true);
00098 }
00099
00100
00101
00102 void
00103 saveCloud (const std::string &filename, const sensor_msgs::PointCloud2 &output)
00104 {
00105 TicToc tt;
00106 tt.tic ();
00107
00108 print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00109
00110 io::savePCDFile (filename, output, translation, orientation, false);
00111
00112 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00113 }
00114
00115
00116 int
00117 main (int argc, char** argv)
00118 {
00119 print_info ("Estimate spin-image descriptors using pcl::SpinEstimation. For more information, use: %s -h\n", argv[0]);
00120 bool help = false;
00121 parse_argument (argc, argv, "-h", help);
00122 if (argc < 3 || help)
00123 {
00124 printHelp (argc, argv);
00125 return (-1);
00126 }
00127
00128
00129 std::vector<int> p_file_indices;
00130 p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00131 if (p_file_indices.size () != 2)
00132 {
00133 print_error ("Need one input PCD file and one output PCD file to continue.\n");
00134 return (-1);
00135 }
00136
00137
00138 double radius = default_radius;
00139 parse_argument (argc, argv, "-radius", radius);
00140 int image_width = default_image_width;
00141 parse_argument (argc, argv, "-width", image_width);
00142 double support_angle = default_support_angle;
00143 parse_argument (argc, argv, "-suppangle", support_angle);
00144 int min_neigh = default_min_neigh;
00145 parse_argument (argc, argv, "-neigh", min_neigh);
00146
00147
00148 sensor_msgs::PointCloud2::Ptr cloud (new sensor_msgs::PointCloud2);
00149 if (!loadCloud (argv[p_file_indices[0]], *cloud))
00150 return (-1);
00151
00152
00153 sensor_msgs::PointCloud2 output;
00154
00155
00156 PointCloud<PointNormal>::Ptr xyznormals (new PointCloud<PointNormal>);
00157 fromROSMsg (*cloud, *xyznormals);
00158
00159
00160 TicToc tt;
00161 tt.tic ();
00162
00163 print_highlight (stderr, "Computing ");
00164
00165 typedef Histogram<153> SpinImage;
00166 SpinImageEstimation<PointNormal, PointNormal, SpinImage> spin_est (image_width, support_angle, min_neigh);
00167
00168 spin_est.setInputCloud (xyznormals);
00169 spin_est.setInputNormals (xyznormals);
00170 spin_est.setSearchMethod (search::KdTree<PointNormal>::Ptr (new search::KdTree<PointNormal>));
00171 spin_est.setRadiusSearch (radius);
00172
00173 if (find_argument(argc, argv, "-radial") > 0)
00174 spin_est.setRadialStructure();
00175
00176 if (find_argument(argc, argv, "-angular") > 0)
00177 spin_est.setAngularDomain();
00178
00179 PointCloud<SpinImage> descriptors;
00180 spin_est.compute (descriptors);
00181
00182 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", descriptors.width * descriptors.height); print_info (" points]\n");
00183
00184
00185 sensor_msgs::PointCloud2 output_descr;
00186 toROSMsg (descriptors, output_descr);
00187 concatenateFields (*cloud, output_descr, output);
00188
00189
00190
00191 saveCloud (argv[p_file_indices[1]], output);
00192 }
00193