Protected Member Functions | Protected Attributes | Private Attributes
pcl_ros::ExtractIndices Class Reference

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

#include <extract_indices.h>

Inheritance diagram for pcl_ros::ExtractIndices:
Inheritance graph
[legend]

List of all members.

Protected Member Functions

virtual bool child_init (ros::NodeHandle &nh, bool &has_service)
 Child initialization routine.
void config_callback (pcl_ros::ExtractIndicesConfig &config, uint32_t level)
 Dynamic reconfigure service callback.
void filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
 Call the actual filter.

Protected Attributes

boost::shared_ptr
< dynamic_reconfigure::Server
< pcl_ros::ExtractIndicesConfig > > 
srv_
 Pointer to a dynamic reconfigure service.

Private Attributes

pcl::ExtractIndices
< pcl::PCLPointCloud2 > 
impl_
 The PCL filter implementation used.

Detailed Description

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 Function Documentation

bool pcl_ros::ExtractIndices::child_init ( ros::NodeHandle nh,
bool &  has_service 
) [protected, virtual]

Child initialization routine.

Parameters:
nhROS node handle
has_serviceset to true if the child has a Dynamic Reconfigure service

Reimplemented from pcl_ros::Filter.

Definition at line 43 of file extract_indices.cpp.

void pcl_ros::ExtractIndices::config_callback ( pcl_ros::ExtractIndicesConfig &  config,
uint32_t  level 
) [protected]

Dynamic reconfigure service callback.

Definition at line 57 of file extract_indices.cpp.

void pcl_ros::ExtractIndices::filter ( const PointCloud2::ConstPtr &  input,
const IndicesPtr indices,
PointCloud2 output 
) [inline, protected, virtual]

Call the actual filter.

Parameters:
inputthe input point cloud dataset
indicesthe input set of indices to use from input
outputthe resultant filtered dataset

Implements pcl_ros::Filter.

Definition at line 65 of file extract_indices.h.


Member Data Documentation

pcl::ExtractIndices<pcl::PCLPointCloud2> pcl_ros::ExtractIndices::impl_ [private]

The PCL filter implementation used.

Definition at line 91 of file extract_indices.h.

boost::shared_ptr<dynamic_reconfigure::Server<pcl_ros::ExtractIndicesConfig> > pcl_ros::ExtractIndices::srv_ [protected]

Pointer to a dynamic reconfigure service.

Reimplemented from pcl_ros::Filter.

Definition at line 57 of file extract_indices.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu May 5 2016 04:16:43