Point Cloud Library (PCL)  1.11.1
statistical_outlier_removal.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2012, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the copyright holder(s) nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * $Id$
37  *
38  */
39 
40 #pragma once
41 
42 #include <pcl/filters/filter_indices.h>
43 #include <pcl/search/pcl_search.h>
44 
45 namespace pcl
46 {
47  /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data.
48  * \details The algorithm iterates through the entire input twice:
49  * During the first iteration it will compute the average distance that each point has to its nearest k neighbors.
50  * The value of k can be set using setMeanK().
51  * Next, the mean and standard deviation of all these distances are computed in order to determine a distance threshold.
52  * The distance threshold will be equal to: mean + stddev_mult * stddev.
53  * The multiplier for the standard deviation can be set using setStddevMulThresh().
54  * During the next iteration the points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively.
55  * <br>
56  * The neighbors found for each query point will be found amongst ALL points of setInputCloud(), not just those indexed by setIndices().
57  * The setIndices() method only indexes the points that will be iterated through as search query points.
58  * <br><br>
59  * For more information:
60  * - R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz.
61  * Towards 3D Point Cloud Based Object Maps for Household Environments
62  * Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008.
63  * <br><br>
64  * Usage example:
65  * \code
66  * pcl::StatisticalOutlierRemoval<PointType> sorfilter (true); // Initializing with true will allow us to extract the removed indices
67  * sorfilter.setInputCloud (cloud_in);
68  * sorfilter.setMeanK (8);
69  * sorfilter.setStddevMulThresh (1.0);
70  * sorfilter.filter (*cloud_out);
71  * // The resulting cloud_out contains all points of cloud_in that have an average distance to their 8 nearest neighbors that is below the computed threshold
72  * // Using a standard deviation multiplier of 1.0 and assuming the average distances are normally distributed there is a 84.1% chance that a point will be an inlier
73  * indices_rem = sorfilter.getRemovedIndices ();
74  * // The indices_rem array indexes all points of cloud_in that are outliers
75  * \endcode
76  * \author Radu Bogdan Rusu
77  * \ingroup filters
78  */
79  template<typename PointT>
81  {
82  protected:
84  using PointCloudPtr = typename PointCloud::Ptr;
87 
88  public:
89 
90  using Ptr = shared_ptr<StatisticalOutlierRemoval<PointT> >;
91  using ConstPtr = shared_ptr<const StatisticalOutlierRemoval<PointT> >;
92 
93 
94  /** \brief Constructor.
95  * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false).
96  */
97  StatisticalOutlierRemoval (bool extract_removed_indices = false) :
98  FilterIndices<PointT> (extract_removed_indices),
99  searcher_ (),
100  mean_k_ (1),
101  std_mul_ (0.0)
102  {
103  filter_name_ = "StatisticalOutlierRemoval";
104  }
105 
106  /** \brief Set the number of nearest neighbors to use for mean distance estimation.
107  * \param[in] nr_k The number of points to use for mean distance estimation.
108  */
109  inline void
110  setMeanK (int nr_k)
111  {
112  mean_k_ = nr_k;
113  }
114 
115  /** \brief Get the number of nearest neighbors to use for mean distance estimation.
116  * \return The number of points to use for mean distance estimation.
117  */
118  inline int
120  {
121  return (mean_k_);
122  }
123 
124  /** \brief Set the standard deviation multiplier for the distance threshold calculation.
125  * \details The distance threshold will be equal to: mean + stddev_mult * stddev.
126  * Points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively.
127  * \param[in] stddev_mult The standard deviation multiplier.
128  */
129  inline void
130  setStddevMulThresh (double stddev_mult)
131  {
132  std_mul_ = stddev_mult;
133  }
134 
135  /** \brief Get the standard deviation multiplier for the distance threshold calculation.
136  * \details The distance threshold will be equal to: mean + stddev_mult * stddev.
137  * Points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively.
138  */
139  inline double
141  {
142  return (std_mul_);
143  }
144 
145  protected:
155 
156  /** \brief Filtered results are indexed by an indices array.
157  * \param[out] indices The resultant indices.
158  */
159  void
160  applyFilter (std::vector<int> &indices) override
161  {
162  applyFilterIndices (indices);
163  }
164 
165  /** \brief Filtered results are indexed by an indices array.
166  * \param[out] indices The resultant indices.
167  */
168  void
169  applyFilterIndices (std::vector<int> &indices);
170 
171  private:
172  /** \brief A pointer to the spatial search object. */
173  SearcherPtr searcher_;
174 
175  /** \brief The number of points to use for mean distance estimation. */
176  int mean_k_;
177 
178  /** \brief Standard deviations threshold (i.e., points outside of
179  * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). */
180  double std_mul_;
181  };
182 
183  /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more
184  * information check:
185  * - R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz.
186  * Towards 3D Point Cloud Based Object Maps for Household Environments
187  * Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008.
188  *
189  * \note setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored.
190  * \author Radu Bogdan Rusu
191  * \ingroup filters
192  */
193  template<>
195  {
198 
201 
203  using KdTreePtr = pcl::search::Search<pcl::PointXYZ>::Ptr;
204 
208 
209  public:
210  /** \brief Empty constructor. */
211  StatisticalOutlierRemoval (bool extract_removed_indices = false) :
212  FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices), mean_k_ (2),
213  std_mul_ (0.0)
214  {
215  filter_name_ = "StatisticalOutlierRemoval";
216  }
217 
218  /** \brief Set the number of points (k) to use for mean distance estimation
219  * \param nr_k the number of points to use for mean distance estimation
220  */
221  inline void
222  setMeanK (int nr_k)
223  {
224  mean_k_ = nr_k;
225  }
226 
227  /** \brief Get the number of points to use for mean distance estimation. */
228  inline int
230  {
231  return (mean_k_);
232  }
233 
234  /** \brief Set the standard deviation multiplier threshold. All points outside the
235  * \f[ \mu \pm \sigma \cdot std\_mul \f]
236  * will be considered outliers, where \f$ \mu \f$ is the estimated mean,
237  * and \f$ \sigma \f$ is the standard deviation.
238  * \param std_mul the standard deviation multiplier threshold
239  */
240  inline void
241  setStddevMulThresh (double std_mul)
242  {
243  std_mul_ = std_mul;
244  }
245 
246  /** \brief Get the standard deviation multiplier threshold as set by the user. */
247  inline double
249  {
250  return (std_mul_);
251  }
252 
253  protected:
254  /** \brief The number of points to use for mean distance estimation. */
255  int mean_k_;
256 
257  /** \brief Standard deviations threshold (i.e., points outside of
258  * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers).
259  */
260  double std_mul_;
261 
262  /** \brief A pointer to the spatial search object. */
263  KdTreePtr tree_;
264 
265  void
266  applyFilter (std::vector<int> &indices) override;
267 
268  void
269  applyFilter (PCLPointCloud2 &output) override;
270 
271  /**
272  * \brief Compute the statistical values used in both applyFilter methods.
273  *
274  * This method tries to avoid duplicate code.
275  */
276  virtual void
277  generateStatistics (double& mean, double& variance, double& stddev, std::vector<float>& distances);
278  };
279 }
280 
281 #ifdef PCL_NO_PRECOMPILE
282 #include <pcl/filters/impl/statistical_outlier_removal.hpp>
283 #endif
pcl::search::Search< pcl::PointXYZ >
pcl
Definition: convolution.h:46
pcl::Filter::Ptr
shared_ptr< Filter< PointT > > Ptr
Definition: filter.h:86
pcl::PCLBase::PointCloudConstPtr
typename PointCloud::ConstPtr PointCloudConstPtr
Definition: pcl_base.h:77
pcl::PCLBase::PointCloudPtr
typename PointCloud::Ptr PointCloudPtr
Definition: pcl_base.h:76
pcl::PCLPointCloud2::Ptr
shared_ptr< ::pcl::PCLPointCloud2 > Ptr
Definition: PCLPointCloud2.h:34
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::setStddevMulThresh
void setStddevMulThresh(double std_mul)
Set the standard deviation multiplier threshold.
Definition: statistical_outlier_removal.h:241
pcl::StatisticalOutlierRemoval::setStddevMulThresh
void setStddevMulThresh(double stddev_mult)
Set the standard deviation multiplier for the distance threshold calculation.
Definition: statistical_outlier_removal.h:130
pcl::StatisticalOutlierRemoval::SearcherPtr
typename pcl::search::Search< PointT >::Ptr SearcherPtr
Definition: statistical_outlier_removal.h:86
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::getStddevMulThresh
double getStddevMulThresh()
Get the standard deviation multiplier threshold as set by the user.
Definition: statistical_outlier_removal.h:248
pcl::PCLBase
PCL base class.
Definition: pcl_base.h:73
pcl::StatisticalOutlierRemoval::getMeanK
int getMeanK()
Get the number of nearest neighbors to use for mean distance estimation.
Definition: statistical_outlier_removal.h:119
pcl::PCLBase< pcl::PCLPointCloud2 >::PCLPointCloud2ConstPtr
PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr
Definition: pcl_base.h:189
pcl::PointCloud
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: distances.h:55
pcl::StatisticalOutlierRemoval::setMeanK
void setMeanK(int nr_k)
Set the number of nearest neighbors to use for mean distance estimation.
Definition: statistical_outlier_removal.h:110
pcl::StatisticalOutlierRemoval::applyFilterIndices
void applyFilterIndices(std::vector< int > &indices)
Filtered results are indexed by an indices array.
Definition: statistical_outlier_removal.hpp:47
pcl::PointXYZRGB
A point structure representing Euclidean xyz coordinates, and the RGB color.
Definition: point_types.hpp:629
pcl::StatisticalOutlierRemoval::getStddevMulThresh
double getStddevMulThresh()
Get the standard deviation multiplier for the distance threshold calculation.
Definition: statistical_outlier_removal.h:140
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::generateStatistics
virtual void generateStatistics(double &mean, double &variance, double &stddev, std::vector< float > &distances)
Compute the statistical values used in both applyFilter methods.
pcl::PCLBase< pcl::PCLPointCloud2 >::PCLPointCloud2Ptr
PCLPointCloud2::Ptr PCLPointCloud2Ptr
Definition: pcl_base.h:188
pcl::PCLPointCloud2::ConstPtr
shared_ptr< const ::pcl::PCLPointCloud2 > ConstPtr
Definition: PCLPointCloud2.h:35
pcl::StatisticalOutlierRemoval::StatisticalOutlierRemoval
StatisticalOutlierRemoval(bool extract_removed_indices=false)
Constructor.
Definition: statistical_outlier_removal.h:97
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::applyFilter
void applyFilter(std::vector< int > &indices) override
Abstract filter method for point cloud indices.
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::std_mul_
double std_mul_
Standard deviations threshold (i.e., points outside of will be marked as outliers).
Definition: statistical_outlier_removal.h:260
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::StatisticalOutlierRemoval
StatisticalOutlierRemoval(bool extract_removed_indices=false)
Empty constructor.
Definition: statistical_outlier_removal.h:211
pcl::Filter::ConstPtr
shared_ptr< const Filter< PointT > > ConstPtr
Definition: filter.h:87
pcl::search::Search::Ptr
shared_ptr< pcl::search::Search< PointT > > Ptr
Definition: search.h:81
pcl::FilterIndices
FilterIndices represents the base class for filters that are about binary point removal.
Definition: filter_indices.h:75
pcl::Filter
Filter represents the base filter class.
Definition: filter.h:84
pcl::PCLPointCloud2
Definition: PCLPointCloud2.h:16
pcl::Filter::filter_name_
std::string filter_name_
The filter name.
Definition: filter.h:161
pcl::PointCloud::Ptr
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:429
pcl::StatisticalOutlierRemoval
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data.
Definition: statistical_outlier_removal.h:81
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::getMeanK
int getMeanK()
Get the number of points to use for mean distance estimation.
Definition: statistical_outlier_removal.h:229
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::tree_
KdTreePtr tree_
A pointer to the spatial search object.
Definition: statistical_outlier_removal.h:263
pcl::PointCloud::ConstPtr
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:430
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::mean_k_
int mean_k_
The number of points to use for mean distance estimation.
Definition: statistical_outlier_removal.h:255
pcl::StatisticalOutlierRemoval::applyFilter
void applyFilter(std::vector< int > &indices) override
Filtered results are indexed by an indices array.
Definition: statistical_outlier_removal.h:160
PCL_EXPORTS
#define PCL_EXPORTS
Definition: pcl_macros.h:328
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::applyFilter
void applyFilter(PCLPointCloud2 &output) override
Abstract filter method for point cloud.
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::setMeanK
void setMeanK(int nr_k)
Set the number of points (k) to use for mean distance estimation.
Definition: statistical_outlier_removal.h:222