Point Cloud Library (PCL)  1.13.1-dev
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/search.h> // for Search
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  {
101  filter_name_ = "StatisticalOutlierRemoval";
102  }
103 
104  /** \brief Set the number of nearest neighbors to use for mean distance estimation.
105  * \param[in] nr_k The number of points to use for mean distance estimation.
106  */
107  inline void
108  setMeanK (int nr_k)
109  {
110  mean_k_ = nr_k;
111  }
112 
113  /** \brief Get the number of nearest neighbors to use for mean distance estimation.
114  * \return The number of points to use for mean distance estimation.
115  */
116  inline int
118  {
119  return (mean_k_);
120  }
121 
122  /** \brief Set the standard deviation multiplier for the distance threshold calculation.
123  * \details The distance threshold will be equal to: mean + stddev_mult * stddev.
124  * Points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively.
125  * \param[in] stddev_mult The standard deviation multiplier.
126  */
127  inline void
128  setStddevMulThresh (double stddev_mult)
129  {
130  std_mul_ = stddev_mult;
131  }
132 
133  /** \brief Get the standard deviation multiplier for the distance threshold calculation.
134  * \details The distance threshold will be equal to: mean + stddev_mult * stddev.
135  * Points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively.
136  */
137  inline double
139  {
140  return (std_mul_);
141  }
142 
143  protected:
153 
154  /** \brief Filtered results are indexed by an indices array.
155  * \param[out] indices The resultant indices.
156  */
157  void
158  applyFilter (Indices &indices) override
159  {
160  applyFilterIndices (indices);
161  }
162 
163  /** \brief Filtered results are indexed by an indices array.
164  * \param[out] indices The resultant indices.
165  */
166  void
167  applyFilterIndices (Indices &indices);
168 
169  private:
170  /** \brief A pointer to the spatial search object. */
171  SearcherPtr searcher_;
172 
173  /** \brief The number of points to use for mean distance estimation. */
174  int mean_k_{1};
175 
176  /** \brief Standard deviations threshold (i.e., points outside of
177  * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). */
178  double std_mul_{0.0};
179  };
180 
181  /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more
182  * information check:
183  * - R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz.
184  * Towards 3D Point Cloud Based Object Maps for Household Environments
185  * Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008.
186  *
187  * \author Radu Bogdan Rusu
188  * \ingroup filters
189  */
190  template<>
192  {
195 
198 
200  using KdTreePtr = pcl::search::Search<pcl::PointXYZ>::Ptr;
201 
205 
206  public:
207  /** \brief Empty constructor. */
208  StatisticalOutlierRemoval (bool extract_removed_indices = false) :
209  FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices)
210  {
211  filter_name_ = "StatisticalOutlierRemoval";
212  }
213 
214  /** \brief Set the number of points (k) to use for mean distance estimation
215  * \param nr_k the number of points to use for mean distance estimation
216  */
217  inline void
218  setMeanK (int nr_k)
219  {
220  mean_k_ = nr_k;
221  }
222 
223  /** \brief Get the number of points to use for mean distance estimation. */
224  inline int
226  {
227  return (mean_k_);
228  }
229 
230  /** \brief Set the standard deviation multiplier threshold. All points outside the
231  * \f[ \mu \pm \sigma \cdot std\_mul \f]
232  * will be considered outliers, where \f$ \mu \f$ is the estimated mean,
233  * and \f$ \sigma \f$ is the standard deviation.
234  * \param std_mul the standard deviation multiplier threshold
235  */
236  inline void
237  setStddevMulThresh (double std_mul)
238  {
239  std_mul_ = std_mul;
240  }
241 
242  /** \brief Get the standard deviation multiplier threshold as set by the user. */
243  inline double
245  {
246  return (std_mul_);
247  }
248 
249  protected:
250  /** \brief The number of points to use for mean distance estimation. */
251  int mean_k_{2};
252 
253  /** \brief Standard deviations threshold (i.e., points outside of
254  * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers).
255  */
256  double std_mul_{0.0};
257 
258  /** \brief A pointer to the spatial search object. */
259  KdTreePtr tree_;
260 
261  void
262  applyFilter (Indices &indices) override;
263 
264  void
265  applyFilter (PCLPointCloud2 &output) override;
266 
267  /**
268  * \brief Compute the statistical values used in both applyFilter methods.
269  *
270  * This method tries to avoid duplicate code.
271  */
272  virtual void
273  generateStatistics (double& mean, double& variance, double& stddev, std::vector<float>& distances);
274  };
275 }
276 
277 #ifdef PCL_NO_PRECOMPILE
278 #include <pcl/filters/impl/statistical_outlier_removal.hpp>
279 #endif
Filter represents the base filter class.
Definition: filter.h:81
shared_ptr< Filter< PointT > > Ptr
Definition: filter.h:83
shared_ptr< const Filter< PointT > > ConstPtr
Definition: filter.h:84
std::string filter_name_
The filter name.
Definition: filter.h:158
FilterIndices represents the base class for filters that are about binary point removal.
PCLPointCloud2::Ptr PCLPointCloud2Ptr
Definition: pcl_base.h:185
PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr
Definition: pcl_base.h:186
PCL base class.
Definition: pcl_base.h:70
typename PointCloud::Ptr PointCloudPtr
Definition: pcl_base.h:73
typename PointCloud::ConstPtr PointCloudConstPtr
Definition: pcl_base.h:74
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:173
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:414
int getMeanK()
Get the number of points to use for mean distance estimation.
void applyFilter(Indices &indices) override
Abstract filter method for point cloud indices.
void applyFilter(PCLPointCloud2 &output) override
Abstract filter method for point cloud.
KdTreePtr tree_
A pointer to the spatial search object.
double getStddevMulThresh()
Get the standard deviation multiplier threshold as set by the user.
virtual void generateStatistics(double &mean, double &variance, double &stddev, std::vector< float > &distances)
Compute the statistical values used in both applyFilter methods.
StatisticalOutlierRemoval(bool extract_removed_indices=false)
Empty constructor.
void setMeanK(int nr_k)
Set the number of points (k) to use for mean distance estimation.
void setStddevMulThresh(double std_mul)
Set the standard deviation multiplier threshold.
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data.
StatisticalOutlierRemoval(bool extract_removed_indices=false)
Constructor.
typename pcl::search::Search< PointT >::Ptr SearcherPtr
double getStddevMulThresh()
Get the standard deviation multiplier for the distance threshold calculation.
int getMeanK()
Get the number of nearest neighbors to use for mean distance estimation.
void applyFilter(Indices &indices) override
Filtered results are indexed by an indices array.
void applyFilterIndices(Indices &indices)
Filtered results are indexed by an indices array.
void setStddevMulThresh(double stddev_mult)
Set the standard deviation multiplier for the distance threshold calculation.
void setMeanK(int nr_k)
Set the number of nearest neighbors to use for mean distance estimation.
shared_ptr< pcl::search::Search< PointT > > Ptr
Definition: search.h:81
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
#define PCL_EXPORTS
Definition: pcl_macros.h:323
shared_ptr< ::pcl::PCLPointCloud2 > Ptr
shared_ptr< const ::pcl::PCLPointCloud2 > ConstPtr
A point structure representing Euclidean xyz coordinates, and the RGB color.