Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::Filter< sensor_msgs::PointCloud2 > Class Template Reference

Filter represents the base filter class. All filters must inherit from this interface. More...

#include <filter.h>

Inheritance diagram for pcl::Filter< sensor_msgs::PointCloud2 >:
Inheritance graph
[legend]

List of all members.

Public Types

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

Public Member Functions

 Filter (bool extract_removed_indices=false)
 Empty constructor.
void filter (PointCloud2 &output)
 Calls the filtering method and returns the filtered dataset in output.
IndicesConstPtr const getRemovedIndices ()
 Get the point indices being removed.

Protected Member Functions

virtual void applyFilter (PointCloud2 &output)=0
 Abstract filter method.
const std::string & getClassName () const
 Get a string representation of the name of this class.

Protected Attributes

bool extract_removed_indices_
 Set to true if we want to return the indices of the removed points.
std::string filter_name_
 The filter name.
IndicesPtr removed_indices_
 Indices of the points that are removed.

Detailed Description

template<>
class pcl::Filter< sensor_msgs::PointCloud2 >

Filter represents the base filter class. All filters must inherit from this interface.

Author:
Radu B. Rusu

Definition at line 161 of file filter.h.


Member Typedef Documentation

typedef sensor_msgs::PointCloud2 pcl::Filter< sensor_msgs::PointCloud2 >::PointCloud2
typedef PointCloud2::ConstPtr pcl::Filter< sensor_msgs::PointCloud2 >::PointCloud2ConstPtr
typedef PointCloud2::Ptr pcl::Filter< sensor_msgs::PointCloud2 >::PointCloud2Ptr

Constructor & Destructor Documentation

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

Empty constructor.

Parameters:
[in]extract_removed_indicesset to true if the filtered data indices should be saved in a separate list. Default: false.

Definition at line 172 of file filter.h.


Member Function Documentation

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

Calls the filtering method and returns the filtered dataset in output.

Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()

Parameters:
[out]outputthe resultant filtered point cloud dataset
outputthe resultant filtered point cloud dataset

Reimplemented in pcl::FilterIndices< sensor_msgs::PointCloud2 >.

Definition at line 63 of file filter.cpp.

const std::string& pcl::Filter< sensor_msgs::PointCloud2 >::getClassName ( ) const [inline, protected]

Get a string representation of the name of this class.

Definition at line 214 of file filter.h.

IndicesConstPtr const pcl::Filter< sensor_msgs::PointCloud2 >::getRemovedIndices ( ) [inline]

Get the point indices being removed.

Reimplemented in pcl::FilterIndices< sensor_msgs::PointCloud2 >.

Definition at line 181 of file filter.h.


Member Data Documentation

bool pcl::Filter< sensor_msgs::PointCloud2 >::extract_removed_indices_ [protected]

Set to true if we want to return the indices of the removed points.

Reimplemented in pcl::FilterIndices< sensor_msgs::PointCloud2 >.

Definition at line 198 of file filter.h.

std::string pcl::Filter< sensor_msgs::PointCloud2 >::filter_name_ [protected]

The filter name.

Definition at line 201 of file filter.h.

IndicesPtr pcl::Filter< sensor_msgs::PointCloud2 >::removed_indices_ [protected]

Indices of the points that are removed.

Reimplemented in pcl::FilterIndices< sensor_msgs::PointCloud2 >.

Definition at line 195 of file filter.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:30