point_cloud_library / 1.12.1 / classpcl_1_1_statistical_outlier_removal.html /

StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. More...

#include <pcl/filters/statistical_outlier_removal.h>

Public Types

using Ptr = shared_ptr< StatisticalOutlierRemoval< PointT > >
using ConstPtr = shared_ptr< const StatisticalOutlierRemoval< PointT > >
- Public Types inherited from pcl::FilterIndices< PointT >
using PointCloud = pcl::PointCloud< PointT >
using Ptr = shared_ptr< FilterIndices< PointT > >
using ConstPtr = shared_ptr< const FilterIndices< PointT > >
- Public Types inherited from pcl::Filter< PointT >
using Ptr = shared_ptr< Filter< PointT > >
using ConstPtr = shared_ptr< const Filter< PointT > >
using PointCloud = pcl::PointCloud< PointT >
using PointCloudPtr = typename PointCloud::Ptr
using PointCloudConstPtr = typename PointCloud::ConstPtr
- Public Types inherited from pcl::PCLBase< PointT >
using PointCloud = pcl::PointCloud< PointT >
using PointCloudPtr = typename PointCloud::Ptr
using PointCloudConstPtr = typename PointCloud::ConstPtr
using PointIndicesPtr = PointIndices::Ptr
using PointIndicesConstPtr = PointIndices::ConstPtr

Public Member Functions

StatisticalOutlierRemoval (bool extract_removed_indices=false)
Constructor. More...
void setMeanK (int nr_k)
Set the number of nearest neighbors to use for mean distance estimation. More...
int getMeanK ()
Get the number of nearest neighbors to use for mean distance estimation. More...
void setStddevMulThresh (double stddev_mult)
Set the standard deviation multiplier for the distance threshold calculation. More...
double getStddevMulThresh ()
Get the standard deviation multiplier for the distance threshold calculation. More...
- Public Member Functions inherited from pcl::FilterIndices< PointT >
FilterIndices (bool extract_removed_indices=false)
Constructor. More...
void filter (Indices &indices)
Calls the filtering method and returns the filtered point cloud indices. More...
void setNegative (bool negative)
Set whether the regular conditions for points filtering should apply, or the inverted conditions. More...
bool getNegative () const
Get whether the regular conditions for points filtering should apply, or the inverted conditions. More...
void setKeepOrganized (bool keep_organized)
Set whether the filtered points should be kept and set to the value given through setUserFilterValue (default: NaN), or removed from the PointCloud, thus potentially breaking its organized structure. More...
bool getKeepOrganized () const
Get whether the filtered points should be kept and set to the value given through setUserFilterValue (default = NaN), or removed from the PointCloud, thus potentially breaking its organized structure. More...
void setUserFilterValue (float value)
Provide a value that the filtered points should be set to instead of removing them. More...
- Public Member Functions inherited from pcl::Filter< PointT >
Filter (bool extract_removed_indices=false)
Empty constructor. More...
const IndicesConstPtr getRemovedIndices () const
Get the point indices being removed. More...
void getRemovedIndices (PointIndices &pi)
Get the point indices being removed. More...
void filter (PointCloud &output)
Calls the filtering method and returns the filtered dataset in output. More...
- Public Member Functions inherited from pcl::PCLBase< PointT >
PCLBase ()
Empty constructor. More...
PCLBase (const PCLBase &base)
Copy constructor. More...
virtual ~PCLBase ()=default
Destructor. More...
virtual void setInputCloud (const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset. More...
const PointCloudConstPtr getInputCloud () const
Get a pointer to the input point cloud dataset. More...
virtual void setIndices (const IndicesPtr &indices)
Provide a pointer to the vector of indices that represents the input data. More...
virtual void setIndices (const IndicesConstPtr &indices)
Provide a pointer to the vector of indices that represents the input data. More...
virtual void setIndices (const PointIndicesConstPtr &indices)
Provide a pointer to the vector of indices that represents the input data. More...
virtual void setIndices (std::size_t row_start, std::size_t col_start, std::size_t nb_rows, std::size_t nb_cols)
Set the indices for the points laying within an interest region of the point cloud. More...
IndicesPtr getIndices ()
Get a pointer to the vector of indices used. More...
const IndicesConstPtr getIndices () const
Get a pointer to the vector of indices used. More...
const PointT & operator[] (std::size_t pos) const
Override PointCloud operator[] to shorten code. More...

Protected Types

using PointCloud = typename FilterIndices< PointT >::PointCloud
using PointCloudPtr = typename PointCloud::Ptr
using PointCloudConstPtr = typename PointCloud::ConstPtr
using SearcherPtr = typename pcl::search::Search< PointT >::Ptr

Protected Member Functions

void applyFilter (Indices &indices) override
Filtered results are indexed by an indices array. More...
void applyFilterIndices (Indices &indices)
Filtered results are indexed by an indices array. More...
- Protected Member Functions inherited from pcl::FilterIndices< PointT >
void applyFilter (PointCloud &output) override
Abstract filter method for point cloud. More...
- Protected Member Functions inherited from pcl::Filter< PointT >
const std::string & getClassName () const
Get a string representation of the name of this class. More...
- Protected Member Functions inherited from pcl::PCLBase< PointT >
bool initCompute ()
This method should get called before starting the actual computation. More...
bool deinitCompute ()
This method should get called after finishing the actual computation. More...

Additional Inherited Members

- Protected Attributes inherited from pcl::FilterIndices< PointT >
bool negative_
False = normal filter behavior (default), true = inverted behavior. More...
bool keep_organized_
False = remove points (default), true = redefine points, keep structure. More...
float user_filter_value_
The user given value that the filtered point dimensions should be set to (default = NaN). More...
- Protected Attributes inherited from pcl::Filter< PointT >
IndicesPtr removed_indices_
Indices of the points that are removed. More...
std::string filter_name_
The filter name. More...
bool extract_removed_indices_
Set to true if we want to return the indices of the removed points. More...
- Protected Attributes inherited from pcl::PCLBase< PointT >
PointCloudConstPtr input_
The input point cloud dataset. More...
IndicesPtr indices_
A pointer to the vector of point indices to use. More...
bool use_indices_
Set to true if point indices are used. More...
bool fake_indices_
If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More...

Detailed Description

template<typename PointT>
class pcl::StatisticalOutlierRemoval< PointT >

StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data.

The algorithm iterates through the entire input twice: During the first iteration it will compute the average distance that each point has to its nearest k neighbors. The value of k can be set using setMeanK(). Next, the mean and standard deviation of all these distances are computed in order to determine a distance threshold. The distance threshold will be equal to: mean + stddev_mult * stddev. The multiplier for the standard deviation can be set using setStddevMulThresh(). 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.
The neighbors found for each query point will be found amongst ALL points of setInputCloud(), not just those indexed by setIndices(). The setIndices() method only indexes the points that will be iterated through as search query points.

For more information:

  • R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz. Towards 3D Point Cloud Based Object Maps for Household Environments Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008.

    Usage example:
    pcl::StatisticalOutlierRemoval<PointType> sorfilter ( true); // Initializing with true will allow us to extract the removed indices
    sorfilter.setInputCloud (cloud_in);
    sorfilter.setMeanK (8);
    sorfilter.setStddevMulThresh (1.0);
    sorfilter.filter (*cloud_out);
    // 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
    // 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
    indices_rem = sorfilter.getRemovedIndices ();
    // The indices_rem array indexes all points of cloud_in that are outliers
    Author
    Radu Bogdan Rusu

Definition at line 80 of file statistical_outlier_removal.h.

Member Typedef Documentation

ConstPtr

template<typename PointT >
using pcl::StatisticalOutlierRemoval< PointT >::ConstPtr = shared_ptr<const StatisticalOutlierRemoval<PointT> >

Definition at line 91 of file statistical_outlier_removal.h.

PointCloud

template<typename PointT >
using pcl::StatisticalOutlierRemoval< PointT >::PointCloud = typename FilterIndices<PointT>::PointCloud
protected

Definition at line 83 of file statistical_outlier_removal.h.

PointCloudConstPtr

template<typename PointT >
using pcl::StatisticalOutlierRemoval< PointT >::PointCloudConstPtr = typename PointCloud::ConstPtr
protected

Definition at line 85 of file statistical_outlier_removal.h.

PointCloudPtr

template<typename PointT >
using pcl::StatisticalOutlierRemoval< PointT >::PointCloudPtr = typename PointCloud::Ptr
protected

Definition at line 84 of file statistical_outlier_removal.h.

Ptr

template<typename PointT >
using pcl::StatisticalOutlierRemoval< PointT >::Ptr = shared_ptr<StatisticalOutlierRemoval<PointT> >

Definition at line 90 of file statistical_outlier_removal.h.

SearcherPtr

template<typename PointT >
using pcl::StatisticalOutlierRemoval< PointT >::SearcherPtr = typename pcl::search::Search<PointT>::Ptr
protected

Definition at line 86 of file statistical_outlier_removal.h.

Constructor & Destructor Documentation

StatisticalOutlierRemoval()

template<typename PointT >
pcl::StatisticalOutlierRemoval< PointT >::StatisticalOutlierRemoval ( bool extract_removed_indices = false )
inline

Constructor.

Parameters
[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false).

Definition at line 97 of file statistical_outlier_removal.h.

References pcl::Filter< PointT >::filter_name_.

Member Function Documentation

applyFilter()

template<typename PointT >
void pcl::StatisticalOutlierRemoval< PointT >::applyFilter ( Indices & indices )
inlineoverrideprotectedvirtual

Filtered results are indexed by an indices array.

Parameters
[out] indices The resultant indices.

Implements pcl::FilterIndices< PointT >.

Definition at line 160 of file statistical_outlier_removal.h.

References pcl::StatisticalOutlierRemoval< PointT >::applyFilterIndices().

applyFilterIndices()

template<typename PointT >
void pcl::StatisticalOutlierRemoval< PointT >::applyFilterIndices ( Indices & indices )
protected

Filtered results are indexed by an indices array.

Parameters
[out] indices The resultant indices.

Definition at line 49 of file statistical_outlier_removal.hpp.

References pcl::geometry::distance().

Referenced by pcl::StatisticalOutlierRemoval< PointT >::applyFilter().

getMeanK()

template<typename PointT >
int pcl::StatisticalOutlierRemoval< PointT >::getMeanK ( )
inline

Get the number of nearest neighbors to use for mean distance estimation.

Returns
The number of points to use for mean distance estimation.

Definition at line 119 of file statistical_outlier_removal.h.

getStddevMulThresh()

template<typename PointT >
double pcl::StatisticalOutlierRemoval< PointT >::getStddevMulThresh ( )
inline

Get the standard deviation multiplier for the distance threshold calculation.

The distance threshold will be equal to: mean + stddev_mult * stddev. Points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively.

Definition at line 140 of file statistical_outlier_removal.h.

setMeanK()

template<typename PointT >
void pcl::StatisticalOutlierRemoval< PointT >::setMeanK ( int nr_k )
inline

Set the number of nearest neighbors to use for mean distance estimation.

Parameters
[in] nr_k The number of points to use for mean distance estimation.

Definition at line 110 of file statistical_outlier_removal.h.

setStddevMulThresh()

template<typename PointT >
void pcl::StatisticalOutlierRemoval< PointT >::setStddevMulThresh ( double stddev_mult )
inline

Set the standard deviation multiplier for the distance threshold calculation.

The distance threshold will be equal to: mean + stddev_mult * stddev. Points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively.

Parameters
[in] stddev_mult The standard deviation multiplier.

Definition at line 130 of file statistical_outlier_removal.h.


The documentation for this class was generated from the following files:

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1_statistical_outlier_removal.html