00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00032 #ifndef _PLANE_ROAD_EXTRACTION_HPP_
00033 #define _PLANE_ROAD_EXTRACTION_HPP_
00034
00035 #include "plane_road_extraction.h"
00036
00037 template <class T>
00038 void plane_road_extraction<T>::filter (const sensor_msgs::PointCloud2Ptr& msg)
00039 {
00040 PointCloud<T> cloud;
00041
00042 fromROSMsg(*msg,cloud);
00043
00044 if ((int)cloud.points.size()>0)
00045 {
00046 tf::Transform road_tf=pms.find_and_publish_road_frame(cloud);
00047
00048
00049 T point_origin;
00050 T point_origin_transformed;
00051 T point_away;
00052 T point_away_transformed;
00053 T pt;
00054
00055 point_origin.x=0; point_origin.y=0; point_origin.z=0;
00056 point_away.x=50; point_away.y=0; point_away.z=0;
00057 point_origin_transformed=transform_pcl_point(cloud.header.frame_id, road_tf, point_origin);
00058 point_away_transformed=transform_pcl_point(cloud.header.frame_id, road_tf, point_away);
00059
00060 PointCloud<T> road_hull;
00061 road_hull.header.frame_id=cloud.header.frame_id;
00062 pt.x = -2; pt.y=50; pt.z=point_origin_transformed.z;
00063 road_hull.points.push_back(pt);
00064 pt.x = 50; pt.y=50; pt.z=point_away_transformed.z;
00065 road_hull.points.push_back(pt);
00066 pt.x = 50; pt.y= -50; pt.z=point_away_transformed.z;
00067 road_hull.points.push_back(pt);
00068 pt.x = -2; pt.y=-50; pt.z=point_origin_transformed.z;
00069 road_hull.points.push_back(pt);
00070
00071
00072 PointCloud<T> cloud_road;
00073 PointCloud<T> cloud_cluster;
00074 points_from_volume<T> pfv_cloud;
00075 cloud_road.header.frame_id=cloud.header.frame_id;
00076 cloud_cluster.header.frame_id=cloud.header.frame_id;
00077 pfv_cloud.set_convex_hull(road_hull);
00078 pfv_cloud.convexhull_function(cloud, z_max, z_min, false);
00079 cloud_road=pfv_cloud.get_pc_in_volume();
00080 pfv_cloud.convexhull_function(cloud, 20, z_max, false);
00081 cloud_cluster=pfv_cloud.get_pc_in_volume();
00082
00083
00084 PointCloud<T> cloud_road_projected;
00085 cloud_road_projected = project_cloud_on_plane(cloud_road, pms.coef);
00086
00087
00088 PointCloud<T> road_perimeter;
00089 ConvexHull<T> chull;
00090 chull.setInputCloud (cloud_road_projected.makeShared());
00091 chull.reconstruct (road_perimeter);
00092
00093
00094 points_from_volume<T> pfv;
00095 PointCloud<T> inside_cloud;
00096 inside_cloud.header.frame_id=msg->header.frame_id;
00097 pfv.set_convex_hull(road_perimeter);
00098 pfv.convexhull_function(cloud_cluster, 20, -20, false);
00099 inside_cloud=pfv.get_pc_in_volume();
00100
00101
00102
00103 sensor_msgs::PointCloud2 msg_road;
00104 sensor_msgs::PointCloud2 msg_cluster;
00105 sensor_msgs::PointCloud2 msg_perimeter;
00106 toROSMsg(cloud_road_projected,msg_road);
00107 toROSMsg(inside_cloud,msg_cluster);
00108 toROSMsg(road_perimeter,msg_perimeter);
00109 pub_clusters_ptr->publish(msg_cluster);
00110 pub_road_ptr->publish(msg_road);
00111 pub_road_perimeter_ptr->publish(msg_perimeter);
00112
00113 }
00114 };
00116
00117 template<class T>
00118 T plane_road_extraction<T>::transform_pcl_point(string frame1, tf::Transform transform, T pt_origin)
00119 {
00120 PointCloud<T> pc_point;
00121 pc_point.points.push_back(pt_origin);
00122 pcl_ros::transformPointCloud (pc_point,pc_point,transform);
00123 return pc_point.points[0];
00124 };
00126
00127 template<class T>
00128 PointCloud<T> plane_road_extraction<T>::project_cloud_on_plane(PointCloud<T> cloud_in, ModelCoefficients::Ptr coefficients)
00129 {
00130 typename PointCloud<T>::Ptr cloud_in_ptr (new PointCloud<T> (cloud_in));
00131 PointCloud<T> cloud_out;
00132
00133
00134 ProjectInliers<T> projection;
00135 projection.setModelType(SACMODEL_PLANE);
00136
00137 projection.setInputCloud(cloud_in_ptr);
00138 projection.setModelCoefficients(coefficients);
00139 projection.filter(cloud_out);
00140
00141 cloud_in_ptr.reset();
00142 return cloud_out;
00143 }
00144
00145 #endif