region_growing_nodelet.cpp
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 ***************************************************************************************************/
35 
36 int main(int argc, char **argv)
37 {
38  // Set up ROS.
39  ros::init(argc, argv, "region_growing_nodelet");
40  ros::NodeHandle n;
41 
42  // Variables to read from launch file
43  string pointcloud_input;
44  string laser_input;
45  string cluster_markers;
46  string cluster_markers_text;
47  // Declare node class object
49 
50  // Read data from launch file
51  ros::NodeHandle private_node_handle_("~");
52  private_node_handle_.param("pointcloud_input", pointcloud_input, string("pointcloud_input"));
53  private_node_handle_.param("laser_input", laser_input, string("laser_input"));
54  private_node_handle_.param("cluster_markers", cluster_markers, string("cluster_markers"));
55  private_node_handle_.param("cluster_markers_text", cluster_markers_text, string("cluster_markers_text"));
56  private_node_handle_.param("min_cluster_size", rg_class->min_cluster_size, double(rg_class->min_cluster_size));
57  private_node_handle_.param("max_cluster_size", rg_class->max_cluster_size, double(rg_class->max_cluster_size));
58  private_node_handle_.param("clustering_tolerance", rg_class->clustering_tolerance, double(rg_class->clustering_tolerance));
59  private_node_handle_.param("radius", rg_class->radius, double(rg_class->radius));
60 
61 
62  // Subscribe messages
63  ros::Subscriber sub_cloud = n.subscribe(pointcloud_input.c_str(), 1, &region_growing_node<PointXYZRGB, PointXYZ>::callback_cloud,rg_class);
64  ros::Subscriber sub_laser = n.subscribe(laser_input.c_str(), 1,&region_growing_node<PointXYZRGB, PointXYZ>::callback_laser,rg_class);
65 
66 
67  // Publish messages
68  ros::Publisher pub_markers=n.advertise<visualization_msgs::Marker>(cluster_markers.c_str(),1000);
69  ros::Publisher pub_markers_text=n.advertise<visualization_msgs::Marker>(cluster_markers_text.c_str(),1000);
70 
71  rg_class->pub_markers_ptr=&pub_markers;
72  rg_class->pub_markers_text_ptr=&pub_markers_text;
73 
74  // Main loop.
75  while (n.ok())
76  {
77  ros::spinOnce();
78  }
79 
80  return 0;
81 }
region_growing_node class main declaration
double min_cluster_size
Minimum points to consider the cluster.
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.
double clustering_tolerance
Tolerance between points on the same cluster.
double radius
The radius limit for region growing algorithm.
int main(int argc, char **argv)


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