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

ExtractIndices extracts a set of indices from a point cloud.
Usage examples: More...

#include <extract_indices.h>

Inheritance diagram for pcl::ExtractIndices< 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

 ExtractIndices ()
 Empty constructor.

Protected Member Functions

void applyFilter (PointCloud2 &output)
 Extract point indices into a separate PointCloud.
void applyFilter (std::vector< int > &indices)
 Extract point indices.

Detailed Description

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

ExtractIndices extracts a set of indices from a point cloud.
Usage examples:

 pcl::ExtractIndices<PointType> filter;
 filter.setInputCloud (cloud_in);
 filter.setIndices (indices_in);
 // Extract the points in cloud_in referenced by indices_in as a separate point cloud:
 filter.filter (*cloud_out);
 // Retrieve indices to all points in cloud_in except those referenced by indices_in:
 filter.setNegative (true);
 filter.filter (*indices_out);
 // The resulting cloud_out is identical to cloud_in, but all points referenced by indices_in are made NaN:
 filter.setNegative (true);
 filter.setKeepOrganized (true);
 filter.filter (*cloud_out);
Note:
Does not inherently remove NaNs from results, hence the extract_removed_indices_ system is not used.
Author:
Radu Bogdan Rusu

Definition at line 157 of file extract_indices.h.


Member Typedef Documentation

typedef sensor_msgs::PointCloud2 pcl::ExtractIndices< sensor_msgs::PointCloud2 >::PointCloud2

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

Definition at line 160 of file extract_indices.h.

typedef PointCloud2::ConstPtr pcl::ExtractIndices< sensor_msgs::PointCloud2 >::PointCloud2ConstPtr

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

Definition at line 162 of file extract_indices.h.

typedef PointCloud2::Ptr pcl::ExtractIndices< sensor_msgs::PointCloud2 >::PointCloud2Ptr

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

Definition at line 161 of file extract_indices.h.


Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 165 of file extract_indices.h.


Member Function Documentation

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

Extract point indices into a separate PointCloud.

Parameters:
[out]outputthe resultant point cloud

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

Definition at line 47 of file filters/src/extract_indices.cpp.

void pcl::ExtractIndices< sensor_msgs::PointCloud2 >::applyFilter ( std::vector< int > &  indices) [protected, virtual]

Extract point indices.

Parameters:
indicesthe resultant indices

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

Definition at line 114 of file filters/src/extract_indices.cpp.


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


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