region_growing_node.hpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 #ifndef _REGION_GROWING_NODE_HPP_
33 #define _REGION_GROWING_NODE_HPP_
34 
36 
37 template<class T, class T1>
38 void region_growing_node<T,T1>::callback_cloud (const sensor_msgs::PointCloud2Ptr& msg)
39 {
40  typename PointCloud<T>::Ptr cloud (new PointCloud<T> ());
41  typename PointCloud<T1>::Ptr laser_scan_ptr (new PointCloud<T1> (laser_scan));
42 
43  fromROSMsg(*msg,*cloud);
44 
46  EuclideanClusterExtraction<T1> ec_inside;
47  vector<PointIndices> indices;
48  ec_inside.setClusterTolerance (clustering_tolerance);
49  ec_inside.setMinClusterSize (min_cluster_size);
50  ec_inside.setMaxClusterSize (max_cluster_size);
51  ec_inside.setInputCloud (laser_scan_ptr);
52  ec_inside.extract (indices);
53 
54  // Create markers class
56 
57  static int marker_id;
58  // Delete all previous markers
59  if (marker_id>0)
60  {
61  for (int i=0; i<=marker_id; ++i)
62  {
63  visualization_msgs::Marker marker_eraser=mk.unmark(msg->header.frame_id, "Obstacle", i);
64  pub_markers_ptr->publish(marker_eraser);
65  pub_markers_text_ptr->publish(marker_eraser);
66  }
67  }
68 
70  marker_id=0;
71 
72  for (vector<PointIndices>::const_iterator it = indices.begin (); it != indices.end (); ++it)
73  {
74 
75  marker_id++;
76  typename PointCloud<T1>::Ptr cluster (new PointCloud<T1>);
77  typename PointCloud<T>::Ptr cluster_growed (new PointCloud<T>);
78  cluster->header.frame_id=msg->header.frame_id;
79  cluster_growed->header.frame_id=msg->header.frame_id;
80  for (vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++)
81  cluster->points.push_back (laser_scan_ptr->points[*pit]);
82 
83 // visualization_msgs::Marker marker=mark_cluster(cluster, "Obstacle" ,marker_id, 1.0, 0.0, 0.0);
84 // pub_marker_ptr->publish(marker);
85 
86  if ((int)cluster->points.size()>0)
87  {
88  PointIndices::Ptr region_indices (new PointIndices ());
89 
91  rg.radius=radius;
92  rg.set_input_seeds(cluster);
93  rg.set_input_cloud(cloud);
94 
95  rg.filter();
96 
97  *region_indices=rg.get_region_point_indices();
98 
99  if (region_indices->indices.size()>0)
100  {
101  // Extract the inliers
102  ExtractIndices<T> extract;
103  extract.setInputCloud (cloud);
104 
105  extract.setIndices (region_indices);
106  extract.setNegative (false);
107  extract.filter (*cluster_growed);
108 
109  visualization_msgs::Marker marker_info=mk.mark_text(cluster_growed, "Obstacle" ,marker_id, 0.0, 1.0, 0.0);
110  visualization_msgs::Marker marker=mk.mark(cluster_growed, "Obstacle" ,marker_id, 1.0, 0.0, 0.0);
111  pub_markers_ptr->publish(marker);
112  pub_markers_text_ptr->publish(marker_info);
113  }
114  cluster_growed.reset();
115  region_indices.reset();
116  }
117  }
118 
119  cloud.reset();
120  laser_scan_ptr.reset();
121 };
123 
124 template<class T, class T1>
125 void region_growing_node<T,T1>::callback_laser (const sensor_msgs::PointCloud2Ptr& msg)
126 {
127 // fromROSMsg(*msg,laser_scan);
128  pcl::PCLPointCloud2 pcl_pc;
129  pcl_conversions::toPCL(*msg, pcl_pc);
130  pcl::fromPCLPointCloud2(pcl_pc, laser_scan);
131 };
133 
134 #endif
visualization_msgs::Marker mark_text(typename PointCloud< T >::Ptr cloud_cluster, string ns, int id, float r, float g, float b)
function to create a marker with some text info about a pointcloud (cluster)
region_growing_node class main declaration
void callback_cloud(const sensor_msgs::PointCloud2Ptr &msg)
callback for point cloud
void set_input_seeds(typename PointCloud< T1 >::Ptr seeds_in)
Sets the input point cloud seeds.
void callback_laser(const sensor_msgs::PointCloud2Ptr &msg)
callback for laser cloud
float radius
The radius for search.
PointIndices get_region_point_indices(void)
Provide acces to the result indices.
void set_input_cloud(typename PointCloud< T >::Ptr cloud_in)
Sets the input point cloud data.
void filter()
simply runs the algorithm
visualization_msgs::Marker unmark(std::string frame_id, std::string ns, int id)
function to estimate a marker arround the cluster to show on rviz This function will set a marker ver...
region growing based algorithm.
visualization_msgs::Marker mark(typename PointCloud< T >::Ptr cloud_cluster, string ns, int id, float r, float g, float b)
function to estimate a marker arround the cluster to show on rviz


pointcloud_segmentation
Author(s): Tiago Talhada
autogenerated on Mon Mar 2 2015 01:32:39