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

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

#include <passthrough.h>

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

List of all members.

Public Member Functions

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.
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).
bool getKeepOrganized ()
 Obtain the value of the internal keep_organized_ parameter.
 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. 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.
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. By default, points are removed.
void setUserFilterValue (float val)
 Provide a value that the filtered points should be set to instead of removing them. Used in conjunction with setKeepOrganized ().

Protected Member Functions

void applyFilter (PCLPointCloud2 &output)
 Abstract filter method.

Private Types

typedef pcl::PCLPointCloud2 PCLPointCloud2
typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr
typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr

Private 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.
bool keep_organized_
 Keep the structure of the data organized, by setting the filtered points to the a user given value (NaN by default).
float user_filter_value_
 User given value to be set to any filtered point. Casted to the correct field type.

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.


Member Typedef Documentation

Reimplemented from pcl::Filter< pcl::PCLPointCloud2 >.

Definition at line 231 of file passthrough.h.

Reimplemented from pcl::Filter< pcl::PCLPointCloud2 >.

Definition at line 233 of file passthrough.h.

Reimplemented from pcl::Filter< pcl::PCLPointCloud2 >.

Definition at line 232 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]outputthe resultant filtered point cloud

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

Definition at line 45 of file filters/src/passthrough.cpp.

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_minthe minimum allowed field value
[out]limit_maxthe maximum allowed field value

Definition at line 314 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_negativetrue if data outside the interval [min; max] is to be returned, false otherwise

Definition at line 334 of file passthrough.h.

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.

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_namethe 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_minthe minimum allowed field value
[in]limit_maxthe 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_negativereturn 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]valset 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]valthe user given value that the filtered point dimensions should be set to

Definition at line 276 of file passthrough.h.


Member Data Documentation

The desired user filter field name.

Definition at line 364 of file passthrough.h.

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

Definition at line 370 of file passthrough.h.

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

Definition at line 367 of file passthrough.h.

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

Definition at line 373 of file passthrough.h.

Keep the structure of the data organized, by setting the filtered points to the a user given value (NaN by default).

Definition at line 356 of file passthrough.h.

User given value to be set to any filtered point. Casted to the correct field type.

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