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
00032 #ifndef _REGION_GROWING_NODE_HPP_
00033 #define _REGION_GROWING_NODE_HPP_
00034
00035 #include <pointcloud_segmentation/region_growing_node.h>
00036
00037 template<class T, class T1>
00038 void region_growing_node<T,T1>::callback_cloud (const sensor_msgs::PointCloud2Ptr& msg)
00039 {
00040 typename PointCloud<T>::Ptr cloud (new PointCloud<T> ());
00041 typename PointCloud<T1>::Ptr laser_scan_ptr (new PointCloud<T1> (laser_scan));
00042
00043 fromROSMsg(*msg,*cloud);
00044
00046 EuclideanClusterExtraction<T1> ec_inside;
00047 vector<PointIndices> indices;
00048 ec_inside.setClusterTolerance (clustering_tolerance);
00049 ec_inside.setMinClusterSize (min_cluster_size);
00050 ec_inside.setMaxClusterSize (max_cluster_size);
00051 ec_inside.setInputCloud (laser_scan_ptr);
00052 ec_inside.extract (indices);
00053
00054
00055 markers<PointXYZRGB> mk;
00056
00057 static int marker_id;
00058
00059 if (marker_id>0)
00060 {
00061 for (int i=0; i<=marker_id; ++i)
00062 {
00063 visualization_msgs::Marker marker_eraser=mk.unmark(msg->header.frame_id, "Obstacle", i);
00064 pub_markers_ptr->publish(marker_eraser);
00065 pub_markers_text_ptr->publish(marker_eraser);
00066 }
00067 }
00068
00070 marker_id=0;
00071
00072 for (vector<PointIndices>::const_iterator it = indices.begin (); it != indices.end (); ++it)
00073 {
00074
00075 marker_id++;
00076 typename PointCloud<T1>::Ptr cluster (new PointCloud<T1>);
00077 typename PointCloud<T>::Ptr cluster_growed (new PointCloud<T>);
00078 cluster->header.frame_id=msg->header.frame_id;
00079 cluster_growed->header.frame_id=msg->header.frame_id;
00080 for (vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++)
00081 cluster->points.push_back (laser_scan_ptr->points[*pit]);
00082
00083
00084
00085
00086 if ((int)cluster->points.size()>0)
00087 {
00088 PointIndices::Ptr region_indices (new PointIndices ());
00089
00090 region_growing<T, T1> rg;
00091 rg.radius=radius;
00092 rg.set_input_seeds(cluster);
00093 rg.set_input_cloud(cloud);
00094
00095 rg.filter();
00096
00097 *region_indices=rg.get_region_point_indices();
00098
00099 if (region_indices->indices.size()>0)
00100 {
00101
00102 ExtractIndices<T> extract;
00103 extract.setInputCloud (cloud);
00104
00105 extract.setIndices (region_indices);
00106 extract.setNegative (false);
00107 extract.filter (*cluster_growed);
00108
00109 visualization_msgs::Marker marker_info=mk.mark_text(cluster_growed, "Obstacle" ,marker_id, 0.0, 1.0, 0.0);
00110 visualization_msgs::Marker marker=mk.mark(cluster_growed, "Obstacle" ,marker_id, 1.0, 0.0, 0.0);
00111 pub_markers_ptr->publish(marker);
00112 pub_markers_text_ptr->publish(marker_info);
00113 }
00114 cluster_growed.reset();
00115 region_indices.reset();
00116 }
00117 }
00118
00119 cloud.reset();
00120 laser_scan_ptr.reset();
00121 };
00123
00124 template<class T, class T1>
00125 void region_growing_node<T,T1>::callback_laser (const sensor_msgs::PointCloud2Ptr& msg)
00126 {
00127 fromROSMsg(*msg,laser_scan);
00128 };
00130
00131 #endif