EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense. More...
#include <extract_clusters.h>
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. |
EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense.
Definition at line 57 of file extract_clusters.h.
Empty constructor.
Definition at line 61 of file extract_clusters.h.
void pcl_ros::EuclideanClusterExtraction::config_callback | ( | EuclideanClusterExtractionConfig & | config, |
uint32_t | level | ||
) | [protected] |
Dynamic reconfigure callback.
config | the config object |
level | the dynamic reconfigure level |
Definition at line 116 of file extract_clusters.cpp.
void pcl_ros::EuclideanClusterExtraction::input_indices_callback | ( | const PointCloudConstPtr & | cloud, |
const PointIndicesConstPtr & | indices | ||
) | [protected] |
Input point cloud callback.
cloud | the pointer to the input point cloud |
indices | the pointer to the input point cloud indices |
DEBUG
Definition at line 142 of file extract_clusters.cpp.
void pcl_ros::EuclideanClusterExtraction::onInit | ( | ) | [protected, virtual] |
Nodelet initialization routine.
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 44 of file extract_clusters.cpp.
pcl::EuclideanClusterExtraction<pcl::PointXYZ> pcl_ros::EuclideanClusterExtraction::impl_ [private] |
The PCL implementation used.
Definition at line 91 of file extract_clusters.h.
int pcl_ros::EuclideanClusterExtraction::max_clusters_ [protected] |
Maximum number of clusters to publish.
Definition at line 69 of file extract_clusters.h.
bool pcl_ros::EuclideanClusterExtraction::publish_indices_ [protected] |
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.
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointIndices> > > pcl_ros::EuclideanClusterExtraction::sync_input_indices_a_ [private] |
Definition at line 98 of file extract_clusters.h.
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointIndices> > > pcl_ros::EuclideanClusterExtraction::sync_input_indices_e_ [private] |
Synchronized input, and indices.
Definition at line 97 of file extract_clusters.h.