statistical_outlier_removal.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  *
00039  */
00040 
00041 #include <pcl/filters/impl/statistical_outlier_removal.hpp>
00042 #include <pcl/conversions.h>
00043 
00045 void
00046 pcl::StatisticalOutlierRemoval<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &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::fromPCLPointCloud2 (*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   int valid_distances = 0;
00086   // Go over all the points and calculate the mean or smallest distance
00087   for (size_t cp = 0; cp < indices_->size (); ++cp)
00088   {
00089     if (!pcl_isfinite (cloud->points[(*indices_)[cp]].x) || 
00090         !pcl_isfinite (cloud->points[(*indices_)[cp]].y) ||
00091         !pcl_isfinite (cloud->points[(*indices_)[cp]].z))
00092     {
00093       distances[cp] = 0;
00094       continue;
00095     }
00096 
00097     if (tree_->nearestKSearch ((*indices_)[cp], mean_k_, nn_indices, nn_dists) == 0)
00098     {
00099       distances[cp] = 0;
00100       PCL_WARN ("[pcl::%s::applyFilter] Searching for the closest %d neighbors failed.\n", getClassName ().c_str (), mean_k_);
00101       continue;
00102     }
00103 
00104     // Minimum distance (if mean_k_ == 2) or mean distance
00105     double dist_sum = 0;
00106     for (int j = 1; j < mean_k_; ++j)
00107       dist_sum += sqrt (nn_dists[j]);
00108     distances[cp] = static_cast<float> (dist_sum / (mean_k_ - 1));
00109     valid_distances++;
00110   }
00111 
00112   // Estimate the mean and the standard deviation of the distance vector
00113   double sum = 0, sq_sum = 0;
00114   for (size_t i = 0; i < distances.size (); ++i)
00115   {
00116     sum += distances[i];
00117     sq_sum += distances[i] * distances[i];
00118   }
00119   double mean = sum / static_cast<double>(valid_distances);
00120   double variance = (sq_sum - sum * sum / static_cast<double>(valid_distances)) / (static_cast<double>(valid_distances) - 1);
00121   double stddev = sqrt (variance);
00122   //getMeanStd (distances, mean, stddev);
00123 
00124   double distance_threshold = mean + std_mul_ * stddev; // a distance that is bigger than this signals an outlier
00125 
00126   // Copy the common fields
00127   output.is_bigendian = input_->is_bigendian;
00128   output.point_step = input_->point_step;
00129   output.height = 1;
00130 
00131   output.data.resize (indices_->size () * input_->point_step); // reserve enough space
00132   removed_indices_->resize (input_->data.size ());
00133 
00134   // Build a new cloud by neglecting outliers
00135   int nr_p = 0;
00136   int nr_removed_p = 0;
00137   for (int cp = 0; cp < static_cast<int> (indices_->size ()); ++cp)
00138   {
00139     if (negative_)
00140     {
00141       if (distances[cp] <= distance_threshold)
00142       {
00143         if (extract_removed_indices_)
00144         {
00145           (*removed_indices_)[nr_removed_p] = cp;
00146           nr_removed_p++;
00147         }
00148         continue;
00149       }
00150     }
00151     else
00152     {
00153       if (distances[cp] > distance_threshold)
00154       {
00155         if (extract_removed_indices_)
00156         {
00157           (*removed_indices_)[nr_removed_p] = cp;
00158           nr_removed_p++;
00159         }
00160         continue;
00161       }
00162     }
00163 
00164     memcpy (&output.data[nr_p * output.point_step], &input_->data[(*indices_)[cp] * output.point_step],
00165             output.point_step);
00166     nr_p++;
00167   }
00168   output.width = nr_p;
00169   output.data.resize (output.width * output.point_step);
00170   output.row_step = output.point_step * output.width;
00171 
00172   removed_indices_->resize (nr_removed_p);
00173 }
00174 
00175 #ifndef PCL_NO_PRECOMPILE
00176 #include <pcl/impl/instantiate.hpp>
00177 #include <pcl/point_types.h>
00178 
00179 // Instantiations of specific point types
00180 PCL_INSTANTIATE(StatisticalOutlierRemoval, PCL_XYZ_POINT_TYPES)
00181 
00182 #endif    // PCL_NO_PRECOMPILE
00183 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:33:48