plane_model_road_segmentation_implementation.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 ***************************************************************************************************/
27 
28 #ifndef _PLANE_MODEL_ROAD_SEGMENTATION_HPP_
29 #define _PLANE_MODEL_ROAD_SEGMENTATION_HPP_
30 
37  // PUBLIC MEMBER FUNCTIONS
38 
39 template <class T>
40 tf::Transform plane_model_road<T>::get_transform(T origin_projected, T pt_x_projected, T pt_y_projected)
41 {
42  tf::Transform transform2;
43  tf::Quaternion quaternion;
44  transform2.setOrigin( tf::Vector3((float)origin_projected.x, (float)origin_projected.y, (float)origin_projected.z) );
45 
46  // Calculate RP angles (R and P only)
47 
48  vector<double> RP=find_RP_angle(origin_projected, pt_x_projected, pt_y_projected);
49 
50  if (debug)
51  {
52  cout << "PMS_DEBUG: R= " << RP[0]<< " P= " << RP[1]<< " Y= "<< RP[3] << endl;
53  }
54 
55  quaternion.setRPY(RP[0]-(pi/2),RP[1]-(pi/2),0.0); // Y does not matter
56  transform2.setRotation(quaternion);
57  return transform2;
58 }
60 
61 template<class T>
62 bool plane_model_road<T>::find_road_frame(pcl::PointCloud<T> cloud_in)
63 {
64  // STEP 1 create the model coeeficients
65  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients ());
67 
68  plane_model_road::coef=coefficients;
69 
70  //STEP 2 project origin to plane, point in x and another in y
74 
75  plane_model_road::origin_projected=origin_projected;
76  plane_model_road::pt_x_projected=pt_x_projected;
77  plane_model_road::pt_y_projected=pt_y_projected;
78 
79  // STEP 3 Find the difference between the cloud frame_id to ground
81 
82  //STEP 4 Calculate the difference z axis
83  double distance=point2.z-origin_projected.z;
84  distance=abs(distance);
85  if (debug)
86  cout << "PMS_DEBUG: Distance to reference frame "<< distance << endl;
87 
88  bool succeed=plane_model_road::check_distance(distance,threshold);
89  return succeed;
90 }
92 
93 template<class T>
94 bool plane_model_road<T>::find_road_frame(const sensor_msgs::PointCloud2ConstPtr& msg)
95 {
96  pcl::PointCloud<T> cloud_in;
97 // pcl::fromROSMsg(*msg,cloud_in);
98  pcl::PCLPointCloud2 pcl_pc;
99  pcl_conversions::toPCL(*msg, pcl_pc);
100  pcl::fromPCLPointCloud2(pcl_pc, cloud_in);
101 
102  return plane_model_road::find_road_frame(cloud_in);
103 };
105 
106 template<class T>
107 tf::Transform plane_model_road<T>::find_and_publish_road_frame(pcl::PointCloud<T> cloud_in)
108 {
111  static tf::Transform transform;
113  if (succeed)
114  {
115  plane_model_road::broadcast_ptr->sendTransform(tf::StampedTransform(transform, ros::Time::now(),cloud_in.header.frame_id, plane_model_road::pub_frame_name));
116  }
117  return transform;
118 };
120 
121 template<class T>
122 tf::Transform plane_model_road<T>::find_and_publish_road_frame(const sensor_msgs::PointCloud2ConstPtr& msg)
123 {
124  pcl::PointCloud<T> cloud_in;
125  pcl::fromROSMsg(*msg,cloud_in);
127 };
129 
130 template<class T>
131 pcl::PointCloud<T> plane_model_road<T>::get_plane_coefficients(pcl::PointCloud<T> cloud_in, int iterations, float threshold, pcl::ModelCoefficients::Ptr coefficients)
132 {
133  typename pcl::PointCloud<T>::Ptr cloud_in_ptr (new pcl::PointCloud<T> (cloud_in));
134  pcl::PointCloud<T> cloud_out;
135  // pcl::ModelCoefficients::Ptr coefficients_ptr (new pcl::ModelCoefficients (coefficients));
136  pcl::PointIndices::Ptr inliers (new pcl::PointIndices ());
137 
138  // Create the segmentation object
139  pcl::SACSegmentation<T> seg;
140  pcl::ExtractIndices<T> extract;
141  // Optional
142  seg.setOptimizeCoefficients (true);
143  // Mandatory
144  seg.setModelType (pcl::SACMODEL_PLANE);
145  seg.setMethodType (pcl::SAC_RANSAC);
146  seg.setMaxIterations (iterations);
147  seg.setDistanceThreshold (threshold);
148  seg.setInputCloud (cloud_in_ptr);
149  seg.segment (*inliers, *coefficients);
150  extract.setInputCloud (cloud_in_ptr);
151  extract.setIndices (inliers);
152  extract.setNegative (true);
153  extract.filter (cloud_out);
154 
155  cloud_in_ptr.reset();
156  inliers.reset();
157  return cloud_out;
158 };
160 
161  // PRIVATE CLASS FUNCTIONS
162 
163 
164 template<class T>
165 T plane_model_road<T>::project_point_to_plane(const T ptin, const pcl::ModelCoefficients::Ptr coeff)
166 {
167  pcl::PointCloud<T> pcin;
168  pcin.points.push_back(ptin);
169 
170  typename pcl::PointCloud<T>::Ptr pcin_ptr (new pcl::PointCloud<T> (pcin) );
171  // pcin_ptr=&pcin;
172 
173  pcl::PointCloud<T> pcout;
174  //Create the projection object
175  pcl::ProjectInliers<T> projection;
176  projection.setModelType(pcl::SACMODEL_PLANE); //set model type
177  projection.setInputCloud(pcin_ptr);
178  projection.setModelCoefficients(coeff);
179  projection.filter(pcout);
180  T ptout = pcout.points[0];
181  return ptout;
182 };
184 
185 template<class T>
186 T plane_model_road<T>::transform_pcl_point(std::string frame1, std::string frame2, T pt_origin)
187 {
188  tf::StampedTransform transform_ground;
189  try
190  {
191  plane_model_road::listener_atc_ground_ptr->lookupTransform(frame1, frame2, ros::Time(0), transform_ground);
192  }
193  catch (tf::TransformException ex)
194  {
195  ROS_ERROR("%s",ex.what());
196  }
197 
198  pcl::PointCloud<T> pc_point; // A point cloud with a single point
199  pc_point.points.push_back(pt_origin);
200  pcl_ros::transformPointCloud (pc_point,pc_point,transform_ground);
201  return pc_point.points[0];
202 };
204 
205 template<class T>
206 vector<double> plane_model_road<T>::find_RP_angle(T origin_projected, T pt_x_projected, T pt_y_projected)
207 {
208  double R,P;
209 
210  // Vector definition
211 
212  vector<double> vect_x;
213  vect_x.push_back(pt_x_projected.x-origin_projected.x);
214  vect_x.push_back(pt_x_projected.y-origin_projected.y);
215  vect_x.push_back(pt_x_projected.z-origin_projected.z);
216 
217  vector<double> vect_y;
218  vect_y.push_back(pt_y_projected.x-origin_projected.x);
219  vect_y.push_back(pt_y_projected.y-origin_projected.y);
220  vect_y.push_back(pt_y_projected.z-origin_projected.z);
221 
222  vector<double> vect_z;
223  vect_z.push_back(0); vect_z.push_back(0); vect_z.push_back(1);
224 
225  double norm_x=sqrt(pow(vect_x[0],2)+pow(vect_x[1],2)+pow(vect_x[2],2));
226  double norm_y=sqrt(pow(vect_y[0],2)+pow(vect_y[1],2)+pow(vect_y[2],2));
227  double norm_z=sqrt(pow(vect_z[0],2)+pow(vect_z[1],2)+pow(vect_z[2],2));
228 
229  R=acos((vect_y[0]*vect_z[0]+vect_y[1]*vect_z[1]+vect_y[2]*vect_z[2])/norm_y*norm_z);
230  P=acos((vect_x[0]*vect_z[0]+vect_x[1]*vect_z[1]+vect_x[2]*vect_z[2])/norm_x*norm_z);
231 
232  vector<double> result;
233  result.push_back(R); result.push_back(P);
234 
235  return result;
236 }
237 
238 #endif
T transform_pcl_point(std::string frame1, std::string frame2, T pt_origin)
Transform a pcl point between two ros frames It uses a tf::Stamped transform to transform a point bet...
tf::TransformBroadcaster * broadcast_ptr
pcl::PointCloud< T > outliers
tf::TransformListener * listener_atc_ground_ptr
T project_point_to_plane(const T ptin, const pcl::ModelCoefficients::Ptr coeff)
Project a point on a plane It uses pcl projectinliers to project a point on a plane.
pcl::PointCloud< T > get_plane_coefficients(pcl::PointCloud< T > cloud_in, int iterations, float threshold, pcl::ModelCoefficients::Ptr coefficients)
Calculate plane coefficients It uses pcl RANSAC model to estimate the coeeficients of a plane...
tf::Transform get_transform(T origin_projected, T pt_x_projected, T pt_y_projected)
get the transformation point Gets the road transform to publish
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 ...
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...
bool find_road_frame(pcl::PointCloud< T > cloud_in)
get the road reference frame
vector< double > find_RP_angle(T origin_projected, T pt_x_projected, T pt_y_projected)
find RP angles for road frame Gets the road frame RP angles. Notice that you don't need the Y...


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