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
00034 #ifndef _polygon_boolean_operations_CPP_
00035 #define _polygon_boolean_operations_CPP_
00036
00037 #include <bo_polygon2d/polygon_boolean_operations.h>
00038
00039
00040 class_polygon_boolean_operations::class_polygon_boolean_operations(void){};
00041 class_polygon_boolean_operations::~class_polygon_boolean_operations(void){};
00042
00043 int class_polygon_boolean_operations::insert(const pcl::PointCloud<pcl::PointXYZ>::Ptr p_pc)
00044 {
00045 pcl::PointCloud<pcl::PointXYZ> pc;
00046 pc=*p_pc;
00047 return insert(&pc);
00048 }
00049
00050 PBO_Polygon_2 class_polygon_boolean_operations::from_pcl_to_cgalpolygon(pcl::PointCloud<pcl::PointXYZ>* pc)
00051 {
00052 PS_CGALPolygon_2 polygon;
00053
00054
00055 pcl::PointCloud<pcl::PointXYZ> pc_local;
00056
00057
00058 transform_global_to_local(pc, &pc_local);
00059
00060 for (size_t i=0; i< pc_local.points.size(); i++)
00061 {
00062 if (!isnan(pc_local.at(i).x))
00063 {
00064 polygon.push_back(PS_CGALPoint_2(
00065 pc_local.at(i).x,
00066 pc_local.at(i).y));
00067 }
00068 }
00069
00070 return polygon;
00071 }
00072
00073 int class_polygon_boolean_operations::insert(pcl::PointCloud<pcl::PointXYZ>* pc)
00074 {
00075
00076 PS_CGALPolygon_2 polygon = from_pcl_to_cgalpolygon(pc);
00077
00078 if (simplify_polygon(&polygon))
00079 {
00080 S.insert(polygon);
00081 return 1;
00082 }
00083 else
00084 {
00085 ROS_ERROR("Could not insert polygon. Input polygon is not simple and could not simplify");
00086 print_polygon(polygon);
00087 return 0;
00088 }
00089 }
00090
00091 int class_polygon_boolean_operations::join(pcl::PointCloud<pcl::PointXYZ>* pc)
00092 {
00093
00094 PS_CGALPolygon_2 polygon = from_pcl_to_cgalpolygon(pc);
00095
00096 if (simplify_polygon(&polygon))
00097 {
00098 S.join(polygon);
00099 return 1;
00100 }
00101 else
00102 {
00103 ROS_ERROR("Could not join polygon. Input polygon is not simple and could not simplify");
00104 print_polygon(polygon);
00105 return 0;
00106 }
00107 }
00108
00109 int class_polygon_boolean_operations::intersection(pcl::PointCloud<pcl::PointXYZ>* pc)
00110 {
00111
00112 PS_CGALPolygon_2 polygon = from_pcl_to_cgalpolygon(pc);
00113
00114 if (simplify_polygon(&polygon))
00115 {
00116 S.intersection(polygon);
00117 return 1;
00118 }
00119 else
00120 {
00121 ROS_ERROR("Could not intersect polygon. Input polygon is not simple and could not simplify");
00122 print_polygon(polygon);
00123 return 0;
00124 }
00125 }
00126
00127 int class_polygon_boolean_operations::complement(void)
00128 {
00129 S.complement();
00130 return 1;
00131 }
00132
00133
00134 int class_polygon_boolean_operations::get_largest_pcl(pcl::PointCloud<pcl::PointXYZ>* pc_out)
00135 {
00136 std::list<PBO_Polygon_with_holes_2> res;
00137 std::list<PBO_Polygon_with_holes_2>::const_iterator it;
00138
00139 std::cout << "The result contains " << S.number_of_polygons_with_holes() << " components:" << std::endl;
00140
00141 S.polygons_with_holes (std::back_inserter (res));
00142
00143 for (it = res.begin(); it != res.end(); ++it)
00144 {
00145 pcl::PointCloud<pcl::PointXYZ> pc_out_local;
00146
00147 PS_CGALPolygon_2::Vertex_const_iterator vit;
00148 for (vit = (*it).outer_boundary().vertices_begin(); vit != (*it).outer_boundary().vertices_end(); ++vit)
00149 {
00150 pcl::PointXYZ pt;
00151 pt.x = CGAL::to_double((*vit).x());
00152 pt.y = CGAL::to_double((*vit).y());
00153 pt.z = 0;
00154 pc_out_local.push_back(pt);
00155 }
00156
00157
00158
00159 if (it==res.begin())
00160 transform_local_to_global(&pc_out_local, pc_out);
00161 else
00162 {
00163 if (pc_out_local.points.size() > pc_out->points.size())
00164 transform_local_to_global(&pc_out_local, pc_out);
00165
00166 }
00167
00168 }
00169
00170
00171
00172 return 1;
00173 }
00174
00175
00176
00177 int class_polygon_boolean_operations::get_all_pcls(std::vector<pcl::PointCloud<pcl::PointXYZ> >* pc_out_vector)
00178 {
00179 std::list<PBO_Polygon_with_holes_2> res;
00180 std::list<PBO_Polygon_with_holes_2>::const_iterator it;
00181
00182 pc_out_vector->erase(pc_out_vector->begin(), pc_out_vector->end());
00183
00184 std::cout << "The result contains " << S.number_of_polygons_with_holes() << " components:" << std::endl;
00185
00186 S.polygons_with_holes (std::back_inserter (res));
00187
00188 int k=0;
00189 for (it = res.begin(); it != res.end(); ++it)
00190 {
00191
00192 pcl::PointCloud<pcl::PointXYZ> pc_out_local;
00193
00194 ROS_INFO("polygon %d is simple %d",k,(*it).outer_boundary().is_simple());
00195
00196
00197 PS_CGALPolygon_2::Vertex_const_iterator vit;
00198 for (vit = (*it).outer_boundary().vertices_begin(); vit != (*it).outer_boundary().vertices_end(); ++vit)
00199 {
00200 pcl::PointXYZ pt;
00201 pt.x = CGAL::to_double((*vit).x());
00202 pt.y = CGAL::to_double((*vit).y());
00203 pt.z = 0;
00204 pc_out_local.push_back(pt);
00205 }
00206
00207
00208 pcl::PointCloud<pcl::PointXYZ> pc_out;
00209 transform_local_to_global(&pc_out_local, &pc_out);
00210
00211 pc_out_vector->push_back(pc_out);
00212 }
00213 return 1;
00214 }
00215
00216 int class_polygon_boolean_operations::get_first_pcl(pcl::PointCloud<pcl::PointXYZ>* pc_out)
00217 {
00218 std::list<PBO_Polygon_with_holes_2> res;
00219 std::list<PBO_Polygon_with_holes_2>::const_iterator it;
00220
00221 std::cout << "The result contains " << S.number_of_polygons_with_holes() << " components:" << std::endl;
00222
00223 S.polygons_with_holes (std::back_inserter (res));
00224
00225 for (it = res.begin(); it != res.end(); ++it)
00226 {
00227 pcl::PointCloud<pcl::PointXYZ> pc_out_local;
00228
00229 PS_CGALPolygon_2::Vertex_const_iterator vit;
00230 for (vit = (*it).outer_boundary().vertices_begin(); vit != (*it).outer_boundary().vertices_end(); ++vit)
00231 {
00232 pcl::PointXYZ pt;
00233 pt.x = CGAL::to_double((*vit).x());
00234 pt.y = CGAL::to_double((*vit).y());
00235 pt.z = 0;
00236 pc_out_local.push_back(pt);
00237 }
00238
00239
00240 transform_local_to_global(&pc_out_local, pc_out);
00241
00242 break;
00243 }
00244
00245
00246
00247 return 1;
00248 }
00249
00250 int class_polygon_boolean_operations::print(void)
00251 {
00252
00253 std::list<PBO_Polygon_with_holes_2> res;
00254 std::list<PBO_Polygon_with_holes_2>::const_iterator it;
00255
00256 std::cout << "The result contains " << S.number_of_polygons_with_holes() << " components:" << std::endl;
00257
00258 S.polygons_with_holes (std::back_inserter (res));
00259
00260 for (it = res.begin(); it != res.end(); ++it)
00261 {
00262 std::cout << "--> ";
00263 print_polygon_with_holes (*it);
00264 }
00265
00266 return 1;
00267 }
00268
00269
00270 #endif
00271