00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00034 #include <pointcloud_segmentation/region_growing_node.h>
00035
00036 int main(int argc, char **argv)
00037 {
00038
00039 ros::init(argc, argv, "region_growing_nodelet");
00040 ros::NodeHandle n;
00041
00042
00043 string pointcloud_input;
00044 string laser_input;
00045 string cluster_markers;
00046 string cluster_markers_text;
00047
00048 region_growing_node<PointXYZRGB, PointXYZ> * rg_class = new region_growing_node<PointXYZRGB, PointXYZ> ();
00049
00050
00051 ros::NodeHandle private_node_handle_("~");
00052 private_node_handle_.param("pointcloud_input", pointcloud_input, string("pointcloud_input"));
00053 private_node_handle_.param("laser_input", laser_input, string("laser_input"));
00054 private_node_handle_.param("cluster_markers", cluster_markers, string("cluster_markers"));
00055 private_node_handle_.param("cluster_markers_text", cluster_markers_text, string("cluster_markers_text"));
00056 private_node_handle_.param("min_cluster_size", rg_class->min_cluster_size, double(rg_class->min_cluster_size));
00057 private_node_handle_.param("max_cluster_size", rg_class->max_cluster_size, double(rg_class->max_cluster_size));
00058 private_node_handle_.param("clustering_tolerance", rg_class->clustering_tolerance, double(rg_class->clustering_tolerance));
00059 private_node_handle_.param("radius", rg_class->radius, double(rg_class->radius));
00060
00061
00062
00063 ros::Subscriber sub_cloud = n.subscribe(pointcloud_input.c_str(), 1, ®ion_growing_node<PointXYZRGB, PointXYZ>::callback_cloud,rg_class);
00064 ros::Subscriber sub_laser = n.subscribe(laser_input.c_str(), 1,®ion_growing_node<PointXYZRGB, PointXYZ>::callback_laser,rg_class);
00065
00066
00067
00068 ros::Publisher pub_markers=n.advertise<visualization_msgs::Marker>(cluster_markers.c_str(),1000);
00069 ros::Publisher pub_markers_text=n.advertise<visualization_msgs::Marker>(cluster_markers_text.c_str(),1000);
00070
00071 rg_class->pub_markers_ptr=&pub_markers;
00072 rg_class->pub_markers_text_ptr=&pub_markers_text;
00073
00074
00075 while (n.ok())
00076 {
00077 ros::spinOnce();
00078 }
00079
00080 return 0;
00081 }