Point Cloud Library (PCL) 1.15.1-dev
Loading...
Searching...
No Matches
radius_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, Search<>::Ptr
44#include <pcl/point_types.h> // for pcl::PointXYZ
45
46namespace pcl
47{
48 /** \brief @b RadiusOutlierRemoval filters points in a cloud based on the number of neighbors they have.
49 * \details Iterates through the entire input once, and for each point, retrieves the number of neighbors within a certain radius.
50 * The point will be considered an outlier if it has too few neighbors, as determined by setMinNeighborsInRadius().
51 * The radius can be changed using setRadiusSearch().
52 * <br>
53 * The neighbors found for each query point will be found amongst ALL points of setInputCloud(), not just those indexed by setIndices().
54 * The setIndices() method only indexes the points that will be iterated through as search query points.
55 * <br><br>
56 * Usage example:
57 * \code
58 * pcl::RadiusOutlierRemoval<PointType> rorfilter (true); // Initializing with true will allow us to extract the removed indices
59 * rorfilter.setInputCloud (cloud_in);
60 * rorfilter.setRadiusSearch (0.1);
61 * rorfilter.setMinNeighborsInRadius (5);
62 * rorfilter.setNegative (true);
63 * rorfilter.filter (*cloud_out);
64 * // The resulting cloud_out contains all points of cloud_in that have 4 or less neighbors within the 0.1 search radius
65 * indices_rem = rorfilter.getRemovedIndices ();
66 * // The indices_rem array indexes all points of cloud_in that have 5 or more neighbors within the 0.1 search radius
67 * \endcode
68 * \sa StatisticalOutlierRemoval
69 * \author Radu Bogdan Rusu
70 * \ingroup filters
71 */
72 template<typename PointT>
73 class RadiusOutlierRemoval : public FilterIndices<PointT>
74 {
75 protected:
80
81 public:
82
83 using Ptr = shared_ptr<RadiusOutlierRemoval<PointT> >;
84 using ConstPtr = shared_ptr<const RadiusOutlierRemoval<PointT> >;
85
86
87 /** \brief Constructor.
88 * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false).
89 */
90 RadiusOutlierRemoval (bool extract_removed_indices = false) :
91 FilterIndices<PointT> (extract_removed_indices),
92 searcher_ ()
93 {
94 filter_name_ = "RadiusOutlierRemoval";
95 }
96
97 /** \brief Set the radius of the sphere that will determine which points are neighbors.
98 * \details The number of points within this distance from the query point will need to be equal or greater
99 * than setMinNeighborsInRadius() in order to be classified as an inlier point (i.e. will not be filtered).
100 * \param[in] radius The radius of the sphere for nearest neighbor searching.
101 */
102 inline void
103 setRadiusSearch (double radius)
104 {
105 search_radius_ = radius;
106 }
107
108 /** \brief Get the radius of the sphere that will determine which points are neighbors.
109 * \details The number of points within this distance from the query point will need to be equal or greater
110 * than setMinNeighborsInRadius() in order to be classified as an inlier point (i.e. will not be filtered).
111 * \return The radius of the sphere for nearest neighbor searching.
112 */
113 inline double
115 {
116 return (search_radius_);
117 }
118
119 /** \brief Set the number of neighbors that need to be present in order to be classified as an inlier.
120 * \details The number of points within setRadiusSearch() from the query point will need to be equal or greater
121 * than this number in order to be classified as an inlier point (i.e. will not be filtered).
122 * \param min_pts The minimum number of neighbors (default = 1).
123 */
124 inline void
126 {
127 min_pts_radius_ = min_pts;
128 }
129
130 /** \brief Get the number of neighbors that need to be present in order to be classified as an inlier.
131 * \details The number of points within setRadiusSearch() from the query point will need to be equal or greater
132 * than this number in order to be classified as an inlier point (i.e. will not be filtered).
133 * \return The minimum number of neighbors (default = 1).
134 */
135 inline int
137 {
138 return (min_pts_radius_);
139 }
140
141 /** \brief Provide a pointer to the search object.
142 * Calling this is optional. If not called, the search method will be chosen automatically.
143 * \param[in] searcher a pointer to the spatial search object.
144 */
145 inline void
146 setSearchMethod (const SearcherPtr &searcher) { searcher_ = searcher; }
147
148 /** \brief Set the number of threads to use.
149 * \param nr_threads the number of hardware threads to use (0 sets the value back
150 * to automatic)
151 */
152 void
153 setNumberOfThreads(unsigned int nr_threads = 0)
154 {
155#ifdef _OPENMP
156 num_threads_ = nr_threads != 0 ? nr_threads : omp_get_num_procs();
157#else
158 if (num_threads_ != 1) {
159 PCL_WARN("OpenMP is not available. Keeping number of threads unchanged at 1\n");
160 }
161 num_threads_ = 1;
162#endif
163 }
164
165 protected:
166 using PCLBase<PointT>::input_;
175
176 /** \brief Filtered results are indexed by an indices array.
177 * \param[out] indices The resultant indices.
178 */
179 void
180 applyFilter (Indices &indices) override
181 {
182 applyFilterIndices (indices);
183 }
184
185 /** \brief Filtered results are indexed by an indices array.
186 * \param[out] indices The resultant indices.
187 */
188 void
189 applyFilterIndices (Indices &indices);
190
191 private:
192 /** \brief A pointer to the spatial search object. */
193 SearcherPtr searcher_;
194
195 /** \brief The nearest neighbors search radius for each point. */
196 double search_radius_{0.0};
197
198 /** \brief The minimum number of neighbors that a point needs to have in the given search radius to be considered an inlier. */
199 int min_pts_radius_{1};
200
201 /**
202 * @brief Number of threads used during filtering
203 */
204 int num_threads_{1};
205 };
206
207 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
208 /** \brief @b RadiusOutlierRemoval is a simple filter that removes outliers if the number of neighbors in a certain
209 * search radius is smaller than a given K.
210 * \author Radu Bogdan Rusu
211 * \ingroup filters
212 */
213 template<>
214 class PCL_EXPORTS RadiusOutlierRemoval<pcl::PCLPointCloud2> : public FilterIndices<pcl::PCLPointCloud2>
215 {
216 using Filter<pcl::PCLPointCloud2>::filter_name_;
217 using Filter<pcl::PCLPointCloud2>::getClassName;
218
219 using Filter<pcl::PCLPointCloud2>::removed_indices_;
220 using Filter<pcl::PCLPointCloud2>::extract_removed_indices_;
221
224
226 using PCLPointCloud2Ptr = PCLPointCloud2::Ptr;
227 using PCLPointCloud2ConstPtr = PCLPointCloud2::ConstPtr;
228
229 public:
230 /** \brief Empty constructor. */
231 RadiusOutlierRemoval (bool extract_removed_indices = false) :
232 FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices)
233 {
234 filter_name_ = "RadiusOutlierRemoval";
235 }
236
237 /** \brief Set the sphere radius that is to be used for determining the k-nearest neighbors for filtering.
238 * \param radius the sphere radius that is to contain all k-nearest neighbors
239 */
240 inline void
241 setRadiusSearch (double radius)
242 {
243 search_radius_ = radius;
244 }
245
246 /** \brief Get the sphere radius used for determining the k-nearest neighbors. */
247 inline double
249 {
250 return (search_radius_);
251 }
252
253 /** \brief Set the minimum number of neighbors that a point needs to have in the given search radius in order to
254 * be considered an inlier (i.e., valid).
255 * \param min_pts the minimum number of neighbors
256 */
257 inline void
259 {
260 min_pts_radius_ = min_pts;
261 }
262
263 /** \brief Get the minimum number of neighbors that a point needs to have in the given search radius to be
264 * considered an inlier and avoid being filtered.
265 */
266 inline double
268 {
269 return (min_pts_radius_);
270 }
271
272 protected:
273 /** \brief The nearest neighbors search radius for each point. */
274 double search_radius_{0.0};
275
276 /** \brief The minimum number of neighbors that a point needs to have in the given search radius to be considered
277 * an inlier.
278 */
279 int min_pts_radius_{1};
280
281 /** \brief A pointer to the spatial search object. */
282 KdTreePtr searcher_;
283
284 void
285 applyFilter (PCLPointCloud2 &output) override;
286
287 void
288 applyFilter (Indices &indices) override;
289 };
290}
291
292#ifdef PCL_NO_PRECOMPILE
293#include <pcl/filters/impl/radius_outlier_removal.hpp>
294#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
double getRadiusSearch() const
Get the sphere radius used for determining the k-nearest neighbors.
void applyFilter(Indices &indices) override
Abstract filter method for point cloud indices.
void setRadiusSearch(double radius)
Set the sphere radius that is to be used for determining the k-nearest neighbors for filtering.
KdTreePtr searcher_
A pointer to the spatial search object.
double getMinNeighborsInRadius() const
Get the minimum number of neighbors that a point needs to have in the given search radius to be consi...
RadiusOutlierRemoval(bool extract_removed_indices=false)
Empty constructor.
void applyFilter(PCLPointCloud2 &output) override
Abstract filter method for point cloud.
void setMinNeighborsInRadius(int min_pts)
Set the minimum number of neighbors that a point needs to have in the given search radius in order to...
RadiusOutlierRemoval filters points in a cloud based on the number of neighbors they have.
void applyFilterIndices(Indices &indices)
Filtered results are indexed by an indices array.
void applyFilter(Indices &indices) override
Filtered results are indexed by an indices array.
double getRadiusSearch() const
Get the radius of the sphere that will determine which points are neighbors.
typename PointCloud::Ptr PointCloudPtr
void setMinNeighborsInRadius(int min_pts)
Set the number of neighbors that need to be present in order to be classified as an inlier.
typename PointCloud::ConstPtr PointCloudConstPtr
void setRadiusSearch(double radius)
Set the radius of the sphere that will determine which points are neighbors.
shared_ptr< RadiusOutlierRemoval< PointT > > Ptr
int getMinNeighborsInRadius() const
Get the number of neighbors that need to be present in order to be classified as an inlier.
RadiusOutlierRemoval(bool extract_removed_indices=false)
Constructor.
shared_ptr< const RadiusOutlierRemoval< PointT > > ConstPtr
typename pcl::search::Search< PointT >::Ptr SearcherPtr
typename FilterIndices< PointT >::PointCloud PointCloud
void setSearchMethod(const SearcherPtr &searcher)
Provide a pointer to the search object.
void setNumberOfThreads(unsigned int nr_threads=0)
Set the number of threads to use.
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.