Public Member Functions | Protected Types | Protected Member Functions

pcl::PassThrough< PointT > Class Template Reference
[Module filters]

PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints. More...

#include <pcl/filters/passthrough.h>

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

List of all members.

Public Member Functions

 PassThrough (bool extract_removed_indices=false)
 Constructor.
void setKeepOrganized (bool val)
 Set whether the filtered points should be kept and set to the value given through setUserFilterValue (default: NaN), or removed from the PointCloud, thus potentially breaking its organized structure.
bool getKeepOrganized ()
void setUserFilterValue (float val)
 Provide a value that the filtered points should be set to instead of removing them.

Protected Types

typedef pcl::traits::fieldList
< PointT >::type 
FieldList

Protected Member Functions

void applyFilter (PointCloud &output)
 Filter a Point Cloud.

Detailed Description

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

PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints.

Author:
Radu Bogdan Rusu

Definition at line 52 of file passthrough.h.


Member Typedef Documentation

template<typename PointT >
typedef pcl::traits::fieldList<PointT>::type pcl::PassThrough< PointT >::FieldList [protected]

Definition at line 115 of file passthrough.h.


Constructor & Destructor Documentation

template<typename PointT >
pcl::PassThrough< PointT >::PassThrough ( bool  extract_removed_indices = false  )  [inline]

Constructor.

Definition at line 71 of file passthrough.h.


Member Function Documentation

template<typename PointT >
void pcl::PassThrough< PointT >::applyFilter ( PointCloud output  )  [protected, virtual]

Filter a Point Cloud.

Parameters:
output the resultant point cloud message

Implements pcl::Filter< PointT >.

Definition at line 46 of file passthrough.hpp.

template<typename PointT >
bool pcl::PassThrough< PointT >::getKeepOrganized (  )  [inline]

Definition at line 93 of file passthrough.h.

template<typename PointT >
void pcl::PassThrough< PointT >::setKeepOrganized ( bool  val  )  [inline]

Set whether the filtered points should be kept and set to the value given through setUserFilterValue (default: NaN), or removed from the PointCloud, thus potentially breaking its organized structure.

By default, points are removed.

Parameters:
val set to true whether the filtered points should be kept and set to a given user value (default: NaN)

Definition at line 87 of file passthrough.h.

template<typename PointT >
void pcl::PassThrough< PointT >::setUserFilterValue ( float  val  )  [inline]

Provide a value that the filtered points should be set to instead of removing them.

Used in conjunction with setKeepOrganized ().

Parameters:
val the user given value that the filtered point dimensions should be set to

Definition at line 104 of file passthrough.h.


The documentation for this class was generated from the following files: