Public Member Functions | Protected Member Functions

pcl::PassThrough< sensor_msgs::PointCloud2 > 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< sensor_msgs::PointCloud2 >:
Inheritance graph
[legend]
Collaboration diagram for pcl::PassThrough< sensor_msgs::PointCloud2 >:
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 Member Functions

void applyFilter (PointCloud2 &output)
 Abstract filter method.

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


Constructor & Destructor Documentation

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

Constructor.

Definition at line 147 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 >.

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

Definition at line 169 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 163 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 180 of file passthrough.h.


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