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 _EUCLIDEAN_CLUSTER_HPP_
00033 #define _EUCLIDEAN_CLUSTER_HPP_
00034
00035
00036 #include <pointcloud_segmentation/euclidean_cluster.h>
00037
00038 template<class T>
00039 void euclidean_cluster_extraction<T>::callback_cloud (const sensor_msgs::PointCloud2Ptr& msg)
00040 {
00041 typename PointCloud<T>::Ptr cloud (new PointCloud<T> ());
00042 fromROSMsg(*msg,*cloud);
00043 if ((int)cloud->points.size()>0)
00044 {
00045
00046 EuclideanClusterExtraction<T> ec_inside;
00047 vector<PointIndices> inside_indices;
00048 ec_inside.setClusterTolerance (cluster_tolerance);
00049 ec_inside.setMinClusterSize (min_cluster_size);
00050 ec_inside.setMaxClusterSize (max_cluster_size);
00051 ec_inside.setInputCloud (cloud);
00052 ec_inside.extract (inside_indices);
00053
00054
00055 markers<T> mk;
00056
00057
00058 static int marker_id;
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_marker_ptr->publish(marker_eraser);
00065 pub_marker_text_ptr->publish(marker_eraser);
00066 }
00067 }
00068
00069 marker_id=0;
00070 for (vector<PointIndices>::const_iterator it = inside_indices.begin (); it != inside_indices.end (); ++it)
00071 {
00072 typename PointCloud<T>::Ptr inside_cluster (new PointCloud<T>);
00073 inside_cluster->header.frame_id=msg->header.frame_id;
00074 for (vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++)
00075 inside_cluster->points.push_back (cloud->points[*pit]);
00076
00077 visualization_msgs::Marker marker_info=mk.mark_text(inside_cluster, "Obstacle" ,marker_id, 1.0, 0.0, 0.0);
00078 visualization_msgs::Marker marker=mk.mark(inside_cluster, "Obstacle" ,marker_id, 0.0, 1.0, 0.0);
00079 marker_id++;
00080 pub_marker_ptr->publish(marker);
00081 pub_marker_text_ptr->publish(marker_info);
00082 inside_cluster.reset();
00083 }
00084
00085 }
00086 else
00087 ROS_ERROR("EUCLIDEAN_CLUSTERING: NO DATA POINTS RECEIVED!");
00088
00089 cloud.reset();
00090 };
00092
00093 #endif