Public Types | Public Member Functions | Protected Types | Protected Member Functions | Private Attributes
pcl::PassThrough< PointT > Class Template Reference

PassThrough passes points in a cloud based on constraints for one particular field of the point type. More...

#include <passthrough.h>

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

List of all members.

Public Types

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

Public Member Functions

std::string const getFilterFieldName ()
 Retrieve the name of the field to be used for filtering data.
void getFilterLimits (float &limit_min, float &limit_max)
 Get the numerical limits for the field for filtering data.
void getFilterLimitsNegative (bool &limit_negative)
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
bool getFilterLimitsNegative ()
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
 PassThrough (bool extract_removed_indices=false)
 Constructor.
void setFilterFieldName (const std::string &field_name)
 Provide the name of the field to be used for filtering data.
void setFilterLimits (const float &limit_min, const float &limit_max)
 Set the numerical limits for the field for filtering data.
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 Types

typedef pcl::traits::fieldList
< PointT >::type 
FieldList
typedef FilterIndices< PointT >
::PointCloud 
PointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr

Protected Member Functions

void applyFilter (PointCloud &output)
 Filtered results are stored in a separate point cloud.
void applyFilter (std::vector< int > &indices)
 Filtered results are indexed by an indices array.
void applyFilterIndices (std::vector< int > &indices)
 Filtered results are indexed by an indices array.

Private Attributes

std::string filter_field_name_
 The name of the field that will be used for filtering.
float filter_limit_max_
 The maximum allowed field value (default = FLT_MIN).
float filter_limit_min_
 The minimum allowed field value (default = FLT_MIN).

Detailed Description

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

PassThrough passes points in a cloud based on constraints for one particular field of the point type.

Iterates through the entire input once, automatically filtering non-finite points and the points outside the interval specified by setFilterLimits(), which applies only to the field specified by setFilterFieldName().

Usage example:

 pcl::PassThrough<PointType> ptfilter (true); // Initializing with true will allow us to extract the removed indices
 ptfilter.setInputCloud (cloud_in);
 ptfilter.setFilterFieldName ("x");
 ptfilter.setFilterLimits (0.0, 1000.0);
 ptfilter.filter (*indices_x);
 // The indices_x array indexes all points of cloud_in that have x between 0.0 and 1000.0
 indices_rem = ptfilter.getRemovedIndices ();
 // The indices_rem array indexes all points of cloud_in that have x smaller than 0.0 or larger than 1000.0
 // and also indexes all non-finite points of cloud_in
 ptfilter.setIndices (indices_x);
 ptfilter.setFilterFieldName ("z");
 ptfilter.setFilterLimits (-10.0, 10.0);
 ptfilter.setNegative (true);
 ptfilter.filter (*indices_xz);
 // The indices_xz array indexes all points of cloud_in that have x between 0.0 and 1000.0 and z larger than 10.0 or smaller than -10.0
 ptfilter.setIndices (indices_xz);
 ptfilter.setFilterFieldName ("intensity");
 ptfilter.setFilterLimits (FLT_MIN, 0.5);
 ptfilter.setNegative (false);
 ptfilter.filter (*cloud_out);
 // The resulting cloud_out contains all points of cloud_in that are finite and have:
 // x between 0.0 and 1000.0, z larger than 10.0 or smaller than -10.0 and intensity smaller than 0.5.
Author:
Radu Bogdan Rusu

Definition at line 80 of file passthrough.h.


Member Typedef Documentation

template<typename PointT>
typedef boost::shared_ptr< const PassThrough<PointT> > pcl::PassThrough< PointT >::ConstPtr

Reimplemented from pcl::FilterIndices< PointT >.

Definition at line 91 of file passthrough.h.

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

Definition at line 86 of file passthrough.h.

template<typename PointT>
typedef FilterIndices<PointT>::PointCloud pcl::PassThrough< PointT >::PointCloud [protected]

Reimplemented from pcl::FilterIndices< PointT >.

Definition at line 83 of file passthrough.h.

template<typename PointT>
typedef PointCloud::ConstPtr pcl::PassThrough< PointT >::PointCloudConstPtr [protected]

Reimplemented from pcl::Filter< PointT >.

Definition at line 85 of file passthrough.h.

template<typename PointT>
typedef PointCloud::Ptr pcl::PassThrough< PointT >::PointCloudPtr [protected]

Reimplemented from pcl::Filter< PointT >.

Definition at line 84 of file passthrough.h.

template<typename PointT>
typedef boost::shared_ptr< PassThrough<PointT> > pcl::PassThrough< PointT >::Ptr

Reimplemented from pcl::FilterIndices< PointT >.

Definition at line 90 of file passthrough.h.


Constructor & Destructor Documentation

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

Constructor.

Parameters:
[in]extract_removed_indicesSet to true if you want to be able to extract the indices of points being removed (default = false).

Definition at line 97 of file passthrough.h.


Member Function Documentation

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

Filtered results are stored in a separate point cloud.

Parameters:
[out]outputThe resultant point cloud.

Implements pcl::Filter< PointT >.

Definition at line 48 of file passthrough.hpp.

template<typename PointT>
void pcl::PassThrough< PointT >::applyFilter ( std::vector< int > &  indices) [inline, protected, virtual]

Filtered results are indexed by an indices array.

Parameters:
[out]indicesThe resultant indices.

Implements pcl::FilterIndices< PointT >.

Definition at line 200 of file passthrough.h.

template<typename PointT >
void pcl::PassThrough< PointT >::applyFilterIndices ( std::vector< int > &  indices) [protected]

Filtered results are indexed by an indices array.

Parameters:
[out]indicesThe resultant indices.

Definition at line 74 of file passthrough.hpp.

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

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

Returns:
The name of the field that will be used for filtering.

Definition at line 120 of file passthrough.h.

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

Get the numerical limits for the field for filtering data.

Parameters:
[out]limit_minThe minimum allowed field value (default = FLT_MIN).
[out]limit_maxThe maximum allowed field value (default = FLT_MAX).

Definition at line 142 of file passthrough.h.

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

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

Warning:
This method will be removed in the future. Use getNegative() instead.
Parameters:
[out]limit_negativetrue if data outside the interval [min; max] is to be returned, false otherwise

Definition at line 164 of file passthrough.h.

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

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

Warning:
This method will be removed in the future. Use getNegative() instead.
Returns:
true if data outside the interval [min; max] is to be returned, false otherwise

Definition at line 174 of file passthrough.h.

template<typename PointT>
void pcl::PassThrough< 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 for this field will be discarded.

Parameters:
[in]field_nameThe name of the field that will be used for filtering.

Definition at line 111 of file passthrough.h.

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

Set the numerical limits for the field for filtering data.

In conjunction with setFilterFieldName(), points having values outside this interval for this field will be discarded.

Parameters:
[in]limit_minThe minimum allowed field value (default = FLT_MIN).
[in]limit_maxThe maximum allowed field value (default = FLT_MAX).

Definition at line 131 of file passthrough.h.

template<typename PointT>
void pcl::PassThrough< 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.

Warning:
This method will be removed in the future. Use setNegative() instead.
Parameters:
[in]limit_negativereturn data inside the interval (false) or outside (true)

Definition at line 154 of file passthrough.h.


Member Data Documentation

template<typename PointT>
std::string pcl::PassThrough< PointT >::filter_field_name_ [private]

The name of the field that will be used for filtering.

Definition at line 213 of file passthrough.h.

template<typename PointT>
float pcl::PassThrough< PointT >::filter_limit_max_ [private]

The maximum allowed field value (default = FLT_MIN).

Definition at line 219 of file passthrough.h.

template<typename PointT>
float pcl::PassThrough< PointT >::filter_limit_min_ [private]

The minimum allowed field value (default = FLT_MIN).

Definition at line 216 of file passthrough.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:42:48