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_INTERSECTION_CPP_
00035 #define _POLYGON_INTERSECTION_CPP_
00036
00037 #include "polygon_intersection.h"
00038
00039 int class_polygon_intersection::clear_all_polygons(void){polygons.erase(polygons.begin(), polygons.end());return 1;};
00040
00041
00042 int class_polygon_intersection::add_polygon_to_list(const pcl::PointCloud<pcl::PointXYZ>::Ptr p_pc)
00043 {
00044 pcl::PointCloud<pcl::PointXYZ> pc;
00045 pc=*p_pc;
00046 return add_polygon_to_list(&pc);
00047 }
00048
00049 int class_polygon_intersection::add_polygon_to_list(pcl::PointCloud<pcl::PointXYZ>* pc)
00050 {
00051
00052 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(CGALPoint_2(
00065 pc_local.at(i).x,
00066 pc_local.at(i).y));
00067
00068 }
00069 }
00070
00071 if (simplify_polygon(&polygon))
00072 {
00073 polygons.push_back(polygon);
00074 return 1;
00075 }
00076 else
00077 {
00078 ROS_ERROR("Could not add polygon. It is not simple and could not simplify");
00079 return 0;
00080 }
00081 }
00082
00083 int class_polygon_intersection::compute_polygon_intersection(pcl::PointCloud<pcl::PointXYZ>* pc_out)
00084 {
00085 CGALPwh_list_2 polygon_out;
00086
00087 CGALPwh_list_2::const_iterator it;
00088
00089
00090 CGAL::intersection (polygons[0], polygons[1], std::back_inserter(polygon_out));
00091
00092 for (size_t k=2; k<polygons.size(); k++)
00093 {
00094
00097 it = polygon_out.begin();
00098
00099 CGAL::intersection (*it, polygons[k], std::back_inserter(polygon_out));
00100 }
00101
00102 int count=0;
00103 for (it = polygon_out.begin(); it != polygon_out.end(); ++it)
00104 {
00105 count++;
00106 }
00107
00108 if(count!=1)
00109 {
00110 ROS_ERROR("Problem in polygon interception. Output was %d polygons",count);
00111 return 0;
00112 }
00113 else
00114 {
00115 it = polygon_out.begin();
00116
00117 if (!(*it).is_unbounded())
00118 {
00119
00120 pcl::PointCloud<pcl::PointXYZ> pc_out_local;
00121
00122 CGALPolygon_2::Vertex_const_iterator vit;
00123 for (vit = (*it).outer_boundary().vertices_begin(); vit != (*it).outer_boundary().vertices_end(); ++vit)
00124 {
00125 pcl::PointXYZ pt;
00126 pt.x = (*vit).x();
00127 pt.y = (*vit).y();
00128 pt.z = 0;
00129 pc_out_local.push_back(pt);
00130 }
00131
00132
00133 transform_local_to_global(&pc_out_local, pc_out);
00134 }
00135
00136 }
00137 return 1;}
00138
00139
00140 int class_polygon_intersection::compute_polygon_union(std::vector<pcl::PointCloud<pcl::PointXYZ> > *pc_list)
00141 {
00142 std::vector<CGALPolygon_with_holes_2> polygon_out_list;
00143
00144 printf("polygon union: i will do union of %d polygons\n", (int)polygons.size());
00145 for (size_t i=0; i< polygons.size(); i++)
00146 {
00147 printf("polygon %d has %d vertices\n", (int)i, (int)polygons[i].size());
00148 }
00149
00150 if (polygons.size()>0)
00151 {
00152
00153 CGALPolygon_with_holes_2 polygon_out;
00154 CGAL::join(polygons[0], polygons[0], polygon_out);
00155 polygon_out_list.push_back(polygon_out);
00156
00157 for (size_t i=1; i<polygons.size(); i++)
00158 {
00159 printf("Computing for plg %d\n", (int)i);
00160 bool was_merged=false;
00161 for (size_t j=0; j<polygon_out_list.size(); j++)
00162 {
00163
00164 if (CGAL::join(polygons[i], polygon_out_list[j], polygon_out_list[j]))
00165 {
00166 printf("plg %d was merged to list %d\n",(int)i,(int)j);
00167 was_merged=true;
00168 break;
00169 }
00170 else
00171 {
00172 printf("plg %d cannot be merged with plg list %d\n",(int)i,(int)j);
00173 }
00174
00175 }
00176
00177 if (was_merged==false)
00178 {
00179 CGALPolygon_with_holes_2 polygon_out;
00180 CGAL::join(polygons[i], polygons[i], polygon_out);
00181 polygon_out_list.push_back(polygon_out);
00182 printf("Adding plg %d to list. Now has %d size\n",(int)i, (int)polygon_out_list.size());
00183 }
00184
00185 }
00186
00188
00190 std::vector<CGALPolygon_with_holes_2> polygon_out_list1;
00191
00192 printf("Will try to compact list\n");
00193
00194
00195 polygon_out_list1.push_back(polygon_out_list[0]);
00196
00197 for (size_t i=1; i<polygon_out_list.size(); i++)
00198 {
00199 printf("Computing for plg %d\n", (int)i);
00200 bool was_merged=false;
00201 for (size_t j=0; j<polygon_out_list1.size(); j++)
00202 {
00203
00204 if (CGAL::join(polygon_out_list[i], polygon_out_list1[j], polygon_out_list1[j]))
00205 {
00206 printf("plg %d was merged to list %d\n",(int)i,(int)j);
00207 was_merged=true;
00208 break;
00209 }
00210 else
00211 {
00212 printf("plg %d cannot be merged with plg list %d\n",(int)i,(int)j);
00213 }
00214
00215 }
00216
00217 if (was_merged==false)
00218 {
00219 polygon_out_list1.push_back(polygon_out_list[i]);
00220 printf("Adding plg %d to list. Now has %d size\n",(int)i, (int)polygon_out_list1.size());
00221 }
00222
00223 }
00224
00225
00226
00227 for (size_t i=0; i< polygon_out_list1.size(); i++)
00228 {
00229
00230
00231 pcl::PointCloud<pcl::PointXYZ> pc_out_local;
00232 pcl::PointCloud<pcl::PointXYZ> pc_out;
00233
00234 CGALPolygon_2::Vertex_const_iterator vit;
00235
00236 for (vit = polygon_out_list1[i].outer_boundary().vertices_begin(); vit != polygon_out_list1[i].outer_boundary().vertices_end(); ++vit)
00237 {
00238 pcl::PointXYZ pt;
00239 pt.x = (*vit).x();
00240 pt.y = (*vit).y();
00241 pt.z = 0;
00242 pc_out_local.push_back(pt);
00243 }
00244
00246 transform_local_to_global(&pc_out_local, &pc_out);
00247 pc_list->push_back(pc_out);
00248 }
00249
00250 }
00251 else if (polygons.size()==0)
00252 {
00253 ROS_ERROR("No polygons given. No union can be performed");
00254
00255 }
00256
00257
00258 return 1;
00259 }
00260
00261 #endif
00262