Point Cloud Library (PCL) 1.15.1-dev
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/point_types.h> // for pcl::PointXYZ
44#include <pcl/search/search.h> // for Search
45
46namespace 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 * \sa RadiusOutlierRemoval
78 * \author Radu Bogdan Rusu
79 * \ingroup filters
80 */
81 template<typename PointT>
83 {
84 protected:
89
90 public:
91
92 using Ptr = shared_ptr<StatisticalOutlierRemoval<PointT> >;
93 using ConstPtr = shared_ptr<const StatisticalOutlierRemoval<PointT> >;
94
95
96 /** \brief Constructor.
97 * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false).
98 */
99 StatisticalOutlierRemoval (bool extract_removed_indices = false) :
100 FilterIndices<PointT> (extract_removed_indices),
101 searcher_ ()
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 /** \brief Provide a pointer to the search object.
146 * Calling this is optional. If not called, the search method will be chosen automatically.
147 * \param[in] searcher a pointer to the spatial search object.
148 */
149 inline void
150 setSearchMethod (const SearcherPtr &searcher) { searcher_ = searcher; }
151 protected:
152 using PCLBase<PointT>::input_;
161
162 /** \brief Filtered results are indexed by an indices array.
163 * \param[out] indices The resultant indices.
164 */
165 void
166 applyFilter (Indices &indices) override
167 {
168 applyFilterIndices (indices);
169 }
170
171 /** \brief Filtered results are indexed by an indices array.
172 * \param[out] indices The resultant indices.
173 */
174 void
175 applyFilterIndices (Indices &indices);
176
177 private:
178 /** \brief A pointer to the spatial search object. */
179 SearcherPtr searcher_;
180
181 /** \brief The number of points to use for mean distance estimation. */
182 int mean_k_{1};
183
184 /** \brief Standard deviations threshold (i.e., points outside of
185 * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). */
186 double std_mul_{0.0};
187 };
188
189 /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more
190 * information check:
191 * - R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz.
192 * Towards 3D Point Cloud Based Object Maps for Household Environments
193 * Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008.
194 *
195 * \author Radu Bogdan Rusu
196 * \ingroup filters
197 */
198 template<>
199 class PCL_EXPORTS StatisticalOutlierRemoval<pcl::PCLPointCloud2> : public FilterIndices<pcl::PCLPointCloud2>
200 {
201 using FilterIndices<pcl::PCLPointCloud2>::filter_name_;
202 using FilterIndices<pcl::PCLPointCloud2>::getClassName;
203
204 using FilterIndices<pcl::PCLPointCloud2>::removed_indices_;
205 using FilterIndices<pcl::PCLPointCloud2>::extract_removed_indices_;
206
209
211 using PCLPointCloud2Ptr = PCLPointCloud2::Ptr;
212 using PCLPointCloud2ConstPtr = PCLPointCloud2::ConstPtr;
213
214 public:
215 /** \brief Empty constructor. */
216 StatisticalOutlierRemoval (bool extract_removed_indices = false) :
217 FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices)
218 {
219 filter_name_ = "StatisticalOutlierRemoval";
220 }
221
222 /** \brief Set the number of points (k) to use for mean distance estimation
223 * \param nr_k the number of points to use for mean distance estimation
224 */
225 inline void
226 setMeanK (int nr_k)
227 {
228 mean_k_ = nr_k;
229 }
230
231 /** \brief Get the number of points to use for mean distance estimation. */
232 inline int
233 getMeanK () const
234 {
235 return (mean_k_);
236 }
237
238 /** \brief Set the standard deviation multiplier threshold. All points outside the
239 * \f[ \mu \pm \sigma \cdot std\_mul \f]
240 * will be considered outliers, where \f$ \mu \f$ is the estimated mean,
241 * and \f$ \sigma \f$ is the standard deviation.
242 * \param std_mul the standard deviation multiplier threshold
243 */
244 inline void
245 setStddevMulThresh (double std_mul)
246 {
247 std_mul_ = std_mul;
248 }
249
250 /** \brief Get the standard deviation multiplier threshold as set by the user. */
251 inline double
253 {
254 return (std_mul_);
255 }
256
257 protected:
258 /** \brief The number of points to use for mean distance estimation. */
259 int mean_k_{2};
260
261 /** \brief Standard deviations threshold (i.e., points outside of
262 * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers).
263 */
264 double std_mul_{0.0};
265
266 /** \brief A pointer to the spatial search object. */
267 KdTreePtr tree_;
268
269 void
270 applyFilter (Indices &indices) override;
271
272 void
273 applyFilter (PCLPointCloud2 &output) override;
274
275 /**
276 * \brief Compute the statistical values used in both applyFilter methods.
277 *
278 * This method tries to avoid duplicate code.
279 */
280 virtual void
281 generateStatistics (double& mean, double& variance, double& stddev, std::vector<float>& distances);
282 };
283}
284
285#ifdef PCL_NO_PRECOMPILE
286#include <pcl/filters/impl/statistical_outlier_removal.hpp>
287#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() const
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.
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.
double getStddevMulThresh() const
Get the standard deviation multiplier threshold as set by the user.
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
double getStddevMulThresh() const
Get the standard deviation multiplier for the distance threshold calculation.
typename pcl::search::Search< PointT >::Ptr SearcherPtr
shared_ptr< StatisticalOutlierRemoval< PointT > > Ptr
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
Defines all the PCL implemented PointT point type structures.
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.