plane_road_extraction_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 ***************************************************************************************************/
34 
35 int main(int argc, char **argv)
36 {
37  // Set up ROS.
38  ros::init(argc, argv, "plane_road_extraction_nodelet");
39  ros::NodeHandle n;
40 
41  // Variables from launch file
42  string pointcloud_input;
43  string pointcloud_road;
44  string pointcloud_clusters;
45  string pointcloud_road_perimeter;
46  double threshold;
47 
48  // Declare the node class object
50 
51  // Read parameters from launch file
52  ros::NodeHandle private_node_handle_("~");
53  private_node_handle_.param("pointcloud_input", pointcloud_input, string("pointcloud_input"));
54  private_node_handle_.param("pointcloud_road", pointcloud_road, string("pointcloud_road"));
55  private_node_handle_.param("pointcloud_clusters", pointcloud_clusters, string("pointcloud_clusters"));
56  private_node_handle_.param("pointcloud_road_perimeter", pointcloud_road_perimeter, string("pointcloud_road_perimeter"));
57  private_node_handle_.param("z_min", extraction->z_min, double(extraction->z_min));
58  private_node_handle_.param("z_max", extraction->z_max, double(extraction->z_max));
59  private_node_handle_.param("threshold", threshold, double(threshold));
60 
61  // Subscribe a pointcloud message
62  ros::Subscriber sub_cloud = n.subscribe(pointcloud_input.c_str(), 1000, &plane_road_extraction<PointXYZRGB>::filter, extraction);
63 
64  // Publish a pointcloud message
65  ros::Publisher pub_road = n.advertise<sensor_msgs::PointCloud2>(pointcloud_road.c_str(), 10);
66  ros::Publisher pub_clusters = n.advertise<sensor_msgs::PointCloud2>(pointcloud_clusters.c_str(), 10);
67  ros::Publisher pub_road_perimeter= n.advertise<sensor_msgs::PointCloud2>(pointcloud_road_perimeter.c_str(), 10);
68 
69  // Set pointers
70  extraction->pub_road_ptr=&pub_road;
71  extraction->pub_clusters_ptr=&pub_clusters;
72  extraction->pub_road_perimeter_ptr=&pub_road_perimeter;
73 
74  // Configure tf
75  tf::TransformListener listener; // atc/vehicle/ground
76  tf::TransformBroadcaster br;
77 
78  extraction->pms.listener_atc_ground_ptr=&listener;
79  extraction->pms.broadcast_ptr=&br;
80 
81  // Configure your frame names
82  extraction->pms.reference_ground_frame=(char *)(ros::names::remap("/atc/vehicle/ground")).c_str();
83  extraction->pms.pub_frame_name=(char *)(ros::names::remap("/environment/road_frame")).c_str();
84  extraction->pms.threshold=(float)(threshold);
85  extraction->pms.debug=false;
86 
87  // Main loop.
88  while (n.ok())
89  {
90  ros::spinOnce();
91  }
92 
93  return 0;
94 }
ros::Publisher * pub_road_ptr
Pointer to road publisher.
plane_road_extraction class declaration
plane_model_road< T > pms
Class object for plane model road segmentation.
ros::Publisher * pub_road_perimeter_ptr
Pointer to road perimeter publisher.
int main(int argc, char **argv)
ros::Publisher * pub_clusters_ptr
Pointer to clusters publisher.
double z_min
Extraction limits to pointcloud.


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