pcl::Filter< PointT > Class Template Reference

Filter represents the base filter class. Some generic 3D operations that are applicable to all filters are defined here as static methods. More...

#include <filter.h>

Inheritance diagram for pcl::Filter< PointT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef pcl::PointCloud< PointT > PointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr

Public Member Functions

void filter (PointCloud &output)
 Calls the filtering method and returns the filtered dataset in output.
 Filter ()
 Empty constructor.
std::string const getFilterFieldName ()
 Get the name of the field used for filtering.
void getFilterLimits (double &limit_min, double &limit_max)
 Get the field filter limits (min/max) set by the user. The default values are -FLT_MAX, FLT_MAX.
bool getFilterLimitsNegative ()
void getFilterLimitsNegative (bool &limit_negative)
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
void setFilterFieldName (const std::string &field_name)
 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.
void setFilterLimits (const double &limit_min, const double &limit_max)
 Set the field filter limits. All points having field values outside this interval will be discarded.
void setFilterLimitsNegative (const bool limit_negative)
 Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). Default: false.

Protected Member Functions

virtual void applyFilter (PointCloud &output)=0
 Abstract filter method.
const std::string & getClassName () const
 Get a string representation of the name of this class.

Protected Attributes

std::string filter_field_name_
 The desired user filter field name.
double filter_limit_max_
 The maximum allowed filter value a point will be considered from.
double filter_limit_min_
 The minimum allowed filter value a point will be considered from.
bool filter_limit_negative_
 Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false.
std::string filter_name_
 The filter name.

Detailed Description

template<typename PointT>
class pcl::Filter< PointT >

Filter represents the base filter class. Some generic 3D operations that are applicable to all filters are defined here as static methods.

Author:
Radu Bogdan Rusu

Definition at line 62 of file filter.h.


Member Typedef Documentation

template<typename PointT>
typedef pcl::PointCloud<PointT> pcl::Filter< PointT >::PointCloud
template<typename PointT>
typedef PointCloud::ConstPtr pcl::Filter< PointT >::PointCloudConstPtr
template<typename PointT>
typedef PointCloud::Ptr pcl::Filter< PointT >::PointCloudPtr

Constructor & Destructor Documentation

template<typename PointT>
pcl::Filter< PointT >::Filter (  )  [inline]

Empty constructor.

Definition at line 76 of file filter.h.


Member Function Documentation

template<typename PointT>
virtual void pcl::Filter< PointT >::applyFilter ( PointCloud output  )  [protected, pure virtual]
template<typename PointT>
void pcl::Filter< PointT >::filter ( PointCloud output  )  [inline]

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

Parameters:
output the resultant filtered point cloud dataset

Definition at line 124 of file filter.h.

template<typename PointT>
const std::string& pcl::Filter< PointT >::getClassName (  )  const [inline, protected]

Get a string representation of the name of this class.

Definition at line 166 of file filter.h.

template<typename PointT>
std::string const pcl::Filter< PointT >::getFilterFieldName (  )  [inline]

Get the name of the field used for filtering.

Definition at line 89 of file filter.h.

template<typename PointT>
void pcl::Filter< PointT >::getFilterLimits ( double &  limit_min,
double &  limit_max 
) [inline]

Get the field filter limits (min/max) set by the user. The default values are -FLT_MAX, FLT_MAX.

Definition at line 104 of file filter.h.

template<typename PointT>
bool pcl::Filter< PointT >::getFilterLimitsNegative (  )  [inline]

Definition at line 118 of file filter.h.

template<typename PointT>
void pcl::Filter< PointT >::getFilterLimitsNegative ( bool &  limit_negative  )  [inline]

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

Definition at line 117 of file filter.h.

template<typename PointT>
void pcl::Filter< PointT >::setFilterFieldName ( const std::string &  field_name  )  [inline]

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_name the name of the field that contains values used for filtering

Definition at line 86 of file filter.h.

template<typename PointT>
void pcl::Filter< PointT >::setFilterLimits ( const double &  limit_min,
const double &  limit_max 
) [inline]

Set the field filter limits. All points having field values outside this interval will be discarded.

Parameters:
limit_min the minimum allowed field value
limit_max the maximum allowed field value

Definition at line 96 of file filter.h.

template<typename PointT>
void pcl::Filter< PointT >::setFilterLimitsNegative ( const bool  limit_negative  )  [inline]

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

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

Definition at line 114 of file filter.h.


Member Data Documentation

template<typename PointT>
std::string pcl::Filter< PointT >::filter_field_name_ [protected]

The desired user filter field name.

Definition at line 148 of file filter.h.

template<typename PointT>
double pcl::Filter< PointT >::filter_limit_max_ [protected]

The maximum allowed filter value a point will be considered from.

Definition at line 154 of file filter.h.

template<typename PointT>
double pcl::Filter< PointT >::filter_limit_min_ [protected]

The minimum allowed filter value a point will be considered from.

Definition at line 151 of file filter.h.

template<typename PointT>
bool pcl::Filter< PointT >::filter_limit_negative_ [protected]

Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false.

Definition at line 157 of file filter.h.

template<typename PointT>
std::string pcl::Filter< PointT >::filter_name_ [protected]

The filter name.

Definition at line 145 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


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