pcl::PassThrough< pcl::PCLPointCloud2 > 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< pcl::PCLPointCloud2 >:
Inheritance graph
[legend]
Collaboration diagram for pcl::PassThrough< pcl::PCLPointCloud2 >:
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 ()
 Obtain the value of the internal keep_organized_ parameter.
void setUserFilterValue (float val)
 Provide a value that the filtered points should be set to instead of removing them.
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 ()
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).

Protected Member Functions

void applyFilter (PCLPointCloud2 &output)
 Abstract filter method.

Detailed Description

template<>
class pcl::PassThrough< pcl::PCLPointCloud2 >

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

Author:
Radu B. Rusu

Definition at line 229 of file passthrough.h.


Constructor & Destructor Documentation

pcl::PassThrough< pcl::PCLPointCloud2 >::PassThrough ( bool  extract_removed_indices = false  )  [inline]

Constructor.

Definition at line 240 of file passthrough.h.


Member Function Documentation

void pcl::PassThrough< pcl::PCLPointCloud2 >::applyFilter ( PCLPointCloud2 output  )  [protected, virtual]

Abstract filter method.

The implementation needs to set output.{data, row_step, point_step, width, height, is_dense}.

Parameters:
[out] output the resultant filtered point cloud

Implements pcl::Filter< pcl::PCLPointCloud2 >.

std::string const pcl::PassThrough< pcl::PCLPointCloud2 >::getFilterFieldName (  )  [inline]

Get the name of the field used for filtering.

Definition at line 293 of file passthrough.h.

void pcl::PassThrough< pcl::PCLPointCloud2 >::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.

Parameters:
[out] limit_min the minimum allowed field value
[out] limit_max the maximum allowed field value

Definition at line 314 of file passthrough.h.

bool pcl::PassThrough< pcl::PCLPointCloud2 >::getFilterLimitsNegative (  )  [inline]

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

Returns:
true if data outside the interval [min; max] is to be returned, false otherwise

Definition at line 343 of file passthrough.h.

void pcl::PassThrough< pcl::PCLPointCloud2 >::getFilterLimitsNegative ( bool &  limit_negative  )  [inline]

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

Parameters:
[out] limit_negative true if data outside the interval [min; max] is to be returned, false otherwise

Definition at line 334 of file passthrough.h.

bool pcl::PassThrough< pcl::PCLPointCloud2 >::getKeepOrganized (  )  [inline]

Obtain the value of the internal keep_organized_ parameter.

Definition at line 265 of file passthrough.h.

void pcl::PassThrough< pcl::PCLPointCloud2 >::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:
[in] field_name the name of the field that contains values used for filtering

Definition at line 286 of file passthrough.h.

void pcl::PassThrough< pcl::PCLPointCloud2 >::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:
[in] limit_min the minimum allowed field value
[in] limit_max the maximum allowed field value

Definition at line 303 of file passthrough.h.

void pcl::PassThrough< pcl::PCLPointCloud2 >::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:
[in] limit_negative return data inside the interval (false) or outside (true)

Definition at line 325 of file passthrough.h.

void pcl::PassThrough< pcl::PCLPointCloud2 >::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:
[in] val set to true whether the filtered points should be kept and set to a given user value (default: NaN)

Definition at line 258 of file passthrough.h.

void pcl::PassThrough< pcl::PCLPointCloud2 >::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:
[in] val the user given value that the filtered point dimensions should be set to

Definition at line 276 of file passthrough.h.


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