pcl::ExtractIndices< sensor_msgs::PointCloud2 > 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< sensor_msgs::PointCloud2 >:
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 (PointCloud2 &output)
 Abstract filter method.

Protected Attributes

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

Private Types

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

Detailed Description

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

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 104 of file extract_indices.h.


Member Typedef Documentation

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

Definition at line 109 of file extract_indices.h.

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

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

Definition at line 111 of file extract_indices.h.

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

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

Definition at line 110 of file extract_indices.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 116 of file extract_indices.h.


Member Function Documentation

void pcl::ExtractIndices< 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 extract_indices.cpp.

bool pcl::ExtractIndices< sensor_msgs::PointCloud2 >::getNegative (  )  [inline]

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

Definition at line 131 of file extract_indices.h.

void pcl::ExtractIndices< sensor_msgs::PointCloud2 >::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 126 of file extract_indices.h.


Member Data Documentation

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

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