points_from_volume.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 _points_from_volume_lib_H_
28 #define _points_from_volume_lib_H_
29 
38 //INCLUDES
41 #include <ros/ros.h>
42 #include <stdio.h>
43 #include <sensor_msgs/PointCloud2.h>
44 #include <pcl_ros/transforms.h>
45 #include <pcl/conversions.h>
46 #include <pcl/point_cloud.h>
47 #include <pcl/point_types.h>
48 #include <pcl/segmentation/extract_polygonal_prism_data.h>
49 #include <pcl/filters/extract_indices.h>
50 #include <pcl/filters/project_inliers.h>
51 #include <pcl_conversions/pcl_conversions.h>
52 typedef enum {SUCCESS, FAILURE}t_func_output;
53 
54 #define _CONVEX_LIB_DEBUG_ 0
55 
56 using namespace std;
57 
58 template<class T>
60 {
61 
62 public:
63 
65  {
66  flag_convexhull_set=false;
67  };
68 
70  {
71 #if _CONVEX_LIB_DEBUG_
72 printf("Destructor...\n");
73 #endif
74  };
75 
76 
83  t_func_output set_convex_hull(pcl::PointCloud<T>& pc_in)
84  {
85  convex_hull=pc_in;
86  convex_hull.header.frame_id = pc_in.header.frame_id;
87  #if _CONVEX_LIB_DEBUG_
88  cout<<"pc_in frame id on set_convex_hul -> "<<pc_in.header.frame_id<<endl;
89  #endif
90  flag_convexhull_set=true;
91  return SUCCESS;
92  };
93 
100  t_func_output set_convex_hull(const sensor_msgs::PointCloud2ConstPtr& pcmsg_in)
101  {
102  pcl::PointCloud<T> pc_in;
103  pcl::PCLPointCloud2 pcl_pc;
104  pcl_conversions::toPCL(*pcmsg_in, pcl_pc);
105  pcl::fromPCLPointCloud2(pcl_pc, pc_in);;
106  return set_convex_hull(pc_in);
107  };
108 
114  pcl::PointCloud<T> get_pc_in_volume()
115  {
116  return pc_in_volume;
117  };
118 
129  t_func_output convexhull_function(pcl::PointCloud<T>& pc_in, double positive_offset, double negative_offset, bool flag_in_out)
130  {
131  if(!flag_convexhull_set)
132  {
133  ROS_ERROR("Flag not set to TRUE");
134  return FAILURE;
135  }
136 
137  if(pc_in.header.frame_id!=convex_hull.header.frame_id)
138  {
139 #if _CONVEX_LIB_DEBUG_
140 cout<<"convex_hull frame id "<<convex_hull.header.frame_id<<endl;
141 cout<<"pc_in frame id on convexhull_function"<<pc_in.header.frame_id<<endl;
142 #endif
143  ROS_ERROR("Non-matching frame id's");
144  return FAILURE;
145  }
146 
147  pcl::ExtractPolygonalPrismData<T> epp;
148  typename pcl::PointCloud<T>::ConstPtr input_cloud_constptr;
149  input_cloud_constptr.reset (new pcl::PointCloud<T> (pc_in));
150  typename pcl::PointCloud<T>::ConstPtr convex_hull_constptr;
151  convex_hull_constptr.reset (new pcl::PointCloud<T> (convex_hull));
152 
153  pcl::ExtractIndices<T> extract; //Create the extraction object
154  pcl::PointIndices::Ptr indices;
155  indices.reset();
156  indices = pcl::PointIndices::Ptr(new pcl::PointIndices);
157 
158  pc_in_volume.header.frame_id=pc_in.header.frame_id;
159 
160  //Set epp parameters
161  epp.setInputCloud(input_cloud_constptr);
162  epp.setInputPlanarHull(convex_hull_constptr);
163  epp.setHeightLimits(negative_offset,positive_offset);
164  epp.setViewPoint(0,0,0); //i dont think this serves any purpose in the case of epp
165  epp.segment(*indices);
166 
167  pc_in_volume.points.clear();
168  pc_in_volume.height=1;
169  pc_in_volume.width=pc_in_volume.points.size();
170  if ((int)indices->indices.size()!=0)
171  {
172  extract.setInputCloud(pc_in.makeShared());
173  extract.setIndices(indices);
174  extract.setNegative(flag_in_out);
175  extract.filter(pc_in_volume);
176  }
177 // else
178 // {
179 // extract.setInputCloud(pc_in.makeShared());
180 // extract.setIndices(indices);
181 // extract.setNegative(flag_in_out);
182 // extract.filter(pc_in_volume);
183 //
184 // cout<<"NUMBER OF POINTS: "<<pc_in_volume.points.size()<<endl;
185 // }
186 // cout<<"NUMBER OF POINTS: "<<pc_in_volume.points.size()<<endl;
187  input_cloud_constptr.reset();
188  convex_hull_constptr.reset();
189  indices.reset();
190  return SUCCESS;
191  }
192 
193 
194 private:
195  pcl::PointCloud<T> pc_in_volume;
197  pcl::PointCloud<T> convex_hull;
198 };
199 
200 
201 #endif
pcl::PointCloud< T > convex_hull
t_func_output convexhull_function(pcl::PointCloud< T > &pc_in, double positive_offset, double negative_offset, bool flag_in_out)
Extract points from the pcl that are inside the convexhull.
t_func_output
t_func_output set_convex_hull(pcl::PointCloud< T > &pc_in)
Set the convexhull.
pcl::PointCloud< T > get_pc_in_volume()
Points in the desired volume.
t_func_output set_convex_hull(const sensor_msgs::PointCloud2ConstPtr &pcmsg_in)
Set the convexhull.
pcl::PointCloud< T > pc_in_volume


points_from_volume
Author(s): Joel Pereira
autogenerated on Mon Mar 2 2015 01:32:40