plane_model_road_segmentation_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 ***************************************************************************************************/
27 #ifndef _plane_model_road_segmentation_CPP_
28 #define _plane_model_road_segmentation_CPP_
29 
30 #include <stdio.h>
32 #include <plane_model_road_segmentation/coefficients.h>
34 
35 #define PFLN printf("FUNCTION=%s LINE=%d\n",__FUNCTION__,__LINE__);
36 
43 // Global declarations
44 tf::TransformListener *listener_center_bumper_ptr;
46 ros::Publisher pub_coeffs;
47 
48 void topic_callback2(const sensor_msgs::PointCloud2ConstPtr& msg)
49 {
50  static int counter=0; counter++;
51  ROS_INFO("Message received number:%d",counter);
52 
53  // Pcl clouds
54  pcl::PointCloud<pcl::PointXYZRGB> cloud_in;
55  pcl::fromROSMsg(*msg,cloud_in);
56 
57  tf::Transform road_tf=pms.find_and_publish_road_frame(cloud_in);
58 
59  plane_model_road_segmentation::coefficients coefficients;
60  coefficients.A=pms.coef->values[0];
61  coefficients.B=pms.coef->values[1];
62  coefficients.C=pms.coef->values[2];
63  coefficients.D=pms.coef->values[3];
64  pub_coeffs.publish(coefficients);
65 }
66 
67 
68 int main(int argc, char **argv)
69 {
70  ROS_INFO("Starting plane_model_road_segmentation nodelet...");
71  ros::init(argc,argv,"plane_segmentation_nodelet");
72 
73  ros::NodeHandle n;
74 
75  // Messages subscription configuration
76  tf::TransformListener listener_center_bumper; // atc/vehicle/center_bumper
77  tf::TransformListener listener_atc_ground; // atc/vehicle/ground
78  listener_center_bumper_ptr=&listener_center_bumper;
79  pms.listener_atc_ground_ptr=&listener_atc_ground;
80 
81  // Getting point cloud from launch file
82  string pointcloud_subscribed;
83  if (!n.hasParam("pointcloud_subscribed"))
84  {
85  ROS_ERROR("Must set properly a input pointcloud (pointcloud_subscribed).");
86  return -1;
87  }
88  else
89  n.getParam("pointcloud_subscribed", pointcloud_subscribed);
90  ros::Subscriber sub = n.subscribe(pointcloud_subscribed, 1, topic_callback2);
91 
92  // Publish a frame
93  tf::TransformBroadcaster br; // Road frame
94  pms.broadcast_ptr=&br;
95 
96  // Publish model coefficients
97  string coefficients_topic_name;
98  if (!n.hasParam("coefficients_topic_name"))
99  {
100  ROS_ERROR("Must set properly a coefficients_topic_name (coefficients_topic_name).");
101  return -1;
102  }
103  else
104  n.getParam("coefficients_topic_name", coefficients_topic_name);
105  pub_coeffs=n.advertise<plane_model_road_segmentation::coefficients>(coefficients_topic_name,1);
106 
107 
108  if (!n.hasParam("road_frame"))
109  ROS_INFO("publishing frame as /environment/road_frame");
110  else
111  n.getParam("road_frame",pms.pub_frame_name);
112 
113  if (!n.hasParam("reference_ground_frame"))
114  ROS_WARN("You didn't set properly your ground reference frame. /atc/vehicle/ground is being used.");
115  else
116  n.getParam("reference_ground_frame",pms.reference_ground_frame);
117 
118  ros::spin();
119 
120  return 1;
121 }
122 #endif
tf::TransformListener * listener_center_bumper_ptr
tf::TransformBroadcaster * broadcast_ptr
void topic_callback2(const sensor_msgs::PointCloud2ConstPtr &msg)
A class to determine a planar model for road detection.
tf::TransformListener * listener_atc_ground_ptr
ros::Publisher pub_coeffs
Plane model road segmentation global includes.
pcl::ModelCoefficients::Ptr coef
plane_model_road< pcl::PointXYZRGB > pms
tf::Transform find_and_publish_road_frame(pcl::PointCloud< T > cloud_in)
get and publish the road frame T his f*unction does all the work for you. here are the main steps: ST...
int main(int argc, char **argv)


plane_model_road_segmentation
Author(s): Tiago Talhada
autogenerated on Mon Mar 2 2015 01:32:38