outlier_removal.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id$
00035  *
00036  */
00037 
00038 #include <sensor_msgs/PointCloud2.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 
00047 using namespace pcl;
00048 using namespace pcl::io;
00049 using namespace pcl::console;
00050 
00051 std::string default_method = "radius";
00052 
00053 int default_mean_k = 2;
00054 double default_std_dev_mul = 0.0;
00055 int default_negative = 1;
00056 
00057 double default_radius = 0.0;
00058 int default_min_pts = 0;
00059 
00060 void
00061 printHelp (int, char **argv)
00062 {
00063   print_error ("Syntax is: %s input.pcd output.pcd <options>\n", argv[0]);
00064   print_info ("  where options are:\n");
00065   print_info ("                     -method X = the outlier removal method to be used (options: radius / statistical) (default: ");
00066   print_value ("%s", default_method.c_str ()); print_info (")\n");
00067   print_info ("                     -radius X = (RadiusOutlierRemoval) the sphere radius used for determining the k-nearest neighbors (default: ");
00068   print_value ("%d", default_min_pts); print_info (")\n");
00069   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: ");
00070   print_value ("%d", default_min_pts); print_info (")\n");
00071   print_info ("                     -mean_k X = (StatisticalOutlierRemoval only) the number of points to use for mean distance estimation (default: ");
00072   print_value ("%d", default_mean_k); print_info (")\n");
00073   print_info ("                     -std_dev_mul X = (StatisticalOutlierRemoval only) the standard deviation multiplier threshold (default: ");
00074   print_value ("%f", default_std_dev_mul); print_info (")\n");
00075   print_info ("                     -inliers X = (StatisticalOutlierRemoval only) decides whether the inliers should be returned (1), or the outliers (0). (default: ");
00076   print_value ("%d", default_negative); 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 void
00095 compute (const sensor_msgs::PointCloud2::ConstPtr &input, sensor_msgs::PointCloud2 &output,
00096          std::string method,
00097          int min_pts, double radius,
00098          int mean_k, double std_dev_mul, bool negative)
00099 {
00100 
00101   PointCloud<PointXYZ>::Ptr xyz_cloud_pre (new pcl::PointCloud<PointXYZ> ()),
00102       xyz_cloud (new pcl::PointCloud<PointXYZ> ());
00103   fromROSMsg (*input, *xyz_cloud_pre);
00104   
00105   std::vector<int> index_vector;
00106   removeNaNFromPointCloud<PointXYZ> (*xyz_cloud_pre, *xyz_cloud, index_vector);
00107 
00108       
00109   TicToc tt;
00110   tt.tic ();
00111   PointCloud<PointXYZ>::Ptr xyz_cloud_filtered (new PointCloud<PointXYZ> ());
00112   if (method == "statistical")
00113   {
00114     StatisticalOutlierRemoval<PointXYZ> filter;
00115     filter.setInputCloud (xyz_cloud);
00116     filter.setMeanK (mean_k);
00117     filter.setStddevMulThresh (std_dev_mul);
00118     filter.setNegative (negative);
00119     PCL_INFO ("Computing filtered cloud with mean_k %d, std_dev_mul %f, inliers %d\n", filter.getMeanK (), filter.getStddevMulThresh (), filter.getNegative ());
00120     filter.filter (*xyz_cloud_filtered);
00121   }
00122   else if (method == "radius")
00123   {
00124     RadiusOutlierRemoval<PointXYZ> filter;
00125     filter.setInputCloud (xyz_cloud);
00126     filter.setRadiusSearch (radius);
00127     filter.setMinNeighborsInRadius (min_pts);
00128     PCL_INFO ("Computing filtered cloud with radius %f, min_pts %d\n", radius, min_pts);
00129     filter.filter (*xyz_cloud_filtered);
00130   }
00131   else
00132   {
00133     PCL_ERROR ("%s is not a valid filter name! Quitting!\n", method.c_str ());
00134     return;
00135   }
00136     
00137   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]\n");
00138 
00139   toROSMsg (*xyz_cloud_filtered, output);
00140 }
00141 
00142 void
00143 saveCloud (const std::string &filename, const sensor_msgs::PointCloud2 &output)
00144 {
00145   TicToc tt;
00146   tt.tic ();
00147 
00148   print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00149 
00150   pcl::io::savePCDFile (filename, output,  Eigen::Vector4f::Zero (),
00151                         Eigen::Quaternionf::Identity (), true);
00152 
00153   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00154 }
00155 
00156 /* ---[ */
00157 int
00158 main (int argc, char** argv)
00159 {
00160   print_info ("Statistical Outlier Removal filtering of a point cloud. For more information, use: %s -h\n", argv[0]);
00161 
00162   if (argc < 3)
00163   {
00164     printHelp (argc, argv);
00165     return (-1);
00166   }
00167 
00168   // Parse the command line arguments for .pcd files
00169   std::vector<int> p_file_indices;
00170   p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00171   if (p_file_indices.size () != 2)
00172   {
00173     print_error ("Need one input PCD file and one output PCD file to continue.\n");
00174     return (-1);
00175   }
00176 
00177   // Command line parsing
00178   std::string method = default_method;
00179   int min_pts = default_min_pts;
00180   double radius = default_radius;
00181   int mean_k = default_mean_k;
00182   double std_dev_mul = default_std_dev_mul;
00183   int negative = default_negative;
00184   
00185 
00186   parse_argument (argc, argv, "-method", method);
00187   parse_argument (argc, argv, "-radius", radius);
00188   parse_argument (argc, argv, "-min_pts", min_pts);
00189   parse_argument (argc, argv, "-mean_k", mean_k);
00190   parse_argument (argc, argv, "-std_dev_mul", std_dev_mul);
00191   parse_argument (argc, argv, "-inliers", negative);
00192   
00193   
00194 
00195   // Load the first file
00196   sensor_msgs::PointCloud2::Ptr cloud (new sensor_msgs::PointCloud2);
00197   if (!loadCloud (argv[p_file_indices[0]], *cloud))
00198     return (-1);
00199 
00200   // Do the smoothing
00201   sensor_msgs::PointCloud2 output;
00202   compute (cloud, output, method, min_pts, radius, mean_k, std_dev_mul, negative);
00203 
00204   // Save into the second file
00205   saveCloud (argv[p_file_indices[1]], output);
00206 }


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