plane_model_road_segmentation.h
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_segmentation_H_
28 #define _plane_model_segmentation_H_
29 
30 #include <ros/ros.h>
31 #include <sensor_msgs/PointCloud2.h>
32 
33 // ROS Transform stuff
34 #include <tf/transform_broadcaster.h>
35 #include <tf/transform_listener.h>
36 // Point cloud library stuff filters and so on
37 
38 #include <pcl/point_cloud.h>
39 #include <pcl/point_types.h>
40 #include <pcl/conversions.h>
41 #include <pcl/filters/voxel_grid.h>
42 #include <pcl_ros/transforms.h>
43 #include <pcl/segmentation/extract_polygonal_prism_data.h>
44 #include <pcl/filters/extract_indices.h>
45 #include <pcl/segmentation/sac_segmentation.h>
46 #include <pcl/sample_consensus/method_types.h>
47 #include <pcl/sample_consensus/model_types.h>
48 #include <pcl/filters/project_inliers.h>
49 #include <pcl_conversions/pcl_conversions.h>
50 
51 using namespace std;
52 
53 #define pi 3.1415926
54 
71 template <class T>
73 {
74 public:
75 
87  bool find_road_frame(pcl::PointCloud<T> cloud_in);
88 
95  bool find_road_frame(const sensor_msgs::PointCloud2ConstPtr& msg);
96 
108  tf::Transform find_and_publish_road_frame(pcl::PointCloud<T> cloud_in);
109 
116  tf::Transform find_and_publish_road_frame(const sensor_msgs::PointCloud2ConstPtr& msg);
117 
132  pcl::PointCloud<T> get_plane_coefficients(pcl::PointCloud<T> cloud_in, int iterations, float threshold, pcl::ModelCoefficients::Ptr coefficients);
133 
134  //variables definition
135  float threshold;
137  bool debug;
141  tf::TransformListener *listener_atc_ground_ptr;
142  tf::TransformBroadcaster *broadcast_ptr;
143  std::string pub_frame_name;
145  pcl::ModelCoefficients::Ptr coef;
146 
147  //Class Constructor
149  {
150  threshold=0.01; //Initialize default values
151  iterations=50;
152  debug=false;
153 
154  point_origin.x=2; point_origin.y=0; point_origin.z=0;
155  point_x.x=4; point_x.y=0; point_x.z=0;
156  point_y.x=4; point_y.y=0; point_y.z=0;
157  pub_frame_name="/environment/road_frame";
158  reference_ground_frame="/atc/vehicle/ground";
159  };
160 
162  {
163  // Class Destructor
164  };
165 
166 private:
167 
168  // Variables definition
169  pcl::PointCloud<T> outliers;
173 
174  // //Function declarations
182  T project_point_to_plane(const T ptin, const pcl::ModelCoefficients::Ptr coeff);
183 
192  T transform_pcl_point(std::string frame1, std::string frame2, T pt_origin);
193 
201  inline bool check_distance(double distance, double threshold)
202  {
203  if (distance<=threshold)
204  {
205  if (debug)
206  cout << "PMS_DEBUG: ROAD FRAME FOUND" << endl;
207  return true;
208  }
209  else
210  return false;
211  };
212 
213 
222  vector<double> find_RP_angle(T origin_projected, T pt_x_projected, T pt_y_projected);
223 
232  tf::Transform get_transform(T origin_projected, T pt_x_projected, T pt_y_projected);
233 
234 };
235 
237 
238 #endif
tf::TransformBroadcaster * broadcast_ptr
tf::TransformListener * listener_atc_ground_ptr
Function implementation for class plane_model_road< T >
pcl::ModelCoefficients::Ptr coef
bool check_distance(double distance, double threshold)
check if distance matches with threshold If returned true, you probably get the road plane ...


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