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
00033 #ifndef _CONSTRAINED_DELAUNAY_TRIANGULATION_H_
00034 #define _CONSTRAINED_DELAUNAY_TRIANGULATION_H_
00035
00036
00037
00038
00039
00040
00041
00042 #include <boost/function.hpp>
00043
00044 #include <CGAL/basic.h>
00045 #include <CGAL/assertions.h>
00046 #include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
00047 #include <CGAL/IO/Color.h>
00048 #include <CGAL/Triangulation_2.h>
00049 #include <CGAL/Triangulation_vertex_base_with_info_2.h>
00050
00051 #include <CGAL/Triangulation_hierarchy_2.h>
00052 #include <CGAL/Polygon_2_algorithms.h>
00053 #include <CGAL/Delaunay_triangulation_2.h>
00054
00055 #include <CGAL/basic.h>
00056 #include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
00057 #include <CGAL/Exact_predicates_exact_constructions_kernel.h>
00058 #include <CGAL/Partition_traits_2.h>
00059 #include <CGAL/Partition_is_valid_traits_2.h>
00060 #include <CGAL/polygon_function_objects.h>
00061 #include <CGAL/partition_2.h>
00062 #include <CGAL/point_generators_2.h>
00063 #include <CGAL/Polygon_set_2.h>
00064 #include <CGAL/Cartesian.h>
00065 #include <CGAL/polygon_function_objects.h>
00066 #include <CGAL/random_polygon_2.h>
00067
00068 #include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
00069 #include <CGAL/Constrained_Delaunay_triangulation_2.h>
00070
00071 #include <pcl/segmentation/sac_segmentation.h>
00072 #include <pcl/filters/project_inliers.h>
00073 #include <pcl/point_cloud.h>
00074 #include <pcl/point_types.h>
00075 #include <pcl_ros/transforms.h>
00076 #include <pcl/ModelCoefficients.h>
00077 #include <tf/tf.h>
00078 #include <visualization_msgs/Marker.h>
00079
00080 #include <CGAL/Constrained_Delaunay_triangulation_2.h>
00081 #include <CGAL/Constrained_triangulation_plus_2.h>
00082 #include <CGAL/circulator_bases.h>
00083 #include "polygon_intersection.h"
00084 #include <CGAL/basic.h>
00085
00086
00087
00088 typedef CGAL::Exact_predicates_exact_constructions_kernel K_exact;
00089
00090
00091
00092 typedef struct {double z;float rgb; size_t index;} t_enriched_vertex_base_2;
00093 typedef CGAL::Triangulation_vertex_base_with_info_2<t_enriched_vertex_base_2, K_exact> Vbb;
00094 typedef CGAL::Triangulation_hierarchy_vertex_base_2<Vbb> Vb;
00095
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128 template <class Gt, class Fb >
00129 class Enriched_face_base_2 : public Fb
00130 {
00131 public:
00132 typedef Gt Geom_traits;
00133 typedef typename Fb::Vertex_handle Vertex_handle;
00134 typedef typename Fb::Face_handle Face_handle;
00135
00136 template < typename TDS2 >
00137 struct Rebind_TDS
00138 {
00139 typedef typename Fb::template Rebind_TDS<TDS2>::Other Fb2;
00140 typedef Enriched_face_base_2<Gt,Fb2> Other;
00141 };
00142
00143 int status;
00144 int counter;
00145 bool visited;
00146
00147 float weight;
00148 int provenience;
00149 inline bool is_in_domain() const { return (status%2 == 1); };
00150
00151 inline void set_in_domain(const bool b) { status = (b ? 1 : 0); };
00152 void initialize_weight_and_provenience(void){weight=-1; provenience=-1;visited=false;};
00153
00154 Enriched_face_base_2(): Fb(), status(-1) {initialize_weight_and_provenience();};
00155
00156 Enriched_face_base_2(Vertex_handle v0,
00157 Vertex_handle v1,
00158 Vertex_handle v2): Fb(v0,v1,v2), status(-1) {initialize_weight_and_provenience();};
00159
00160 Enriched_face_base_2(Vertex_handle v0,
00161 Vertex_handle v1,
00162 Vertex_handle v2,
00163 Face_handle n0,
00164 Face_handle n1,
00165 Face_handle n2): Fb(v0,v1,v2,n0,n1,n2), status(-1) {initialize_weight_and_provenience();};
00166
00167 };
00168
00169
00170 typedef Enriched_face_base_2<K_exact, CGAL::Constrained_triangulation_face_base_2<K_exact> > Fb;
00171
00172
00173 typedef CGAL::Triangulation_data_structure_2<Vb,Fb> TDS;
00174
00175
00176
00177 typedef CGAL::No_intersection_tag Itag;
00178
00179
00180 typedef CGAL::Constrained_Delaunay_triangulation_2<K_exact, TDS, Itag> CDT1;
00181
00182 typedef CGAL::Triangulation_hierarchy_2<CDT1> CDT;
00183
00184
00185
00186
00187 typedef CDT::Vertex_handle Vertex_handle1;
00188 typedef CDT::Vertex_iterator Vertex_iterator;
00189 typedef CDT::Point Point_2;
00190 typedef CDT::Finite_vertices_iterator Finite_vertices_iterator;
00191 typedef CDT::Finite_faces_iterator Finite_faces_iterator;
00192 typedef CDT::All_faces_iterator All_faces_iterator;
00193
00194 typedef CDT::Vertex_handle Vertex_handle2;
00195 typedef CDT::Face_handle Face_handle;
00196
00197 typedef enum
00198 {
00199 CAN_ADD=77,
00200 CANNOT_ADD,
00201 EXISTS,
00202 ERROR
00203 }e_vertex_analysis;
00204
00205 typedef struct
00206 {
00207 Point_2 v0,v1,v2;
00208 }t_face;
00209
00210
00211
00212
00213 class class_constrained_delaunay_triangulation
00214 {
00215 public:
00216 class_constrained_delaunay_triangulation(void)
00217 {
00218 index_count=1;
00219 debug=1;
00220 };
00221 ~class_constrained_delaunay_triangulation(void){};
00222
00223 bool is_degenerate(double x0, double y0, double z0,
00224 double x1, double y1, double z1,
00225 double x2, double y2, double z2);
00226
00227 CDT::Vertex_handle get_vertex_at(Point_2 p);
00228 int test_if_triangulation_is_valid(void);
00229 int remove_constraint(CDT::Face_handle fh, int li);
00230 bool equal(Point_2 p1, Point_2 p2);
00231 bool equal_e(CGAL::Point_2<K_exact> p1, CGAL::Point_2<K_exact> p2);
00232 bool overlaps(Point_2* v0, Point_2* v1, Point_2* v2, Point_2* p);
00233 int export_all_points_to_pc(void);
00234 int cleanup_isolated_vertices(void);
00235 int add_face_to_mesh(double x0, double y0, double z0, float rgb0,
00236 double x1, double y1, double z1, float rgb1,
00237 double x2, double y2, double z2, float rgb2,
00238 float face_weight, int provenience);
00239
00240 int print_all_vertices(void);
00241 int clear_constraints(void);
00242 int clear_vertices(void);
00243 int set_transform(tf::Transform* st);
00244 int add_point_cloud(const pcl::PointCloud<pcl::PointXYZRGB>* pc, std::vector<float>* vweight,int provenience);
00245 int add_point_manager(double x, double y, double z, float rgb, float weight, int provenience);
00246
00247
00248
00249 int get_seed_list_of_faces_for_tti(CDT::Face_handle fti, std::vector<CDT::Face_handle>* queue);
00250 int add_face_manager(double x0, double y0, double z0, float rgb0,
00251 double x1, double y1, double z1, float rgb1,
00252 double x2, double y2, double z2, float rgb2,
00253 float face_weight, int provenience);
00254
00255
00256 int add_vertex_to_mesh(double x, double y, double z, float rgb, float weight, int provenience);
00257 int export_points_to_pc(void);
00258 int compute_union(void);
00259 int project_triangulation_to_new_plane(pcl::ModelCoefficients::Ptr plane, tf::Transform tf);
00260 int cleanup_neighbours(Vertex_handle1 vh);
00261
00262
00263
00264
00265
00266
00267
00268
00269
00270
00274 int set_constraint_polygon(void);
00275 int filter_isolated_vertexes(void);
00276
00277
00278 int get_point_face_distances(double x, double y, Face_handle fh, double* dv0, double* dv1, double* dv2);
00279 int get_point_face_proveniences(Face_handle fh, int* p0, int* p1, int* p2);
00280 bool do_face_vertices_have_equal_provenience(Face_handle fh, int* provenience=NULL);
00281 bool are_there_at_least_two_vertices_with_equal_provenience_not_mine(Face_handle fh, int my_provenience);
00282 bool at_least_two_vertices_have_my_provenience(Face_handle fh, int my_provenience);
00283 bool at_least_one_vertice_has_infinite_provenience(Face_handle fh);
00284 float get_face_average_weight(Face_handle fh);
00285 void remove_face_vertexes_without_this_provenience(Face_handle fh, int provenience);
00286
00287
00288 int remove_vertices_inside_triangle(double x0, double y0, double z0, float rgb0,
00289 double x1, double y1, double z1, float rgb1,
00290 double x2, double y2, double z2, float rgb2,
00291 float face_weight, int provenience);
00292
00293 int add_vertex_manager(double x, double y, double z, float rgb, float weight, int provenience);
00294 bool check_if_face_should_be_inserted(double x0, double y0, double z0, float rgb0,
00295 double x1, double y1, double z1, float rgb1,
00296 double x2, double y2, double z2, float rgb2,
00297 float face_weight, int provenience);
00298
00299 int remove_intersecting_constrained_edges(double x0, double y0, double z0, float rgb0,
00300 double x1, double y1, double z1, float rgb1,
00301 double x2, double y2, double z2, float rgb2,
00302 float face_weight, int provenience);
00303
00304
00305 CDT::Face face(double x0, double y0, double z0, float rgb0,
00306 double x1, double y1, double z1, float rgb1,
00307 double x2, double y2, double z2, float rgb2,
00308 float face_weight, int provenience);
00309
00310
00311
00312
00313
00314 int iterate_intersecting_faces(CDT::Face_handle fti, int predicate_number);
00315
00316
00317 bool predicate_should_add_face(CDT::Face_handle fti, CDT::Face_handle fh)
00318 {
00319
00320 float boost = 1.2*fh->weight;
00321 if (boost>1) boost=1;
00322
00323 if (fh->provenience==-1)
00324 {
00325 return true;
00326 }
00327 if (boost > fti->weight && fh->provenience != fti->provenience)
00328 {
00329 if(debug>0)ROS_INFO("Triangle to add overlaps faces with larger weight, not adding");
00330 return false;
00331 }
00332 else
00333 return true;
00334 }
00335
00344 bool predicate_remove_vertex(CDT::Face_handle fti, CDT::Face_handle fh);
00345 bool predicate_remove_intersecting_constraints(CDT::Face_handle fti, CDT::Face_handle fh);
00346
00347 int add_face_to_mesh(CDT::Face_handle fti);
00348 float face_max_weight(Face_handle fh);
00349
00350 int get_intersecting_faces_list(double x0, double y0, double z0, float rgb0,
00351 double x1, double y1, double z1, float rgb1,
00352 double x2, double y2, double z2, float rgb2,
00353 float face_weight, int provenience);
00354
00355 CDT::Face_handle get_face_handle_from_t_face(t_face* f);
00356
00357
00358
00359
00360
00361
00362
00363 bool triangles_overlap(Point_2 t0_p0, Point_2 t0_p1, Point_2 t0_p2,
00364 Point_2 t1_p0, Point_2 t1_p1, Point_2 t1_p2);
00365
00366
00367 int printf_face_info(CDT::Face_handle fh);
00368
00369 unsigned int debug;
00370 std::vector<t_face> vector_faces;
00371 pcl::PointCloud<pcl::PointXYZ> pc_faces_visited;
00372 pcl::PointCloud<pcl::PointXYZ> pc_faces_intersect;
00373
00374 CDT dt;
00375 tf::Transform transform;
00376 pcl::PointCloud<pcl::PointXYZRGB> pc;
00377 pcl::PointCloud<pcl::PointXYZ> pc_constraints;
00378 std::vector<int> pc_proveniences;
00379
00380 std::vector<size_t> pc_vertices_indices;
00381 pcl::PointCloud<pcl::PointXYZ> pc_vertices;
00382
00383 class_polygon_intersection pi;
00384 std::vector<pcl::PointCloud<pcl::PointXYZ> > projection_union;
00385
00386 private:
00387
00388 size_t index_count;
00389
00390 bool segments_intersect_not_at_endpoints(CGAL::Segment_2<K_exact> seg1, CGAL::Segment_2<K_exact> seg2);
00391
00392
00393
00394 void discoverComponents(const CDT & ct);
00395 void discoverComponent(const CDT & ct, Face_handle start, int index, std::list<CDT::Edge>& border );
00396 int initialize_all_faces_status(void)
00397 {
00398 for(All_faces_iterator it = dt.all_faces_begin(); it != dt.all_faces_end(); ++it)
00399 {
00400 it->counter=-1;
00401 it->status=-1;
00402 }
00403 return 1;
00404 }
00405
00406 int initialize_visited(void)
00407 {
00408 for(All_faces_iterator it = dt.all_faces_begin(); it != dt.all_faces_end(); ++it)
00409 {
00410 it->visited=false;
00411 }
00412 return 1;
00413 }
00414
00415 };
00416
00417
00418
00419 #endif
00420