Point Cloud Library (PCL)  1.3.1
Public Types | Public Member Functions
pcl::RadiusOutlierRemoval Class 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 <pcl/filters/radius_outlier_removal.h>

Inheritance diagram for pcl::RadiusOutlierRemoval:
Inheritance graph
[legend]
Collaboration diagram for pcl::RadiusOutlierRemoval:
Collaboration graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< Filter< PointT > > 
Ptr
typedef boost::shared_ptr
< const Filter< PointT > > 
ConstPtr

Public Member Functions

 RadiusOutlierRemoval (bool extract_removed_indices=false)
 Empty constructor.
void setRadiusSearch (double radius)
 Set the sphere radius that is to be used for determining the k-nearest neighbors for filtering.
double getRadiusSearch ()
 Get the sphere radius used for determining the k-nearest neighbors.
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).
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.
IndicesConstPtr const getRemovedIndices ()
 Get the point indices being removed.
void setFilterFieldName (const std::string &field_name)
 Provide the name of the field to be used for filtering data.
std::string const getFilterFieldName ()
 Get the name of the field used for filtering.
void setFilterLimits (const double &limit_min, const double &limit_max)
 Set the field filter limits.
void getFilterLimits (double &limit_min, double &limit_max)
 Get the field filter limits (min/max) set by the user.
void setFilterLimitsNegative (const bool limit_negative)
 Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max).
void getFilterLimitsNegative (bool &limit_negative)
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
bool getFilterLimitsNegative ()
void filter (PointCloud &output)
 Calls the filtering method and returns the filtered dataset in output.

Detailed Description

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

Member Typedef Documentation

typedef boost::shared_ptr< const Filter<PointT> > pcl::Filter::ConstPtr [inherited]

Definition at line 75 of file filter.h.

typedef boost::shared_ptr< Filter<PointT> > pcl::Filter::Ptr [inherited]

Definition at line 74 of file filter.h.


Constructor & Destructor Documentation

pcl::RadiusOutlierRemoval::RadiusOutlierRemoval ( bool  extract_removed_indices = false) [inline]

Empty constructor.

Definition at line 74 of file radius_outlier_removal.h.


Member Function Documentation

void pcl::Filter::filter ( PointCloud output) [inline, inherited]

Calls the filtering method and returns the filtered dataset in output.

Parameters:
outputthe resultant filtered point cloud dataset

Reimplemented in pcl::FilterIndices.

Definition at line 160 of file filter.h.

std::string const pcl::Filter::getFilterFieldName ( ) [inline, inherited]

Get the name of the field used for filtering.

Definition at line 110 of file filter.h.

void pcl::Filter::getFilterLimits ( double &  limit_min,
double &  limit_max 
) [inline, inherited]

Get the field filter limits (min/max) set by the user.

The default values are -FLT_MAX, FLT_MAX.

Definition at line 128 of file filter.h.

void pcl::Filter::getFilterLimitsNegative ( bool &  limit_negative) [inline, inherited]

Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).

Definition at line 146 of file filter.h.

bool pcl::Filter::getFilterLimitsNegative ( ) [inline, inherited]

Definition at line 151 of file filter.h.

double pcl::RadiusOutlierRemoval::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 111 of file radius_outlier_removal.h.

double pcl::RadiusOutlierRemoval::getRadiusSearch ( ) [inline]

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

Definition at line 92 of file radius_outlier_removal.h.

IndicesConstPtr const pcl::Filter::getRemovedIndices ( ) [inline, inherited]

Get the point indices being removed.

Definition at line 93 of file filter.h.

void pcl::Filter::setFilterFieldName ( const std::string &  field_name) [inline, inherited]

Provide the name of the field to be used for filtering data.

In conjunction with setFilterLimits, points having values outside this interval will be discarded.

Parameters:
field_namethe name of the field that contains values used for filtering

Definition at line 103 of file filter.h.

void pcl::Filter::setFilterLimits ( const double &  limit_min,
const double &  limit_max 
) [inline, inherited]

Set the field filter limits.

All points having field values outside this interval will be discarded.

Parameters:
limit_minthe minimum allowed field value
limit_maxthe maximum allowed field value

Definition at line 120 of file filter.h.

void pcl::Filter::setFilterLimitsNegative ( const bool  limit_negative) [inline, inherited]

Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max).

Default: false.

Parameters:
limit_negativereturn data inside the interval (false) or outside (true)

Definition at line 139 of file filter.h.

void pcl::RadiusOutlierRemoval::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 102 of file radius_outlier_removal.h.

void pcl::RadiusOutlierRemoval::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 85 of file radius_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