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 ()
 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::KdTree
< pcl::PointXYZ
KdTree
typedef pcl::KdTree
< 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 143 of file statistical_outlier_removal.h.


Member Typedef Documentation

Definition at line 148 of file statistical_outlier_removal.h.

Definition at line 149 of file statistical_outlier_removal.h.

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

Definition at line 151 of file statistical_outlier_removal.h.

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

Definition at line 153 of file statistical_outlier_removal.h.

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

Definition at line 152 of file statistical_outlier_removal.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 157 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}.

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 168 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.

Definition at line 189 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 179 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_k the number of points to use for mean distance estimation

Definition at line 165 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:
negative true if all points _except_ the input indices will be returned, false otherwise

Definition at line 184 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_mul the standard deviation multiplier threshold

Definition at line 176 of file statistical_outlier_removal.h.


Member Data Documentation

The number of points to use for mean distance estimation.

Definition at line 193 of file statistical_outlier_removal.h.

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

Definition at line 203 of file statistical_outlier_removal.h.

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

Definition at line 197 of file statistical_outlier_removal.h.

A pointer to the spatial search object.

Definition at line 200 of file statistical_outlier_removal.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:23 2013