Point Cloud Library (PCL)  1.3.1
Public Types | Public Member Functions
pcl::FilterIndices Class Reference

Filter represents the base filter class. More...

#include <pcl/filters/filter_indices.h>

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

List of all members.

Public Types

typedef pcl::PointCloud< PointT > PointCloud
typedef boost::shared_ptr
< Filter< PointT > > 
Ptr
typedef boost::shared_ptr
< const Filter< PointT > > 
ConstPtr
typedef PointCloud::Ptr PointCloudPtr
typedef PointCloud::ConstPtr PointCloudConstPtr

Public Member Functions

virtual void filter (PointCloud &output)
 Calls the filtering method and returns the filtered dataset in output.
void filter (std::vector< int > &indices)
 Calls the filtering method and returns the filtered point cloud indices.
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 ()

Detailed Description

Filter represents the base filter class.

Some generic 3D operations that are applicable to all filters are defined here as static methods.

Author:
Justin Rosen

Member Typedef Documentation

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

Definition at line 75 of file filter.h.

Reimplemented from pcl::Filter< PointT >.

Definition at line 70 of file filter_indices.h.

Definition at line 79 of file filter.h.

Definition at line 78 of file filter.h.

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

Definition at line 74 of file filter.h.


Member Function Documentation

virtual void pcl::FilterIndices::filter ( PointCloud output) [inline, virtual]

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

Parameters:
outputthe resultant filtered point cloud dataset

Reimplemented from pcl::Filter< PointT >.

Definition at line 73 of file filter_indices.h.

void pcl::FilterIndices::filter ( std::vector< int > &  indices) [inline]

Calls the filtering method and returns the filtered point cloud indices.

Parameters:
indicesthe resultant filtered point cloud indices

Definition at line 83 of file filter_indices.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.

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.


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