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

RadiusOutlierRemoval is a simple filter that removes outliers if the number of neighbors in a certain search radius is smaller than a given K. More...

#include <radius_outlier_removal.h>

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

List of all members.

Public Member Functions

double getMinNeighborsInRadius ()
 Get the minimum number of neighbors that a point needs to have in the given search radius to be considered an inlier and avoid being filtered.
double getRadiusSearch ()
 Get the sphere radius used for determining the k-nearest neighbors.
 RadiusOutlierRemoval (bool extract_removed_indices=false)
 Empty constructor.
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 be considered an inlier (i.e., valid).
void setRadiusSearch (double radius)
 Set the sphere radius that is to be used for determining the k-nearest neighbors for filtering.

Protected Member Functions

void applyFilter (PointCloud2 &output)
 Abstract filter method.

Protected Attributes

int min_pts_radius_
 The minimum number of neighbors that a point needs to have in the given search radius to be considered an inlier.
double search_radius_
 The nearest neighbors search radius for each point.
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::RadiusOutlierRemoval< sensor_msgs::PointCloud2 >

RadiusOutlierRemoval is a simple filter that removes outliers if the number of neighbors in a certain search radius is smaller than a given K.

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

Definition at line 188 of file radius_outlier_removal.h.


Member Typedef Documentation

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

Definition at line 196 of file radius_outlier_removal.h.

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

Definition at line 197 of file radius_outlier_removal.h.

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

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

Definition at line 199 of file radius_outlier_removal.h.

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

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

Definition at line 201 of file radius_outlier_removal.h.

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

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

Definition at line 200 of file radius_outlier_removal.h.


Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 205 of file radius_outlier_removal.h.


Member Function Documentation

void pcl::RadiusOutlierRemoval< 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 filters/src/radius_outlier_removal.cpp.

double pcl::RadiusOutlierRemoval< sensor_msgs::PointCloud2 >::getMinNeighborsInRadius ( ) [inline]

Get the minimum number of neighbors that a point needs to have in the given search radius to be considered an inlier and avoid being filtered.

Definition at line 242 of file radius_outlier_removal.h.

double pcl::RadiusOutlierRemoval< sensor_msgs::PointCloud2 >::getRadiusSearch ( ) [inline]

Get the sphere radius used for determining the k-nearest neighbors.

Definition at line 223 of file radius_outlier_removal.h.

void pcl::RadiusOutlierRemoval< sensor_msgs::PointCloud2 >::setMinNeighborsInRadius ( int  min_pts) [inline]

Set the minimum number of neighbors that a point needs to have in the given search radius in order to be considered an inlier (i.e., valid).

Parameters:
min_ptsthe minimum number of neighbors

Definition at line 233 of file radius_outlier_removal.h.

void pcl::RadiusOutlierRemoval< sensor_msgs::PointCloud2 >::setRadiusSearch ( double  radius) [inline]

Set the sphere radius that is to be used for determining the k-nearest neighbors for filtering.

Parameters:
radiusthe sphere radius that is to contain all k-nearest neighbors

Definition at line 216 of file radius_outlier_removal.h.


Member Data Documentation

int pcl::RadiusOutlierRemoval< sensor_msgs::PointCloud2 >::min_pts_radius_ [protected]

The minimum number of neighbors that a point needs to have in the given search radius to be considered an inlier.

Definition at line 254 of file radius_outlier_removal.h.

double pcl::RadiusOutlierRemoval< sensor_msgs::PointCloud2 >::search_radius_ [protected]

The nearest neighbors search radius for each point.

Definition at line 249 of file radius_outlier_removal.h.

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

A pointer to the spatial search object.

Definition at line 257 of file radius_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:19:58