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 <pcl/PCLPointCloud2.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/console/print.h>
00042 #include <pcl/console/parse.h>
00043 #include <pcl/console/time.h>
00044 #include <pcl/filters/radius_outlier_removal.h>
00045 #include <pcl/filters/statistical_outlier_removal.h>
00046 #include <pcl/filters/extract_indices.h>
00047
00048 using namespace pcl;
00049 using namespace pcl::io;
00050 using namespace pcl::console;
00051
00052 std::string default_method = "radius";
00053
00054 int default_mean_k = 2;
00055 double default_std_dev_mul = 0.0;
00056 int default_negative = 0;
00057
00058 double default_radius = 0.0;
00059 int default_min_pts = 0;
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 (" -method X = the outlier removal method to be used (options: radius / statistical) (default: ");
00067 print_value ("%s", default_method.c_str ()); print_info (")\n");
00068 print_info (" -radius X = (RadiusOutlierRemoval) the sphere radius used for determining the k-nearest neighbors (default: ");
00069 print_value ("%d", default_min_pts); print_info (")\n");
00070 print_info (" -min_pts X = (RadiusOutlierRemoval) the minimum number of neighbors that a point needs to have in the given search radius in order to be considered an inlier (default: ");
00071 print_value ("%d", default_min_pts); print_info (")\n");
00072 print_info (" -mean_k X = (StatisticalOutlierRemoval only) the number of points to use for mean distance estimation (default: ");
00073 print_value ("%d", default_mean_k); print_info (")\n");
00074 print_info (" -std_dev_mul X = (StatisticalOutlierRemoval only) the standard deviation multiplier threshold (default: ");
00075 print_value ("%f", default_std_dev_mul); print_info (")\n\n");
00076 print_info (" -negative X = decides whether the inliers should be returned (1), or the outliers (0). (default: ");
00077 print_value ("%d", default_negative); print_info (")\n");
00078 print_info (" -keep_organized = keep the filtered points in organized format.\n");
00079 }
00080
00081 bool
00082 loadCloud (const std::string &filename, pcl::PCLPointCloud2 &cloud,
00083 Eigen::Vector4f &translation, Eigen::Quaternionf &orientation)
00084 {
00085 TicToc tt;
00086 print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00087
00088 tt.tic ();
00089 if (loadPCDFile (filename, cloud, translation, orientation) < 0)
00090 return (false);
00091 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00092 print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00093
00094 return (true);
00095 }
00096
00097 void
00098 compute (const pcl::PCLPointCloud2::ConstPtr &input, pcl::PCLPointCloud2 &output,
00099 std::string method,
00100 int min_pts, double radius,
00101 int mean_k, double std_dev_mul, bool negative, bool keep_organized)
00102 {
00103
00104 PointCloud<PointXYZ>::Ptr xyz_cloud_pre (new pcl::PointCloud<PointXYZ> ()),
00105 xyz_cloud (new pcl::PointCloud<PointXYZ> ());
00106 fromPCLPointCloud2 (*input, *xyz_cloud_pre);
00107
00108 pcl::PointIndices::Ptr removed_indices (new PointIndices),
00109 indices (new PointIndices);
00110 std::vector<int> valid_indices;
00111 if (keep_organized)
00112 {
00113 xyz_cloud = xyz_cloud_pre;
00114 for (int i = 0; i < int (xyz_cloud->size ()); ++i)
00115 valid_indices.push_back (i);
00116 }
00117 else
00118 removeNaNFromPointCloud<PointXYZ> (*xyz_cloud_pre, *xyz_cloud, valid_indices);
00119
00120 TicToc tt;
00121 tt.tic ();
00122 PointCloud<PointXYZ>::Ptr xyz_cloud_filtered (new PointCloud<PointXYZ> ());
00123 if (method == "statistical")
00124 {
00125 StatisticalOutlierRemoval<PointXYZ> filter (true);
00126 filter.setInputCloud (xyz_cloud);
00127 filter.setMeanK (mean_k);
00128 filter.setStddevMulThresh (std_dev_mul);
00129 filter.setNegative (negative);
00130 filter.setKeepOrganized (keep_organized);
00131 PCL_INFO ("Computing filtered cloud from %zu points with mean_k %d, std_dev_mul %f, inliers %d ...", xyz_cloud->size (), filter.getMeanK (), filter.getStddevMulThresh (), filter.getNegative ());
00132 filter.filter (*xyz_cloud_filtered);
00133
00134 filter.getRemovedIndices (*removed_indices);
00135 }
00136 else if (method == "radius")
00137 {
00138 RadiusOutlierRemoval<PointXYZ> filter (true);
00139 filter.setInputCloud (xyz_cloud);
00140 filter.setRadiusSearch (radius);
00141 filter.setMinNeighborsInRadius (min_pts);
00142 filter.setNegative (negative);
00143 filter.setKeepOrganized (keep_organized);
00144 PCL_INFO ("Computing filtered cloud from %zu points with radius %f, min_pts %d ...", xyz_cloud->size (), radius, min_pts);
00145 filter.filter (*xyz_cloud_filtered);
00146
00147 filter.getRemovedIndices (*removed_indices);
00148 }
00149 else
00150 {
00151 PCL_ERROR ("%s is not a valid filter name! Quitting!\n", method.c_str ());
00152 return;
00153 }
00154
00155 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", xyz_cloud_filtered->width * xyz_cloud_filtered->height); print_info (" points, %zu indices removed]\n", removed_indices->indices.size ());
00156
00157 if (keep_organized)
00158 {
00159 pcl::PCLPointCloud2 output_filtered;
00160 toPCLPointCloud2 (*xyz_cloud_filtered, output_filtered);
00161 concatenateFields (*input, output_filtered, output);
00162 }
00163 else
00164 {
00165
00166 for (size_t i = 0; i < removed_indices->indices.size (); ++i)
00167 indices->indices.push_back (valid_indices[removed_indices->indices[i]]);
00168
00169
00170 pcl::ExtractIndices<pcl::PCLPointCloud2> ei;
00171 ei.setInputCloud (input);
00172 ei.setIndices (indices);
00173 ei.setNegative (true);
00174 ei.filter (output);
00175 }
00176 }
00177
00178 void
00179 saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &output,
00180 const Eigen::Vector4f &translation, const Eigen::Quaternionf &rotation)
00181 {
00182 TicToc tt;
00183 tt.tic ();
00184
00185 print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00186
00187 PCDWriter w;
00188 w.writeBinaryCompressed (filename, output, translation, rotation);
00189
00190 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00191 }
00192
00193
00194 int
00195 main (int argc, char** argv)
00196 {
00197 print_info ("Statistical Outlier Removal filtering of a point cloud. For more information, use: %s -h\n", argv[0]);
00198
00199 if (argc < 3)
00200 {
00201 printHelp (argc, argv);
00202 return (-1);
00203 }
00204
00205
00206 std::vector<int> p_file_indices;
00207 p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00208 if (p_file_indices.size () != 2)
00209 {
00210 print_error ("Need one input PCD file and one output PCD file to continue.\n");
00211 return (-1);
00212 }
00213
00214
00215 std::string method = default_method;
00216 int min_pts = default_min_pts;
00217 double radius = default_radius;
00218 int mean_k = default_mean_k;
00219 double std_dev_mul = default_std_dev_mul;
00220 int negative = default_negative;
00221
00222
00223 parse_argument (argc, argv, "-method", method);
00224 parse_argument (argc, argv, "-radius", radius);
00225 parse_argument (argc, argv, "-min_pts", min_pts);
00226 parse_argument (argc, argv, "-mean_k", mean_k);
00227 parse_argument (argc, argv, "-std_dev_mul", std_dev_mul);
00228 parse_argument (argc, argv, "-negative", negative);
00229 bool keep_organized = find_switch (argc, argv, "-keep_organized");
00230
00231
00232 Eigen::Vector4f translation;
00233 Eigen::Quaternionf rotation;
00234 pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
00235 if (!loadCloud (argv[p_file_indices[0]], *cloud, translation, rotation))
00236 return (-1);
00237
00238 if (keep_organized && cloud->height == 1)
00239 {
00240 print_error ("Point cloud dataset (%s) is not organized (height = %d), but -keep_organized requested!\n", argv[p_file_indices[0]], cloud->height);
00241 return (-1);
00242 }
00243
00244
00245 pcl::PCLPointCloud2 output;
00246 compute (cloud, output, method, min_pts, radius, mean_k, std_dev_mul, negative, keep_organized);
00247
00248
00249 saveCloud (argv[p_file_indices[1]], output, translation, rotation);
00250 }