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
00027 #ifndef _points_from_volume_lib_H_
00028 #define _points_from_volume_lib_H_
00029
00038
00039
00041 #include <ros/ros.h>
00042 #include <stdio.h>
00043 #include <sensor_msgs/PointCloud2.h>
00044 #include <pcl_ros/transforms.h>
00045 #include <pcl/ros/conversions.h>
00046 #include <pcl/point_cloud.h>
00047 #include <pcl/point_types.h>
00048 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00049 #include <pcl/filters/extract_indices.h>
00050 #include <pcl/filters/project_inliers.h>
00051 typedef enum {SUCCESS, FAILURE}t_func_output;
00052
00053 #define _CONVEX_LIB_DEBUG_ 0
00054
00055 using namespace std;
00056
00057 template<class T>
00058 class points_from_volume
00059 {
00060
00061 public:
00062
00063 points_from_volume()
00064 {
00065 flag_convexhull_set=false;
00066 };
00067
00068 ~points_from_volume()
00069 {
00070 #if _CONVEX_LIB_DEBUG_
00071 printf("Destructor...\n");
00072 #endif
00073 };
00074
00075
00082 t_func_output set_convex_hull(pcl::PointCloud<T>& pc_in)
00083 {
00084 convex_hull=pc_in;
00085 convex_hull.header.frame_id = pc_in.header.frame_id;
00086 #if _CONVEX_LIB_DEBUG_
00087 cout<<"pc_in frame id on set_convex_hul -> "<<pc_in.header.frame_id<<endl;
00088 #endif
00089 flag_convexhull_set=true;
00090 return SUCCESS;
00091 };
00092
00099 t_func_output set_convex_hull(const sensor_msgs::PointCloud2ConstPtr& pcmsg_in)
00100 {
00101 pcl::PointCloud<T> pc_in;
00102 pcl::fromROSMsg(*pcmsg_in,pc_in);
00103 return set_convex_hull(pc_in);
00104 };
00105
00111 pcl::PointCloud<T> get_pc_in_volume()
00112 {
00113 return pc_in_volume;
00114 };
00115
00126 t_func_output convexhull_function(pcl::PointCloud<T>& pc_in, double positive_offset, double negative_offset, bool flag_in_out)
00127 {
00128 if(!flag_convexhull_set)
00129 {
00130 ROS_ERROR("Flag not set to TRUE");
00131 return FAILURE;
00132 }
00133
00134 if(pc_in.header.frame_id!=convex_hull.header.frame_id)
00135 {
00136 #if _CONVEX_LIB_DEBUG_
00137 cout<<"convex_hull frame id "<<convex_hull.header.frame_id<<endl;
00138 cout<<"pc_in frame id on convexhull_function"<<pc_in.header.frame_id<<endl;
00139 #endif
00140 ROS_ERROR("Non-matching frame id's");
00141 return FAILURE;
00142 }
00143
00144 pcl::ExtractPolygonalPrismData<T> epp;
00145 typename pcl::PointCloud<T>::ConstPtr input_cloud_constptr;
00146 input_cloud_constptr.reset (new pcl::PointCloud<T> (pc_in));
00147 typename pcl::PointCloud<T>::ConstPtr convex_hull_constptr;
00148 convex_hull_constptr.reset (new pcl::PointCloud<T> (convex_hull));
00149
00150 pcl::ExtractIndices<T> extract;
00151 pcl::PointIndices::Ptr indices;
00152 indices.reset();
00153 indices = pcl::PointIndices::Ptr(new pcl::PointIndices);
00154
00155 pc_in_volume.header.frame_id=pc_in.header.frame_id;
00156
00157
00158 epp.setInputCloud(input_cloud_constptr);
00159 epp.setInputPlanarHull(convex_hull_constptr);
00160 epp.setHeightLimits(negative_offset,positive_offset);
00161 epp.setViewPoint(0,0,0);
00162 epp.segment(*indices);
00163
00164 pc_in_volume.points.clear();
00165 pc_in_volume.height=1;
00166 pc_in_volume.width=pc_in_volume.points.size();
00167 if ((int)indices->indices.size()!=0)
00168 {
00169 extract.setInputCloud(pc_in.makeShared());
00170 extract.setIndices(indices);
00171 extract.setNegative(flag_in_out);
00172 extract.filter(pc_in_volume);
00173 }
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183
00184 input_cloud_constptr.reset();
00185 convex_hull_constptr.reset();
00186 indices.reset();
00187 return SUCCESS;
00188 }
00189
00190
00191 private:
00192 pcl::PointCloud<T> pc_in_volume;
00193 bool flag_convexhull_set;
00194 pcl::PointCloud<T> convex_hull;
00195 };
00196
00197
00198 #endif