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
00037 #ifndef _POLYGON_INTERSECTION_H_
00038 #define _POLYGON_INTERSECTION_H_
00039
00040 #define PFLN {printf("DEBUG PRINT FILE %s LINE %d\n",__FILE__,__LINE__);}
00041
00042
00045 #include <ros/ros.h>
00046
00047 #include <pcl/point_cloud.h>
00048 #include <pcl/point_types.h>
00049 #include <pcl_ros/transforms.h>
00050 #include <tf/tf.h>
00051
00052
00053 #include <CGAL/basic.h>
00054 #include <CGAL/Polygon_2.h>
00055 #include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
00056 #include <CGAL/Partition_traits_2.h>
00057 #include <CGAL/Partition_is_valid_traits_2.h>
00058 #include <CGAL/polygon_function_objects.h>
00059 #include <CGAL/partition_2.h>
00060 #include <CGAL/point_generators_2.h>
00061 #include <CGAL/Polygon_set_2.h>
00062
00063 #include <CGAL/random_polygon_2.h>
00064
00065
00066
00067 #include <CGAL/Cartesian.h>
00068 #include <CGAL/Boolean_set_operations_2.h>
00069
00070
00071 #include <bo_polygon2d/polygon_simplification.h>
00072 #include <bo_polygon2d/transform_wrapper.h>
00073
00074 typedef CGAL::Exact_predicates_inexact_constructions_kernel CGALKernel;
00075 typedef CGALKernel::Point_2 CGALPoint_2;
00076 typedef CGAL::Polygon_2<CGALKernel> CGALPolygon_2;
00077 typedef CGAL::Polygon_with_holes_2<CGALKernel> CGALPolygon_with_holes_2;
00078 typedef std::list<CGALPolygon_with_holes_2> CGALPwh_list_2;
00079
00080
00081 class class_polygon_intersection: public class_polygon_simplification, public class_transform_wrapper
00082 {
00083 public:
00084 class_polygon_intersection(void){};
00085 ~class_polygon_intersection(void){};
00086
00087 int clear_all_polygons(void);
00088 int add_polygon_to_list(pcl::PointCloud<pcl::PointXYZ>::Ptr p_pc);
00089 int add_polygon_to_list(pcl::PointCloud<pcl::PointXYZ>* pc);
00090 int compute_polygon_intersection(pcl::PointCloud<pcl::PointXYZ>* pc_out);
00091 int compute_polygon_union(std::vector<pcl::PointCloud<pcl::PointXYZ> > *pc_list);
00092
00093 protected:
00094 std::vector<CGALPolygon_2> polygons;
00095
00096
00097 };
00098
00099
00100 #endif
00101