region_growing_node< T, T1 > Class Template Reference

#include <region_growing_node.h>

List of all members.

Public Member Functions

void callback_cloud (const sensor_msgs::PointCloud2Ptr &msg)
 callback for point cloud
void callback_laser (const sensor_msgs::PointCloud2Ptr &msg)
 callback for laser cloud
 region_growing_node ()
 class constructor
 ~region_growing_node ()
 class destructor

Public Attributes

double clustering_tolerance
 Tolerance between points on the same cluster.
PointCloud< T1 > laser_scan
 Laser input point cloud.
double max_cluster_size
 Maximum points to consider the cluster.
double min_cluster_size
 Minimum points to consider the cluster.
ros::Publisher * pub_markers_ptr
 A publisher pointer to a marker.
ros::Publisher * pub_markers_text_ptr
 A publisher pointer to add some text in clusters.
double radius
 The radius limit for region growing algorithm.

Detailed Description

template<class T, class T1>
class region_growing_node< T, T1 >

Definition at line 56 of file region_growing_node.h.


Constructor & Destructor Documentation

template<class T, class T1>
region_growing_node< T, T1 >::region_growing_node (  )  [inline]

class constructor

Definition at line 61 of file region_growing_node.h.

template<class T, class T1>
region_growing_node< T, T1 >::~region_growing_node (  )  [inline]

class destructor

Definition at line 66 of file region_growing_node.h.


Member Function Documentation

template<class T , class T1 >
void region_growing_node< T, T1 >::callback_cloud ( const sensor_msgs::PointCloud2Ptr &  msg  )  [inline]

callback for point cloud

Step 1 Cluster the laser scan

And now call for region growing on each cluster from laser

Definition at line 38 of file region_growing_node.hpp.

template<class T , class T1 >
void region_growing_node< T, T1 >::callback_laser ( const sensor_msgs::PointCloud2Ptr &  msg  )  [inline]

callback for laser cloud

Definition at line 125 of file region_growing_node.hpp.


Member Data Documentation

template<class T, class T1>
double region_growing_node< T, T1 >::clustering_tolerance

Tolerance between points on the same cluster.

Definition at line 88 of file region_growing_node.h.

template<class T, class T1>
PointCloud<T1> region_growing_node< T, T1 >::laser_scan

Laser input point cloud.

Definition at line 68 of file region_growing_node.h.

template<class T, class T1>
double region_growing_node< T, T1 >::max_cluster_size

Maximum points to consider the cluster.

Definition at line 85 of file region_growing_node.h.

template<class T, class T1>
double region_growing_node< T, T1 >::min_cluster_size

Minimum points to consider the cluster.

Definition at line 82 of file region_growing_node.h.

template<class T, class T1>
ros::Publisher* region_growing_node< T, T1 >::pub_markers_ptr

A publisher pointer to a marker.

Definition at line 76 of file region_growing_node.h.

template<class T, class T1>
ros::Publisher* region_growing_node< T, T1 >::pub_markers_text_ptr

A publisher pointer to add some text in clusters.

Definition at line 79 of file region_growing_node.h.

template<class T, class T1>
double region_growing_node< T, T1 >::radius

The radius limit for region growing algorithm.

Definition at line 91 of file region_growing_node.h.


The documentation for this class was generated from the following files:
 All Classes Files Functions Variables Defines


pointcloud_segmentation
Author(s): Tiago Talhada
autogenerated on Wed Jul 23 04:33:32 2014