Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes
pcl_ros::EuclideanClusterExtraction Class Reference

EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense. More...

#include <extract_clusters.h>

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

List of all members.

Public Member Functions

 EuclideanClusterExtraction ()
 Empty constructor.

Protected Member Functions

void config_callback (EuclideanClusterExtractionConfig &config, uint32_t level)
 Dynamic reconfigure callback.
void input_indices_callback (const PointCloudConstPtr &cloud, const PointIndicesConstPtr &indices)
 Input point cloud callback.
void onInit ()
 Nodelet initialization routine.

Protected Attributes

int max_clusters_
 Maximum number of clusters to publish.
bool publish_indices_
 Publish indices or convert to PointCloud clusters. Default: false.
boost::shared_ptr
< dynamic_reconfigure::Server
< EuclideanClusterExtractionConfig > > 
srv_
 Pointer to a dynamic reconfigure service.

Private Attributes

pcl::EuclideanClusterExtraction
< pcl::PointXYZ > 
impl_
 The PCL implementation used.
ros::Subscriber sub_input_
 The input PointCloud subscriber.
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ApproximateTime
< PointCloud, PointIndices > > > 
sync_input_indices_a_
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ExactTime
< PointCloud, PointIndices > > > 
sync_input_indices_e_
 Synchronized input, and indices.

Detailed Description

EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense.

Author:
Radu Bogdan Rusu

Definition at line 57 of file extract_clusters.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 61 of file extract_clusters.h.


Member Function Documentation

void pcl_ros::EuclideanClusterExtraction::config_callback ( EuclideanClusterExtractionConfig &  config,
uint32_t  level 
) [protected]

Dynamic reconfigure callback.

Parameters:
configthe config object
levelthe dynamic reconfigure level

Definition at line 121 of file extract_clusters.cpp.

Input point cloud callback.

Parameters:
cloudthe pointer to the input point cloud
indicesthe pointer to the input point cloud indices

DEBUG

Definition at line 147 of file extract_clusters.cpp.

void pcl_ros::EuclideanClusterExtraction::onInit ( ) [protected, virtual]

Nodelet initialization routine.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 51 of file extract_clusters.cpp.


Member Data Documentation

The PCL implementation used.

Definition at line 91 of file extract_clusters.h.

Maximum number of clusters to publish.

Definition at line 69 of file extract_clusters.h.

Publish indices or convert to PointCloud clusters. Default: false.

Definition at line 61 of file extract_clusters.h.

boost::shared_ptr<dynamic_reconfigure::Server<EuclideanClusterExtractionConfig> > pcl_ros::EuclideanClusterExtraction::srv_ [protected]

Pointer to a dynamic reconfigure service.

Definition at line 72 of file extract_clusters.h.

The input PointCloud subscriber.

Definition at line 94 of file extract_clusters.h.

Definition at line 98 of file extract_clusters.h.

Synchronized input, and indices.

Definition at line 97 of file extract_clusters.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 Jun 6 2019 21:01:44