statistical_outlier_removal.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, 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: statistical_outlier_removal.cpp 5026 2012-03-12 02:51:44Z rusu $
00035  *
00036  */
00037 
00038 #include <pcl/impl/instantiate.hpp>
00039 #include <pcl/point_types.h>
00040 #include <pcl/filters/statistical_outlier_removal.h>
00041 #include <pcl/filters/impl/statistical_outlier_removal.hpp>
00042 #include <pcl/ros/conversions.h>
00043 
00045 void
00046 pcl::StatisticalOutlierRemoval<sensor_msgs::PointCloud2>::applyFilter (PointCloud2 &output)
00047 {
00048   output.is_dense = true;
00049   // If fields x/y/z are not present, we cannot filter
00050   if (x_idx_ == -1 || y_idx_ == -1 || z_idx_ == -1)
00051   {
00052     PCL_ERROR ("[pcl::%s::applyFilter] Input dataset doesn't have x-y-z coordinates!\n", getClassName ().c_str ());
00053     output.width = output.height = 0;
00054     output.data.clear ();
00055     return;
00056   }
00057 
00058   if (std_mul_ == 0.0)
00059   {
00060     PCL_ERROR ("[pcl::%s::applyFilter] Standard deviation multipler not set!\n", getClassName ().c_str ());
00061     output.width = output.height = 0;
00062     output.data.clear ();
00063     return;
00064   }
00065   // Send the input dataset to the spatial locator
00066   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00067   pcl::fromROSMsg (*input_, *cloud);
00068 
00069   // Initialize the spatial locator
00070   if (!tree_)
00071   {
00072     if (cloud->isOrganized ())
00073       tree_.reset (new pcl::search::OrganizedNeighbor<pcl::PointXYZ> ());
00074     else
00075       tree_.reset (new pcl::search::KdTree<pcl::PointXYZ> (false));
00076   }
00077 
00078   tree_->setInputCloud (cloud);
00079 
00080   // Allocate enough space to hold the results
00081   std::vector<int> nn_indices (mean_k_);
00082   std::vector<float> nn_dists (mean_k_);
00083 
00084   std::vector<float> distances (indices_->size ());
00085   // Go over all the points and calculate the mean or smallest distance
00086   for (size_t cp = 0; cp < indices_->size (); ++cp)
00087   {
00088     if (!pcl_isfinite (cloud->points[(*indices_)[cp]].x) || !pcl_isfinite (cloud->points[(*indices_)[cp]].y)
00089         ||
00090         !pcl_isfinite (cloud->points[(*indices_)[cp]].z))
00091     {
00092       distances[cp] = 0;
00093       continue;
00094     }
00095 
00096     if (tree_->nearestKSearch ((*indices_)[cp], mean_k_, nn_indices, nn_dists) == 0)
00097     {
00098       distances[cp] = 0;
00099       PCL_WARN ("[pcl::%s::applyFilter] Searching for the closest %d neighbors failed.\n", getClassName ().c_str (), mean_k_);
00100       continue;
00101     }
00102 
00103     // Minimum distance (if mean_k_ == 2) or mean distance
00104     double dist_sum = 0;
00105     for (int j = 1; j < mean_k_; ++j)
00106       dist_sum += sqrt (nn_dists[j]);
00107     distances[cp] = static_cast<float> (dist_sum / (mean_k_ - 1));
00108   }
00109 
00110   // Estimate the mean and the standard deviation of the distance vector
00111   double mean, stddev;
00112   getMeanStd (distances, mean, stddev);
00113   double distance_threshold = mean + std_mul_ * stddev; // a distance that is bigger than this signals an outlier
00114 
00115   // Copy the common fields
00116   output.is_bigendian = input_->is_bigendian;
00117   output.point_step = input_->point_step;
00118   output.height = 1;
00119 
00120   output.data.resize (indices_->size () * input_->point_step); // reserve enough space
00121   removed_indices_->resize (input_->data.size ());
00122 
00123   // Build a new cloud by neglecting outliers
00124   int nr_p = 0;
00125   int nr_removed_p = 0;
00126   for (int cp = 0; cp < static_cast<int> (indices_->size ()); ++cp)
00127   {
00128     if (negative_)
00129     {
00130       if (distances[cp] <= distance_threshold)
00131       {
00132         if (extract_removed_indices_)
00133         {
00134           (*removed_indices_)[nr_removed_p] = cp;
00135           nr_removed_p++;
00136         }
00137         continue;
00138       }
00139     }
00140     else
00141     {
00142       if (distances[cp] > distance_threshold)
00143       {
00144         if (extract_removed_indices_)
00145         {
00146           (*removed_indices_)[nr_removed_p] = cp;
00147           nr_removed_p++;
00148         }
00149         continue;
00150       }
00151     }
00152 
00153     memcpy (&output.data[nr_p * output.point_step], &input_->data[(*indices_)[cp] * output.point_step],
00154             output.point_step);
00155     nr_p++;
00156   }
00157   output.width = nr_p;
00158   output.data.resize (output.width * output.point_step);
00159   output.row_step = output.point_step * output.width;
00160 
00161   removed_indices_->resize (nr_removed_p);
00162 }
00163 // Instantiations of specific point types
00164 PCL_INSTANTIATE(StatisticalOutlierRemoval, PCL_XYZ_POINT_TYPES)
00165 


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