polygon_boolean_operations.cpp
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 ***************************************************************************************************/
34 #ifndef _polygon_boolean_operations_CPP_
35 #define _polygon_boolean_operations_CPP_
36 
38 
39 
42 
43 int class_polygon_boolean_operations::insert(const pcl::PointCloud<pcl::PointXYZ>::Ptr p_pc)
44 {
45  pcl::PointCloud<pcl::PointXYZ> pc;
46  pc=*p_pc;
47  return insert(&pc);
48 }
49 
51 {
52  PS_CGALPolygon_2 polygon;
53 
54  //declare de point cloud in local coordinates
55  pcl::PointCloud<pcl::PointXYZ> pc_local;
56 
57  //transform the pc to local coordinates
58  transform_global_to_local(pc, &pc_local);
59 
60  for (size_t i=0; i< pc_local.points.size(); i++) //Build the CGAL polygon
61  {
62  if (!isnan(pc_local.at(i).x))
63  {
64  polygon.push_back(PS_CGALPoint_2(
65  pc_local.at(i).x,
66  pc_local.at(i).y));
67  }
68  }
69 
70  return polygon;
71 }
72 
73 int class_polygon_boolean_operations::insert(pcl::PointCloud<pcl::PointXYZ>* pc)
74 {
75  //declare a polygon
77 
78  if (simplify_polygon(&polygon))
79  {
80  S.insert(polygon); //Push back on the polygons vector
81  return 1;
82  }
83  else
84  {
85  ROS_ERROR("Could not insert polygon. Input polygon is not simple and could not simplify");
86  print_polygon(polygon);
87  return 0;
88  }
89 }
90 
91 int class_polygon_boolean_operations::join(pcl::PointCloud<pcl::PointXYZ>* pc)
92 {
93  //declare a polygon
95 
96  if (simplify_polygon(&polygon))
97  {
98  S.join(polygon); //Push back on the polygons vector
99  return 1;
100  }
101  else
102  {
103  ROS_ERROR("Could not join polygon. Input polygon is not simple and could not simplify");
104  print_polygon(polygon);
105  return 0;
106  }
107 }
108 
109 int class_polygon_boolean_operations::intersection(pcl::PointCloud<pcl::PointXYZ>* pc)
110 {
111  //declare a polygon
113 
114  if (simplify_polygon(&polygon))
115  {
116  S.intersection(polygon); //Push back on the polygons vector
117  return 1;
118  }
119  else
120  {
121  ROS_ERROR("Could not intersect polygon. Input polygon is not simple and could not simplify");
122  print_polygon(polygon);
123  return 0;
124  }
125 }
126 
128 {
129  S.complement();
130  return 1;
131 }
132 
133 
134 int class_polygon_boolean_operations::get_largest_pcl(pcl::PointCloud<pcl::PointXYZ>* pc_out)
135 {
136  std::list<PBO_Polygon_with_holes_2> res;
137  std::list<PBO_Polygon_with_holes_2>::const_iterator it;
138 
139  std::cout << "The result contains " << S.number_of_polygons_with_holes() << " components:" << std::endl;
140 
141  S.polygons_with_holes (std::back_inserter (res));
142 
143  for (it = res.begin(); it != res.end(); ++it)
144  {
145  pcl::PointCloud<pcl::PointXYZ> pc_out_local;
146 
147  PS_CGALPolygon_2::Vertex_const_iterator vit;
148  for (vit = (*it).outer_boundary().vertices_begin(); vit != (*it).outer_boundary().vertices_end(); ++vit)
149  {
150  pcl::PointXYZ pt;
151  pt.x = CGAL::to_double((*vit).x());
152  pt.y = CGAL::to_double((*vit).y());
153  pt.z = 0;
154  pc_out_local.push_back(pt);
155  }
156 
157  //transform the pc to global coordinates
158 
159  if (it==res.begin())
160  transform_local_to_global(&pc_out_local, pc_out);
161  else
162  {
163  if (pc_out_local.points.size() > pc_out->points.size())
164  transform_local_to_global(&pc_out_local, pc_out);
165 
166  }
167 
168  }
169 
170 
171 
172  return 1;
173 }
174 
175 
176 
177 int class_polygon_boolean_operations::get_all_pcls(std::vector<pcl::PointCloud<pcl::PointXYZ> >* pc_out_vector)
178 {
179  std::list<PBO_Polygon_with_holes_2> res;
180  std::list<PBO_Polygon_with_holes_2>::const_iterator it;
181 
182  pc_out_vector->erase(pc_out_vector->begin(), pc_out_vector->end());
183 
184  std::cout << "The result contains " << S.number_of_polygons_with_holes() << " components:" << std::endl;
185 
186  S.polygons_with_holes (std::back_inserter (res));
187 
188  int k=0;
189  for (it = res.begin(); it != res.end(); ++it)
190  {
191 
192  pcl::PointCloud<pcl::PointXYZ> pc_out_local;
193 
194  ROS_INFO("polygon %d is simple %d",k,(*it).outer_boundary().is_simple());
195 
196 
197  PS_CGALPolygon_2::Vertex_const_iterator vit;
198  for (vit = (*it).outer_boundary().vertices_begin(); vit != (*it).outer_boundary().vertices_end(); ++vit)
199  {
200  pcl::PointXYZ pt;
201  pt.x = CGAL::to_double((*vit).x());
202  pt.y = CGAL::to_double((*vit).y());
203  pt.z = 0;
204  pc_out_local.push_back(pt);
205  }
206 
207  //transform the pc to global coordinates
208  pcl::PointCloud<pcl::PointXYZ> pc_out;
209  transform_local_to_global(&pc_out_local, &pc_out);
210 
211  pc_out_vector->push_back(pc_out);
212  }
213  return 1;
214 }
215 
216 int class_polygon_boolean_operations::get_first_pcl(pcl::PointCloud<pcl::PointXYZ>* pc_out)
217 {
218  std::list<PBO_Polygon_with_holes_2> res;
219  std::list<PBO_Polygon_with_holes_2>::const_iterator it;
220 
221  std::cout << "The result contains " << S.number_of_polygons_with_holes() << " components:" << std::endl;
222 
223  S.polygons_with_holes (std::back_inserter (res));
224 
225  for (it = res.begin(); it != res.end(); ++it)
226  {
227  pcl::PointCloud<pcl::PointXYZ> pc_out_local;
228 
229  PS_CGALPolygon_2::Vertex_const_iterator vit;
230  for (vit = (*it).outer_boundary().vertices_begin(); vit != (*it).outer_boundary().vertices_end(); ++vit)
231  {
232  pcl::PointXYZ pt;
233  pt.x = CGAL::to_double((*vit).x());
234  pt.y = CGAL::to_double((*vit).y());
235  pt.z = 0;
236  pc_out_local.push_back(pt);
237  }
238 
239  //transform the pc to global coordinates
240  transform_local_to_global(&pc_out_local, pc_out);
241 
242  break;
243  }
244 
245 
246 
247  return 1;
248 }
249 
251  {
252  // Print the result.
253  std::list<PBO_Polygon_with_holes_2> res;
254  std::list<PBO_Polygon_with_holes_2>::const_iterator it;
255 
256  std::cout << "The result contains " << S.number_of_polygons_with_holes() << " components:" << std::endl;
257 
258  S.polygons_with_holes (std::back_inserter (res));
259 
260  for (it = res.begin(); it != res.end(); ++it)
261  {
262  std::cout << "--> ";
264  }
265 
266  return 1;
267  }
268 
269 
270 #endif
271 
int get_all_pcls(std::vector< pcl::PointCloud< pcl::PointXYZ > > *pc_out_vector)
int transform_global_to_local(pcl::PointCloud< pcl::PointXYZ > *pc_global, pcl::PointCloud< pcl::PointXYZ > *pc_local)
int insert(pcl::PointCloud< pcl::PointXYZ >::Ptr p_pc)
PS_CGALKernel::Point_2 PS_CGALPoint_2
PBO_Polygon_2 from_pcl_to_cgalpolygon(pcl::PointCloud< pcl::PointXYZ > *pc)
int get_largest_pcl(pcl::PointCloud< pcl::PointXYZ > *pc_out)
int transform_local_to_global(pcl::PointCloud< pcl::PointXYZ > *pc_local, pcl::PointCloud< pcl::PointXYZ > *pc_global)
int simplify_polygon(PS_CGALPolygon_2 *p)
int join(pcl::PointCloud< pcl::PointXYZ > *pc)
int intersection(pcl::PointCloud< pcl::PointXYZ > *pc)
CGAL::Polygon_2< PS_CGALKernel > PS_CGALPolygon_2
int get_first_pcl(pcl::PointCloud< pcl::PointXYZ > *pc_out)
CGAL::Polygon_2< PBO_Kernel > PBO_Polygon_2
void print_polygon_with_holes(const CGAL::Polygon_with_holes_2< Kernel, Container > &pwh)
Defines the class bo_boolean operations *.
void print_polygon(const CGAL::Polygon_2< Kernel, Container > &P)


bo_polygon2d
Author(s): Miguel Oliveira
autogenerated on Mon Mar 2 2015 01:31:29