pcl::ExtractIndices< PointT > Class Template Reference

ExtractIndices extracts a set of indices from a PointCloud as a separate PointCloud. More...

#include <extract_indices.h>

Inheritance diagram for pcl::ExtractIndices< PointT >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 ExtractIndices ()
 Empty constructor.
bool getNegative ()
 Get the value of the internal negative parameter. If true, all points _except_ the input indices will be returned.
void setNegative (bool negative)
 Set whether the indices should be returned, or all points _except_ the indices.

Protected Member Functions

void applyFilter (PointCloud &output)
 Extract point indices into a separate PointCloud.

Protected Attributes

bool negative_
 If true, all the points _except_ the input indices will be returned. False by default.

Private Types

typedef Filter< PointT >
::PointCloud 
PointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr

Detailed Description

template<typename PointT>
class pcl::ExtractIndices< PointT >

ExtractIndices extracts a set of indices from a PointCloud as a separate PointCloud.

Note:
setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored.
Author:
Radu Bogdan Rusu

Definition at line 53 of file extract_indices.h.


Member Typedef Documentation

template<typename PointT>
typedef Filter<PointT>::PointCloud pcl::ExtractIndices< PointT >::PointCloud [private]

Reimplemented from pcl::Filter< PointT >.

Definition at line 61 of file extract_indices.h.

template<typename PointT>
typedef PointCloud::ConstPtr pcl::ExtractIndices< PointT >::PointCloudConstPtr [private]

Reimplemented from pcl::Filter< PointT >.

Definition at line 63 of file extract_indices.h.

template<typename PointT>
typedef PointCloud::Ptr pcl::ExtractIndices< PointT >::PointCloudPtr [private]

Reimplemented from pcl::Filter< PointT >.

Definition at line 62 of file extract_indices.h.


Constructor & Destructor Documentation

template<typename PointT>
pcl::ExtractIndices< PointT >::ExtractIndices (  )  [inline]

Empty constructor.

Definition at line 68 of file extract_indices.h.


Member Function Documentation

template<typename PointT >
void pcl::ExtractIndices< PointT >::applyFilter ( PointCloud output  )  [inline, protected, virtual]

Extract point indices into a separate PointCloud.

Parameters:
output the resultant point cloud message

Implements pcl::Filter< PointT >.

Definition at line 46 of file extract_indices.hpp.

template<typename PointT>
bool pcl::ExtractIndices< PointT >::getNegative (  )  [inline]

Get the value of the internal negative parameter. If true, all points _except_ the input indices will be returned.

Definition at line 83 of file extract_indices.h.

template<typename PointT>
void pcl::ExtractIndices< PointT >::setNegative ( bool  negative  )  [inline]

Set whether the indices should be returned, or all points _except_ the indices.

Parameters:
negative true if all points _except_ the input indices will be returned, false otherwise

Definition at line 78 of file extract_indices.h.


Member Data Documentation

template<typename PointT>
bool pcl::ExtractIndices< PointT >::negative_ [protected]

If true, all the points _except_ the input indices will be returned. False by default.

Definition at line 93 of file extract_indices.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:17 2013