plane_road_extraction.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 _PLANE_ROAD_EXTRACTION_HPP_
33 #define _PLANE_ROAD_EXTRACTION_HPP_
34 
35 #include "plane_road_extraction.h"
36 
37 template <class T>
38 void plane_road_extraction<T>::filter (const sensor_msgs::PointCloud2Ptr& msg)
39 {
40  PointCloud<T> cloud;
41 
42  fromROSMsg(*msg,cloud);
43 
44  if ((int)cloud.points.size()>0)
45  {
46  tf::Transform road_tf=pms.find_and_publish_road_frame(cloud);
47 
48  // Create the convex hull to extract the point clouds
49  T point_origin;
50  T point_origin_transformed;
51  T point_away;
52  T point_away_transformed;
53  T pt;
54 
55  point_origin.x=0; point_origin.y=0; point_origin.z=0; // Transform a point on the origin
56  point_away.x=50; point_away.y=0; point_away.z=0; // Transform a point far (10m)
57  point_origin_transformed=transform_pcl_point(cloud.header.frame_id, road_tf, point_origin);
58  point_away_transformed=transform_pcl_point(cloud.header.frame_id, road_tf, point_away);
59 
60  PointCloud<T> road_hull;
61  road_hull.header.frame_id=cloud.header.frame_id;
62  pt.x = -2; pt.y=50; pt.z=point_origin_transformed.z;
63  road_hull.points.push_back(pt);
64  pt.x = 50; pt.y=50; pt.z=point_away_transformed.z;
65  road_hull.points.push_back(pt);
66  pt.x = 50; pt.y= -50; pt.z=point_away_transformed.z;
67  road_hull.points.push_back(pt);
68  pt.x = -2; pt.y=-50; pt.z=point_origin_transformed.z;
69  road_hull.points.push_back(pt);
70 
71  // Roadless point cloud
72  PointCloud<T> cloud_road;
73  PointCloud<T> cloud_cluster;
74  points_from_volume<T> pfv_cloud;
75  cloud_road.header.frame_id=cloud.header.frame_id;
76  cloud_cluster.header.frame_id=cloud.header.frame_id;
77  pfv_cloud.set_convex_hull(road_hull);
78  pfv_cloud.convexhull_function(cloud, z_max, z_min, false);
79  cloud_road=pfv_cloud.get_pc_in_volume();
80  pfv_cloud.convexhull_function(cloud, 20, z_max, false);
81  cloud_cluster=pfv_cloud.get_pc_in_volume();
82 
83  // Project road cloud on the plane
84  PointCloud<T> cloud_road_projected;
85  cloud_road_projected = project_cloud_on_plane(cloud_road, pms.coef);
86 
87  // Calculate the road perimeter
88  PointCloud<T> road_perimeter;
89  ConvexHull<T> chull;
90  chull.setInputCloud (cloud_road_projected.makeShared());
91  chull.reconstruct (road_perimeter);
92 
93  // Create an extraction object
94  points_from_volume<T> pfv;
95  PointCloud<T> inside_cloud;
96  inside_cloud.header.frame_id=msg->header.frame_id;
97  pfv.set_convex_hull(road_perimeter);
98  pfv.convexhull_function(cloud_cluster, 20, -20, false);
99  inside_cloud=pfv.get_pc_in_volume(); // -> All points inside road convex_hull
100 
101  // cout << cloud_cluster.points.size() << endl;
102 
103  sensor_msgs::PointCloud2 msg_road;
104  sensor_msgs::PointCloud2 msg_cluster;
105  sensor_msgs::PointCloud2 msg_perimeter;
106  toROSMsg(cloud_road_projected,msg_road);
107  toROSMsg(inside_cloud,msg_cluster);
108  toROSMsg(road_perimeter,msg_perimeter);
109  pub_clusters_ptr->publish(msg_cluster);
110  pub_road_ptr->publish(msg_road);
111  pub_road_perimeter_ptr->publish(msg_perimeter);
112 
113  }
114 };
116 
117 template<class T>
118 T plane_road_extraction<T>::transform_pcl_point(string frame1, tf::Transform transform, T pt_origin)
119 {
120  PointCloud<T> pc_point; // A point cloud with a single point
121  pc_point.points.push_back(pt_origin);
122  pcl_ros::transformPointCloud (pc_point,pc_point,transform);
123  return pc_point.points[0];
124 };
126 
127 template<class T>
128 PointCloud<T> plane_road_extraction<T>::project_cloud_on_plane(PointCloud<T> cloud_in, ModelCoefficients::Ptr coefficients)
129 {
130  typename PointCloud<T>::Ptr cloud_in_ptr (new PointCloud<T> (cloud_in));
131  PointCloud<T> cloud_out;
132 
133  //Create the projection object
134  ProjectInliers<T> projection;
135  projection.setModelType(SACMODEL_PLANE); //set model type
136 
137  projection.setInputCloud(cloud_in_ptr);
138  projection.setModelCoefficients(coefficients);
139  projection.filter(cloud_out);
140 
141  cloud_in_ptr.reset();
142  return cloud_out;
143 }
144 
145 #endif
PointCloud< T > project_cloud_on_plane(PointCloud< T > cloud_in, ModelCoefficients::Ptr coefficients)
project a point cloud on a plane
plane_road_extraction class declaration
void filter(const sensor_msgs::PointCloud2Ptr &msg)
callback function
T transform_pcl_point(string frame1, tf::Transform transform, T pt_origin)
transform pcl points between ros frames


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