Point Cloud Library (PCL) 1.15.0
Loading...
Searching...
No Matches
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 > Class Reference

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

#include <pcl/filters/statistical_outlier_removal.h>

+ Inheritance diagram for pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >:
+ Collaboration diagram for pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >:

Public Types

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

Public Member Functions

 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.
 
int getMeanK ()
 Get the number of points to use for mean distance estimation.
 
void setStddevMulThresh (double std_mul)
 Set the standard deviation multiplier threshold.
 
double getStddevMulThresh ()
 Get the standard deviation multiplier threshold as set by the user.
 
 StatisticalOutlierRemoval (bool extract_removed_indices=false)
 Constructor.
 
void setMeanK (int nr_k)
 Set the number of nearest neighbors to use for mean distance estimation.
 
int getMeanK ()
 Get the number of nearest neighbors to use for mean distance estimation.
 
void setStddevMulThresh (double stddev_mult)
 Set the standard deviation multiplier for the distance threshold calculation.
 
double getStddevMulThresh ()
 Get the standard deviation multiplier for the distance threshold calculation.
 
void setSearchMethod (const SearcherPtr &searcher)
 Provide a pointer to the search object.
 
- Public Member Functions inherited from pcl::FilterIndices< pcl::PCLPointCloud2 >
 FilterIndices (bool extract_removed_indices=false)
 Constructor.
 
void filter (Indices &indices)
 Calls the filtering method and returns the filtered point cloud indices.
 
void setNegative (bool negative)
 Set whether the regular conditions for points filtering should apply, or the inverted conditions.
 
bool getNegative () const
 Get whether the regular conditions for points filtering should apply, or the inverted conditions.
 
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.
 
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.
 
void setUserFilterValue (float value)
 Provide a value that the filtered points should be set to instead of removing them.
 
 FilterIndices (bool extract_removed_indices=false)
 Constructor.
 
void filter (Indices &indices)
 Calls the filtering method and returns the filtered point cloud indices.
 
void setNegative (bool negative)
 Set whether the regular conditions for points filtering should apply, or the inverted conditions.
 
bool getNegative () const
 Get whether the regular conditions for points filtering should apply, or the inverted conditions.
 
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.
 
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.
 
void setUserFilterValue (float value)
 Provide a value that the filtered points should be set to instead of removing them.
 
- Public Member Functions inherited from pcl::Filter< pcl::PCLPointCloud2 >
 Filter (bool extract_removed_indices=false)
 Empty constructor.
 
IndicesConstPtr const getRemovedIndices () const
 Get the point indices being removed.
 
void getRemovedIndices (PointIndices &pi)
 Get the point indices being removed.
 
void filter (PCLPointCloud2 &output)
 Calls the filtering method and returns the filtered dataset in output.
 
 Filter (bool extract_removed_indices=false)
 Empty constructor.
 
IndicesConstPtr const getRemovedIndices () const
 Get the point indices being removed.
 
void getRemovedIndices (PointIndices &pi)
 Get the point indices being removed.
 
void filter (PointCloud &output)
 Calls the filtering method and returns the filtered dataset in output.
 
- Public Member Functions inherited from pcl::PCLBase< pcl::PCLPointCloud2 >
 PCLBase ()
 Empty constructor.
 
virtual ~PCLBase ()=default
 destructor.
 
void setInputCloud (const PCLPointCloud2ConstPtr &cloud)
 Provide a pointer to the input dataset.
 
PCLPointCloud2ConstPtr const getInputCloud () const
 Get a pointer to the input point cloud dataset.
 
void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
 
void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
 
IndicesPtr const getIndices () const
 Get a pointer to the vector of indices used.
 
 PCLBase ()
 Empty constructor.
 
 PCLBase (const PCLBase &base)
 Copy constructor.
 
virtual ~PCLBase ()=default
 Destructor.
 
virtual void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset.
 
PointCloudConstPtr const getInputCloud () const
 Get a pointer to the input point cloud dataset.
 
virtual void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
 
virtual void setIndices (const IndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
 
virtual void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
 
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.
 
IndicesPtr getIndices ()
 Get a pointer to the vector of indices used.
 
IndicesConstPtr const getIndices () const
 Get a pointer to the vector of indices used.
 
const pcl::PCLPointCloud2operator[] (std::size_t pos) const
 Override PointCloud operator[] to shorten code.
 

Protected Types

using PointCloud
 
using PointCloudPtr
 
using PointCloudConstPtr
 
using SearcherPtr
 

Protected Member Functions

void applyFilter (Indices &indices) override
 Abstract filter method for point cloud indices.
 
void applyFilter (PCLPointCloud2 &output) override
 Abstract filter method for point cloud.
 
virtual void generateStatistics (double &mean, double &variance, double &stddev, std::vector< float > &distances)
 Compute the statistical values used in both applyFilter methods.
 
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.
 
- Protected Member Functions inherited from pcl::FilterIndices< pcl::PCLPointCloud2 >
void applyFilter (PointCloud &output) override
 Abstract filter method for point cloud.
 
- Protected Member Functions inherited from pcl::Filter< pcl::PCLPointCloud2 >
const std::string & getClassName () const
 Get a string representation of the name of this class.
 
virtual void applyFilter (PointCloud &output)=0
 Abstract filter method.
 
const std::string & getClassName () const
 Get a string representation of the name of this class.
 
- Protected Member Functions inherited from pcl::PCLBase< pcl::PCLPointCloud2 >
bool initCompute ()
 
bool deinitCompute ()
 
bool initCompute ()
 This method should get called before starting the actual computation.
 
bool deinitCompute ()
 This method should get called after finishing the actual computation.
 

Protected Attributes

int mean_k_ {2}
 The number of points to use for mean distance estimation.
 
double std_mul_ {0.0}
 Standard deviations threshold (i.e., points outside of $ \mu \pm \sigma \cdot std\_mul $ will be marked as outliers).
 
KdTreePtr tree_
 A pointer to the spatial search object.
 
- Protected Attributes inherited from pcl::FilterIndices< pcl::PCLPointCloud2 >
bool negative_ {false}
 False = normal filter behavior (default), true = inverted behavior.
 
bool keep_organized_ {false}
 False = remove points (default), true = redefine points, keep structure.
 
float user_filter_value_
 The user given value that the filtered point dimensions should be set to (default = NaN).
 
bool negative_
 False = normal filter behavior (default), true = inverted behavior.
 
bool keep_organized_
 False = remove points (default), true = redefine points, keep structure.
 
float user_filter_value_
 The user given value that the filtered point dimensions should be set to (default = NaN).
 
- Protected Attributes inherited from pcl::Filter< pcl::PCLPointCloud2 >
IndicesPtr removed_indices_
 Indices of the points that are removed.
 
bool extract_removed_indices_
 Set to true if we want to return the indices of the removed points.
 
std::string filter_name_
 The filter name.
 
IndicesPtr removed_indices_
 Indices of the points that are removed.
 
std::string filter_name_
 The filter name.
 
bool extract_removed_indices_
 Set to true if we want to return the indices of the removed points.
 
- Protected Attributes inherited from pcl::PCLBase< pcl::PCLPointCloud2 >
PCLPointCloud2ConstPtr input_
 The input point cloud dataset.
 
IndicesPtr indices_
 A pointer to the vector of point indices to use.
 
bool use_indices_
 Set to true if point indices are used.
 
bool fake_indices_
 If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud.
 
std::vector< uindex_tfield_sizes_
 The size of each individual field.
 
index_t x_idx_
 The x-y-z fields indices.
 
index_t y_idx_
 
index_t z_idx_
 
std::string x_field_name_
 The desired x-y-z field names.
 
std::string y_field_name_
 
std::string z_field_name_
 
PointCloudConstPtr input_
 The input point cloud dataset.
 
IndicesPtr indices_
 A pointer to the vector of point indices to use.
 
bool use_indices_
 Set to true if point indices are used.
 
bool fake_indices_
 If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud.
 

Detailed Description

StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data.

For more information check:

  • 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.
Author
Radu Bogdan Rusu

Definition at line 198 of file statistical_outlier_removal.h.

Member Typedef Documentation

◆ ConstPtr

◆ PointCloud

◆ PointCloudConstPtr

using pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::PointCloudConstPtr
protected

Definition at line 86 of file statistical_outlier_removal.h.

◆ PointCloudPtr

using pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::PointCloudPtr
protected

Definition at line 85 of file statistical_outlier_removal.h.

◆ Ptr

◆ SearcherPtr

using pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::SearcherPtr
protected

Definition at line 87 of file statistical_outlier_removal.h.

Constructor & Destructor Documentation

◆ StatisticalOutlierRemoval() [1/2]

pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::StatisticalOutlierRemoval ( bool extract_removed_indices = false)
inline

◆ StatisticalOutlierRemoval() [2/2]

pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::StatisticalOutlierRemoval ( bool extract_removed_indices = false)
inline

Constructor.

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

Definition at line 98 of file statistical_outlier_removal.h.

Member Function Documentation

◆ applyFilter() [1/3]

void pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::applyFilter ( Indices & indices)
inlineoverrideprotectedvirtual

Filtered results are indexed by an indices array.

Parameters
[out]indicesThe resultant indices.

Implements pcl::FilterIndices< pcl::PCLPointCloud2 >.

Definition at line 165 of file statistical_outlier_removal.h.

◆ applyFilter() [2/3]

void pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::applyFilter ( Indices & indices)
overrideprotectedvirtual

Abstract filter method for point cloud indices.

Implements pcl::FilterIndices< pcl::PCLPointCloud2 >.

◆ applyFilter() [3/3]

void pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::applyFilter ( PCLPointCloud2 & output)
overrideprotectedvirtual

Abstract filter method for point cloud.

Implements pcl::FilterIndices< pcl::PCLPointCloud2 >.

◆ applyFilterIndices()

void pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::applyFilterIndices ( Indices & indices)
protected

Filtered results are indexed by an indices array.

Parameters
[out]indicesThe resultant indices.

Definition at line 174 of file statistical_outlier_removal.hpp.

◆ generateStatistics()

virtual void pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::generateStatistics ( double & mean,
double & variance,
double & stddev,
std::vector< float > & distances )
protectedvirtual

Compute the statistical values used in both applyFilter methods.

This method tries to avoid duplicate code.

◆ getMeanK() [1/2]

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 118 of file statistical_outlier_removal.h.

◆ getMeanK() [2/2]

Get the number of points to use for mean distance estimation.

Definition at line 232 of file statistical_outlier_removal.h.

References mean_k_.

◆ getStddevMulThresh() [1/2]

double pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::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 139 of file statistical_outlier_removal.h.

◆ getStddevMulThresh() [2/2]

double pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::getStddevMulThresh ( )
inline

Get the standard deviation multiplier threshold as set by the user.

Definition at line 251 of file statistical_outlier_removal.h.

References std_mul_.

◆ setMeanK() [1/2]

void pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::setMeanK ( int nr_k)
inline

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

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

Definition at line 109 of file statistical_outlier_removal.h.

◆ setMeanK() [2/2]

void pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::setMeanK ( int nr_k)
inline

Set the number of points (k) to use for mean distance estimation.

Parameters
nr_kthe number of points to use for mean distance estimation

Definition at line 225 of file statistical_outlier_removal.h.

References mean_k_.

◆ setSearchMethod()

void pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::setSearchMethod ( const SearcherPtr & searcher)
inline

Provide a pointer to the search object.

Calling this is optional. If not called, the search method will be chosen automatically.

Parameters
[in]searchera pointer to the spatial search object.

Definition at line 149 of file statistical_outlier_removal.h.

◆ setStddevMulThresh() [1/2]

void pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::setStddevMulThresh ( double std_mul)
inline

Set the standard deviation multiplier threshold.

All points outside the

\[ \mu \pm \sigma \cdot std\_mul \]

will be considered outliers, where $ \mu $ is the estimated mean, and $ \sigma $ is the standard deviation.

Parameters
std_multhe standard deviation multiplier threshold

Definition at line 244 of file statistical_outlier_removal.h.

References std_mul_.

◆ setStddevMulThresh() [2/2]

void pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::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_multThe standard deviation multiplier.

Definition at line 129 of file statistical_outlier_removal.h.

Member Data Documentation

◆ mean_k_

int pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::mean_k_ {2}
protected

The number of points to use for mean distance estimation.

Definition at line 258 of file statistical_outlier_removal.h.

Referenced by getMeanK(), and setMeanK().

◆ std_mul_

double pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::std_mul_ {0.0}
protected

Standard deviations threshold (i.e., points outside of $ \mu \pm \sigma \cdot std\_mul $ will be marked as outliers).

Definition at line 263 of file statistical_outlier_removal.h.

Referenced by getStddevMulThresh(), and setStddevMulThresh().

◆ tree_

KdTreePtr pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::tree_
protected

A pointer to the spatial search object.

Definition at line 266 of file statistical_outlier_removal.h.


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