Public Member Functions | Protected Member Functions | Protected Attributes | Private Types
pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 > Class Template Reference

StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more information check: More...

#include <statistical_outlier_removal.h>

Inheritance diagram for pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

int getMeanK ()
 Get the number of points to use for mean distance estimation.
bool getNegative ()
 Get the value of the internal negative_ parameter. If true, all points except the input indices will be returned.
double getStddevMulThresh ()
 Get the standard deviation multiplier threshold as set by the user.
void setMeanK (int nr_k)
 Set the number of points (k) to use for mean distance estimation.
void setNegative (bool negative)
 Set whether the indices should be returned, or all points except the indices.
void setStddevMulThresh (double std_mul)
 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.

 StatisticalOutlierRemoval (bool extract_removed_indices=false)
 Empty constructor.

Protected Member Functions

void applyFilter (PointCloud2 &output)
 Abstract filter method.

Protected Attributes

int mean_k_
 The number of points to use for mean distance estimation.
bool negative_
 If true, the outliers will be returned instead of the inliers (default: false).
double std_mul_
 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.

Private Types

typedef pcl::search::Search
< pcl::PointXYZ
KdTree
typedef pcl::search::Search
< pcl::PointXYZ >::Ptr 
KdTreePtr
typedef sensor_msgs::PointCloud2 PointCloud2
typedef PointCloud2::ConstPtr PointCloud2ConstPtr
typedef PointCloud2::Ptr PointCloud2Ptr

Detailed Description

template<>
class pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >

StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more information check:

Note:
setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored.
Author:
Radu Bogdan Rusu

Definition at line 197 of file statistical_outlier_removal.h.


Member Typedef Documentation

typedef pcl::search::Search<pcl::PointXYZ> pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::KdTree [private]

Definition at line 205 of file statistical_outlier_removal.h.

typedef pcl::search::Search<pcl::PointXYZ>::Ptr pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::KdTreePtr [private]

Definition at line 206 of file statistical_outlier_removal.h.

typedef sensor_msgs::PointCloud2 pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::PointCloud2 [private]

Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 208 of file statistical_outlier_removal.h.

typedef PointCloud2::ConstPtr pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::PointCloud2ConstPtr [private]

Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 210 of file statistical_outlier_removal.h.

typedef PointCloud2::Ptr pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::PointCloud2Ptr [private]

Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 209 of file statistical_outlier_removal.h.


Constructor & Destructor Documentation

pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::StatisticalOutlierRemoval ( bool  extract_removed_indices = false) [inline]

Empty constructor.

Definition at line 214 of file statistical_outlier_removal.h.


Member Function Documentation

void pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::applyFilter ( PointCloud2 output) [protected, virtual]

Abstract filter method.

The implementation needs to set output.{data, row_step, point_step, width, height, is_dense}.

Parameters:
[out]outputthe resultant filtered point cloud

Implements pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 46 of file statistical_outlier_removal.cpp.

int pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::getMeanK ( ) [inline]

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

Definition at line 232 of file statistical_outlier_removal.h.

bool pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::getNegative ( ) [inline]

Get the value of the internal negative_ parameter. If true, all points except the input indices will be returned.

Returns:
The value of the "negative" flag

Definition at line 270 of file statistical_outlier_removal.h.

double pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::getStddevMulThresh ( ) [inline]

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

Definition at line 251 of file statistical_outlier_removal.h.

void pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::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.

void pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::setNegative ( bool  negative) [inline]

Set whether the indices should be returned, or all points except the indices.

Parameters:
negativetrue if all points except the input indices will be returned, false otherwise

Definition at line 260 of file statistical_outlier_removal.h.

void pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::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.


Member Data Documentation

int pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::mean_k_ [protected]

The number of points to use for mean distance estimation.

Definition at line 277 of file statistical_outlier_removal.h.

bool pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::negative_ [protected]

If true, the outliers will be returned instead of the inliers (default: false).

Definition at line 288 of file statistical_outlier_removal.h.

double pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::std_mul_ [protected]

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

Definition at line 282 of file statistical_outlier_removal.h.

KdTreePtr pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >::tree_ [protected]

A pointer to the spatial search object.

Definition at line 285 of file statistical_outlier_removal.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:17