pcl::PassThrough< sensor_msgs::PointCloud2 > 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< sensor_msgs::PointCloud2 >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool getKeepOrganized ()
 PassThrough ()
 Empty 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. 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 (PointCloud2 &output)
 Abstract filter method.

Private Types

typedef sensor_msgs::PointCloud2 PointCloud2
typedef PointCloud2::ConstPtr PointCloud2ConstPtr
typedef PointCloud2::Ptr PointCloud2Ptr

Private Attributes

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< sensor_msgs::PointCloud2 >

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 115 of file passthrough.h.


Member Typedef Documentation

Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 117 of file passthrough.h.

typedef PointCloud2::ConstPtr pcl::PassThrough< sensor_msgs::PointCloud2 >::PointCloud2ConstPtr [private]

Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 119 of file passthrough.h.

typedef PointCloud2::Ptr pcl::PassThrough< sensor_msgs::PointCloud2 >::PointCloud2Ptr [private]

Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 118 of file passthrough.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 123 of file passthrough.h.


Member Function Documentation

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

Abstract filter method.

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

Implements pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 45 of file passthrough.cpp.

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

Definition at line 139 of file passthrough.h.

void pcl::PassThrough< sensor_msgs::PointCloud2 >::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 137 of file passthrough.h.

void pcl::PassThrough< sensor_msgs::PointCloud2 >::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 146 of file passthrough.h.


Member Data Documentation

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

Definition at line 154 of file passthrough.h.

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

Definition at line 158 of file passthrough.h.


The documentation for this class was generated from the following files:
 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:20 2013