32 #ifndef _REGION_GROWING_NODE_H_
33 #define _REGION_GROWING_NODE_H_
37 #include <sensor_msgs/PointCloud2.h>
38 #include <sensor_msgs/LaserScan.h>
39 #include <visualization_msgs/Marker.h>
42 #include <pcl/kdtree/kdtree_flann.h>
43 #include <pcl/segmentation/extract_clusters.h>
44 #include <pcl/surface/convex_hull.h>
45 #include <pcl/common/common.h>
46 #include <pcl_conversions/pcl_conversions.h>
56 template<
class T,
class T1>
74 PointCloud<T1> laser_scan;
97 void callback_cloud (
const sensor_msgs::PointCloud2Ptr& msg);
100 void callback_laser (
const sensor_msgs::PointCloud2Ptr& msg);
double min_cluster_size
Minimum points to consider the cluster.
markers class main declaration
region_growing_node()
class constructor
ros::Publisher * pub_markers_text_ptr
A publisher pointer to add some text in clusters.
ros::Publisher * pub_markers_ptr
A publisher pointer to a marker.
double max_cluster_size
Maximum points to consider the cluster.
region_growing_node class functions implementation
double clustering_tolerance
Tolerance between points on the same cluster.
double radius
The radius limit for region growing algorithm.
Class for pcl region growing algorithm.
~region_growing_node()
class destructor