Point Cloud Library (PCL)  1.7.2
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 #ifndef PCL_FILTERS_STATISTICAL_OUTLIER_REMOVAL_H_
41 #define PCL_FILTERS_STATISTICAL_OUTLIER_REMOVAL_H_
42 
43 #include <pcl/filters/filter_indices.h>
44 #include <pcl/search/pcl_search.h>
45 
46 namespace pcl
47 {
48  /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data.
49  * \details The algorithm iterates through the entire input twice:
50  * During the first iteration it will compute the average distance that each point has to its nearest k neighbors.
51  * The value of k can be set using setMeanK().
52  * Next, the mean and standard deviation of all these distances are computed in order to determine a distance threshold.
53  * The distance threshold will be equal to: mean + stddev_mult * stddev.
54  * The multiplier for the standard deviation can be set using setStddevMulThresh().
55  * 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.
56  * <br>
57  * The neighbors found for each query point will be found amongst ALL points of setInputCloud(), not just those indexed by setIndices().
58  * The setIndices() method only indexes the points that will be iterated through as search query points.
59  * <br><br>
60  * For more information:
61  * - R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz.
62  * Towards 3D Point Cloud Based Object Maps for Household Environments
63  * Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008.
64  * <br><br>
65  * Usage example:
66  * \code
67  * pcl::StatisticalOutlierRemoval<PointType> sorfilter (true); // Initializing with true will allow us to extract the removed indices
68  * sorfilter.setInputCloud (cloud_in);
69  * sorfilter.setMeanK (8);
70  * sorfilter.setStddevMulThresh (1.0);
71  * sorfilter.filter (*cloud_out);
72  * // 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
73  * // 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
74  * indices_rem = sorfilter.getRemovedIndices ();
75  * // The indices_rem array indexes all points of cloud_in that are outliers
76  * \endcode
77  * \author Radu Bogdan Rusu
78  * \ingroup filters
79  */
80  template<typename PointT>
82  {
83  protected:
85  typedef typename PointCloud::Ptr PointCloudPtr;
88 
89  public:
90 
91  typedef boost::shared_ptr< StatisticalOutlierRemoval<PointT> > Ptr;
92  typedef boost::shared_ptr< const StatisticalOutlierRemoval<PointT> > ConstPtr;
93 
94 
95  /** \brief Constructor.
96  * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false).
97  */
98  StatisticalOutlierRemoval (bool extract_removed_indices = false) :
99  FilterIndices<PointT>::FilterIndices (extract_removed_indices),
100  searcher_ (),
101  mean_k_ (1),
102  std_mul_ (0.0)
103  {
104  filter_name_ = "StatisticalOutlierRemoval";
105  }
106 
107  /** \brief Set the number of nearest neighbors to use for mean distance estimation.
108  * \param[in] nr_k The number of points to use for mean distance estimation.
109  */
110  inline void
111  setMeanK (int nr_k)
112  {
113  mean_k_ = nr_k;
114  }
115 
116  /** \brief Get the number of nearest neighbors to use for mean distance estimation.
117  * \return The number of points to use for mean distance estimation.
118  */
119  inline int
121  {
122  return (mean_k_);
123  }
124 
125  /** \brief Set the standard deviation multiplier for the distance threshold calculation.
126  * \details The distance threshold will be equal to: mean + stddev_mult * stddev.
127  * Points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively.
128  * \param[in] stddev_mult The standard deviation multiplier.
129  */
130  inline void
131  setStddevMulThresh (double stddev_mult)
132  {
133  std_mul_ = stddev_mult;
134  }
135 
136  /** \brief Get the standard deviation multiplier for the distance threshold calculation.
137  * \details The distance threshold will be equal to: mean + stddev_mult * stddev.
138  * Points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively.
139  */
140  inline double
142  {
143  return (std_mul_);
144  }
145 
146  protected:
156 
157  /** \brief Filtered results are stored in a separate point cloud.
158  * \param[out] output The resultant point cloud.
159  */
160  void
161  applyFilter (PointCloud &output);
162 
163  /** \brief Filtered results are indexed by an indices array.
164  * \param[out] indices The resultant indices.
165  */
166  void
167  applyFilter (std::vector<int> &indices)
168  {
169  applyFilterIndices (indices);
170  }
171 
172  /** \brief Filtered results are indexed by an indices array.
173  * \param[out] indices The resultant indices.
174  */
175  void
176  applyFilterIndices (std::vector<int> &indices);
177 
178  private:
179  /** \brief A pointer to the spatial search object. */
180  SearcherPtr searcher_;
181 
182  /** \brief The number of points to use for mean distance estimation. */
183  int mean_k_;
184 
185  /** \brief Standard deviations threshold (i.e., points outside of
186  * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). */
187  double std_mul_;
188  };
189 
190  /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more
191  * information check:
192  * - R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz.
193  * Towards 3D Point Cloud Based Object Maps for Household Environments
194  * Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008.
195  *
196  * \note setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored.
197  * \author Radu Bogdan Rusu
198  * \ingroup filters
199  */
200  template<>
201  class PCL_EXPORTS StatisticalOutlierRemoval<pcl::PCLPointCloud2> : public Filter<pcl::PCLPointCloud2>
202  {
205 
208 
210  typedef pcl::search::Search<pcl::PointXYZ>::Ptr KdTreePtr;
211 
215 
216  public:
217  /** \brief Empty constructor. */
218  StatisticalOutlierRemoval (bool extract_removed_indices = false) :
219  Filter<pcl::PCLPointCloud2>::Filter (extract_removed_indices), mean_k_ (2),
220  std_mul_ (0.0), tree_ (), negative_ (false)
221  {
222  filter_name_ = "StatisticalOutlierRemoval";
223  }
224 
225  /** \brief Set the number of points (k) to use for mean distance estimation
226  * \param nr_k the number of points to use for mean distance estimation
227  */
228  inline void
229  setMeanK (int nr_k)
230  {
231  mean_k_ = nr_k;
232  }
233 
234  /** \brief Get the number of points to use for mean distance estimation. */
235  inline int
236  getMeanK ()
237  {
238  return (mean_k_);
239  }
240 
241  /** \brief Set the standard deviation multiplier threshold. All points outside the
242  * \f[ \mu \pm \sigma \cdot std\_mul \f]
243  * will be considered outliers, where \f$ \mu \f$ is the estimated mean,
244  * and \f$ \sigma \f$ is the standard deviation.
245  * \param std_mul the standard deviation multiplier threshold
246  */
247  inline void
248  setStddevMulThresh (double std_mul)
249  {
250  std_mul_ = std_mul;
251  }
252 
253  /** \brief Get the standard deviation multiplier threshold as set by the user. */
254  inline double
255  getStddevMulThresh ()
256  {
257  return (std_mul_);
258  }
259 
260  /** \brief Set whether the indices should be returned, or all points \e except the indices.
261  * \param negative true if all points \e except the input indices will be returned, false otherwise
262  */
263  inline void
264  setNegative (bool negative)
265  {
266  negative_ = negative;
267  }
268 
269  /** \brief Get the value of the internal #negative_ parameter. If
270  * true, all points \e except the input indices will be returned.
271  * \return The value of the "negative" flag
272  */
273  inline bool
274  getNegative ()
275  {
276  return (negative_);
277  }
278 
279  protected:
280  /** \brief The number of points to use for mean distance estimation. */
281  int mean_k_;
282 
283  /** \brief Standard deviations threshold (i.e., points outside of
284  * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers).
285  */
286  double std_mul_;
287 
288  /** \brief A pointer to the spatial search object. */
289  KdTreePtr tree_;
290 
291  /** \brief If true, the outliers will be returned instead of the inliers (default: false). */
292  bool negative_;
293 
294  void
295  applyFilter (PCLPointCloud2 &output);
296  };
297 }
298 
299 #ifdef PCL_NO_PRECOMPILE
300 #include <pcl/filters/impl/statistical_outlier_removal.hpp>
301 #endif
302 
303 #endif // PCL_FILTERS_STATISTICAL_OUTLIER_REMOVAL_H_
304