Point Cloud Library (PCL) 1.14.0
Loading...
Searching...
No Matches
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
45namespace 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:
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 /** \brief Provide a pointer to the search object.
144 * Calling this is optional. If not called, the search method will be chosen automatically.
145 * \param[in] searcher a pointer to the spatial search object.
146 */
147 inline void
148 setSearchMethod (const SearcherPtr &searcher) { searcher_ = searcher; }
149 protected:
150 using PCLBase<PointT>::input_;
159
160 /** \brief Filtered results are indexed by an indices array.
161 * \param[out] indices The resultant indices.
162 */
163 void
164 applyFilter (Indices &indices) override
165 {
166 applyFilterIndices (indices);
167 }
168
169 /** \brief Filtered results are indexed by an indices array.
170 * \param[out] indices The resultant indices.
171 */
172 void
173 applyFilterIndices (Indices &indices);
174
175 private:
176 /** \brief A pointer to the spatial search object. */
177 SearcherPtr searcher_;
178
179 /** \brief The number of points to use for mean distance estimation. */
180 int mean_k_{1};
181
182 /** \brief Standard deviations threshold (i.e., points outside of
183 * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). */
184 double std_mul_{0.0};
185 };
186
187 /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more
188 * information check:
189 * - R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz.
190 * Towards 3D Point Cloud Based Object Maps for Household Environments
191 * Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008.
192 *
193 * \author Radu Bogdan Rusu
194 * \ingroup filters
195 */
196 template<>
197 class PCL_EXPORTS StatisticalOutlierRemoval<pcl::PCLPointCloud2> : public FilterIndices<pcl::PCLPointCloud2>
198 {
199 using FilterIndices<pcl::PCLPointCloud2>::filter_name_;
200 using FilterIndices<pcl::PCLPointCloud2>::getClassName;
201
202 using FilterIndices<pcl::PCLPointCloud2>::removed_indices_;
203 using FilterIndices<pcl::PCLPointCloud2>::extract_removed_indices_;
204
207
209 using PCLPointCloud2Ptr = PCLPointCloud2::Ptr;
210 using PCLPointCloud2ConstPtr = PCLPointCloud2::ConstPtr;
211
212 public:
213 /** \brief Empty constructor. */
214 StatisticalOutlierRemoval (bool extract_removed_indices = false) :
215 FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices)
216 {
217 filter_name_ = "StatisticalOutlierRemoval";
218 }
219
220 /** \brief Set the number of points (k) to use for mean distance estimation
221 * \param nr_k the number of points to use for mean distance estimation
222 */
223 inline void
224 setMeanK (int nr_k)
225 {
226 mean_k_ = nr_k;
227 }
228
229 /** \brief Get the number of points to use for mean distance estimation. */
230 inline int
232 {
233 return (mean_k_);
234 }
235
236 /** \brief Set the standard deviation multiplier threshold. All points outside the
237 * \f[ \mu \pm \sigma \cdot std\_mul \f]
238 * will be considered outliers, where \f$ \mu \f$ is the estimated mean,
239 * and \f$ \sigma \f$ is the standard deviation.
240 * \param std_mul the standard deviation multiplier threshold
241 */
242 inline void
243 setStddevMulThresh (double std_mul)
244 {
245 std_mul_ = std_mul;
246 }
247
248 /** \brief Get the standard deviation multiplier threshold as set by the user. */
249 inline double
251 {
252 return (std_mul_);
253 }
254
255 protected:
256 /** \brief The number of points to use for mean distance estimation. */
257 int mean_k_{2};
258
259 /** \brief Standard deviations threshold (i.e., points outside of
260 * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers).
261 */
262 double std_mul_{0.0};
263
264 /** \brief A pointer to the spatial search object. */
265 KdTreePtr tree_;
266
267 void
268 applyFilter (Indices &indices) override;
269
270 void
271 applyFilter (PCLPointCloud2 &output) override;
272
273 /**
274 * \brief Compute the statistical values used in both applyFilter methods.
275 *
276 * This method tries to avoid duplicate code.
277 */
278 virtual void
279 generateStatistics (double& mean, double& variance, double& stddev, std::vector<float>& distances);
280 };
281}
282
283#ifdef PCL_NO_PRECOMPILE
284#include <pcl/filters/impl/statistical_outlier_removal.hpp>
285#endif
Filter represents the base filter class.
Definition filter.h:81
bool extract_removed_indices_
Set to true if we want to return the indices of the removed points.
Definition filter.h:161
const std::string & getClassName() const
Get a string representation of the name of this class.
Definition filter.h:174
std::string filter_name_
The filter name.
Definition filter.h:158
IndicesPtr removed_indices_
Indices of the points that are removed.
Definition filter.h:155
FilterIndices represents the base class for filters that are about binary point removal.
float user_filter_value_
The user given value that the filtered point dimensions should be set to (default = NaN).
bool keep_organized_
False = remove points (default), true = redefine points, keep structure.
bool negative_
False = normal filter behavior (default), true = inverted behavior.
PCL base class.
Definition pcl_base.h:70
PointCloudConstPtr input_
The input point cloud dataset.
Definition pcl_base.h:147
IndicesPtr indices_
A pointer to the vector of point indices to use.
Definition pcl_base.h:150
PointCloud represents the base class in PCL for storing collections of 3D points.
shared_ptr< PointCloud< PointT > > Ptr
shared_ptr< const PointCloud< PointT > > ConstPtr
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 PointCloud::ConstPtr PointCloudConstPtr
typename pcl::search::Search< PointT >::Ptr SearcherPtr
shared_ptr< StatisticalOutlierRemoval< PointT > > Ptr
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.
void setSearchMethod(const SearcherPtr &searcher)
Provide a pointer to the search object.
typename FilterIndices< PointT >::PointCloud PointCloud
shared_ptr< const StatisticalOutlierRemoval< PointT > > ConstPtr
shared_ptr< pcl::search::Search< PointT > > Ptr
Definition search.h:81
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition types.h:133
shared_ptr< ::pcl::PCLPointCloud2 > Ptr
shared_ptr< const ::pcl::PCLPointCloud2 > ConstPtr
A point structure representing Euclidean xyz coordinates, and the RGB color.