33 #ifndef _projection_mesh_H_
34 #define _projection_mesh_H_
41 #include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
42 #include <CGAL/IO/Color.h>
43 #include <CGAL/Triangulation_2.h>
44 #include <CGAL/Triangulation_vertex_base_with_info_2.h>
46 #include <CGAL/Polygon_2_algorithms.h>
47 #include <CGAL/Delaunay_triangulation_2.h>
49 #include <CGAL/basic.h>
50 #include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
51 #include <CGAL/Exact_predicates_exact_constructions_kernel.h>
52 #include <CGAL/Partition_traits_2.h>
53 #include <CGAL/Partition_is_valid_traits_2.h>
54 #include <CGAL/polygon_function_objects.h>
55 #include <CGAL/partition_2.h>
56 #include <CGAL/point_generators_2.h>
57 #include <CGAL/Polygon_set_2.h>
58 #include <CGAL/Cartesian.h>
59 #include <CGAL/polygon_function_objects.h>
60 #include <CGAL/random_polygon_2.h>
62 #include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
63 #include <CGAL/Constrained_Delaunay_triangulation_2.h>
65 #include <pcl/segmentation/sac_segmentation.h>
66 #include <pcl/filters/project_inliers.h>
67 #include <pcl/point_cloud.h>
68 #include <pcl/point_types.h>
69 #include <pcl_ros/transforms.h>
70 #include <pcl/ModelCoefficients.h>
72 #include <visualization_msgs/Marker.h>
74 #include <CGAL/Constrained_Delaunay_triangulation_2.h>
75 #include <CGAL/Constrained_triangulation_plus_2.h>
77 #include <opencv2/imgproc/imgproc.hpp>
78 #include <opencv2/highgui/highgui.hpp>
79 #include <opencv2/core/core.hpp>
83 typedef CGAL::Exact_predicates_inexact_constructions_kernel
K;
89 template <
class Gt,
class Fb >
97 template <
typename TDS2 >
136 typedef CGAL::Triangulation_data_structure_2<CGAL::Triangulation_vertex_base_with_info_2<t_vertex_extension, K>,
140 typedef CGAL::Constrained_triangulation_plus_2<CGAL::Constrained_Delaunay_triangulation_2<K, TDS_projection_mesh, CGAL::No_intersection_tag> >
PT;
159 int export_triangles(pcl::PointCloud<pcl::PointXYZRGB>* vertex_list, std::vector<float>* face_weights);
int initialize_all_faces_status(void)
CGAL::Exact_predicates_inexact_constructions_kernel K
bool is_in_domain() const
int compute_face_weights(void)
void discoverComponents(const PT &ct)
face_extension(Vertex_handle v0, Vertex_handle v1, Vertex_handle v2, Face_handle n0, Face_handle n1, Face_handle n2)
int print_all_vertices(void)
CGAL::Triangulation_data_structure_2< CGAL::Triangulation_vertex_base_with_info_2< t_vertex_extension, K >, face_extension< K, CGAL::Constrained_triangulation_face_base_2< K > > > TDS_projection_mesh
CDT::All_faces_iterator All_faces_iterator
int draw_mesh_triangles(cv::Mat *image, cv::Scalar color, int thickness)
class_projection_mesh(void)
Fb::Face_handle Face_handle
int clear_constraints(void)
face_extension< Gt, Fb2 > Other
void set_in_domain(const bool b)
void discoverComponent(const PT &ct, PT::Face_handle start, int index, std::list< PT::Edge > &border)
int initialize_visited(void)
Fb::Vertex_handle Vertex_handle
Fb::Vertex_handle Vertex_handle
int set_constraint_polygon(std::vector< pcl::PointXY > *p)
face_extension(Vertex_handle v0, Vertex_handle v1, Vertex_handle v2)
~class_projection_mesh(void)
CGAL::Constrained_triangulation_plus_2< CGAL::Constrained_Delaunay_triangulation_2< K, TDS_projection_mesh, CGAL::No_intersection_tag > > PT
int add_vertex_to_mesh(double x, double y, double z, float rgb, float weight)
int export_triangles_in_order(pcl::PointCloud< pcl::PointXYZRGB > *vertex_list, std::vector< float > *face_weights)
Fb::Face_handle Face_handle
CDT::Face_handle Face_handle
int export_triangles(pcl::PointCloud< pcl::PointXYZRGB > *vertex_list, std::vector< float > *face_weights)
Fb::template Rebind_TDS< TDS2 >::Other Fb2