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 _TEXTURED_TRIANGLE_H_
00034 #define _TEXTURED_TRIANGLE_H_
00035
00036
00037
00038
00039
00040 #include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
00041 #include <CGAL/Constrained_Delaunay_triangulation_2.h>
00042
00043 typedef CGAL::Exact_predicates_inexact_constructions_kernel K1;
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054 #include <pcl/segmentation/sac_segmentation.h>
00055 #include <pcl/filters/project_inliers.h>
00056 #include <pcl/point_cloud.h>
00057 #include <pcl/point_types.h>
00058 #include <pcl_ros/transforms.h>
00059 #include <pcl/ModelCoefficients.h>
00060 #include <tf/tf.h>
00061 #include <visualization_msgs/Marker.h>
00062 #include <queue>
00063
00064 #define DONT_INTERSECT 0
00065 #define DO_INTERSECT 1
00066 #define COLLINEAR 2
00067
00068 #define SAME_SIGNS( a, b ) \
00069 (((long) ((unsigned long) a ^ (unsigned long) b)) >= 0 )
00070
00071
00072
00073 class class_textured_vertex
00074 {
00075 public:
00076 class_textured_vertex(void){};
00077 class_textured_vertex(float vx, float vy, float vz, float vrgb);
00078 ~class_textured_vertex(void){};
00079
00080 class_textured_vertex operator=(class_textured_vertex vin)
00081 {
00082 class_textured_vertex v_out;
00083 v_out.x = vin.x;
00084 v_out.y = vin.y;
00085 v_out.z = vin.z;
00086 v_out.rgb = vin.rgb;
00087 return v_out;
00088
00089 }
00090
00091 float x,y,z,rgb;
00092
00093 };
00094
00095 class class_textured_triangle
00096 {
00097 public:
00098 class_textured_triangle(void){};
00099 class_textured_triangle(class_textured_vertex v0, class_textured_vertex v1,class_textured_vertex v2, float weight=0, int provenience=-1);
00100
00101 ~class_textured_triangle(void){};
00102
00103 class_textured_vertex v[3];
00104 float weight;
00105 float provenience;
00106
00107 bool overlaps(class_textured_triangle* t);
00108 void print_info(void)
00109 {
00110 ROS_INFO("v0 x=%f y=%f z=%f rgb=%f\n v1 x=%f y=%f z=%f rgb=%f\n v2 x=%f y=%f z=%f rgb=%f\n", v[0].x, v[0].y, v[0].z, v[0].rgb, v[1].x, v[1].y, v[1].z, v[1].rgb,v[2].x, v[2].y, v[2].z, v[2].rgb);
00111 }
00112
00113 private:
00114
00115
00116 int test2( double px, double py, double m, double b ) {
00117 if (py < m * px + b ) {
00118 return -1;
00119 }else if ( py == m * px + b ){
00120 return 0;
00121 } else {
00122 return 1;
00123 }
00124 }
00125
00126 int test1(double px, double py, double m,double b, double lx,double ly) {
00127 return (test2(px,py, m,b) == test2(lx,ly,m,b));
00128 }
00129
00130
00131
00132 int point_inside_triangle(double x0,double y0,double x1,double y1,double x2,double y2,double px, double py)
00133 {
00134 int line1, line2, line3;
00135 double m01 = (y1-y0)/(x1-x0);
00136 double b01 = m01 * -x1 + y1;
00137 double m02, m12, b02, b12;
00138 m02 = (y2-y0)/(x2-x0);
00139 m12 = (y2-y1)/(x2-x1);
00140 b02 = m02 * -x2 + y2;
00141 b12 = m12 * -x2 + y2;
00142
00143
00144
00145
00146 if( x1 == x0 ) {
00147 line1 = ( (px < x0) == (x2 < x0) );
00148 } else {
00149 line1 = test1( px, py, m01, b01,x2,y2);
00150 }
00151
00152 if( x1 == x2 ) {
00153 line2 = ( (px < x2) == (x0 < x2) );
00154 } else {
00155 line2 = test1(px,py, m12, b12,x0,y0);
00156 }
00157
00158 if( x2 == x0 ) {
00159 line3 = ( (px < x0 ) == (x1 < x0) );} else {
00160 line3 = test1(px, py, m02,b02,x1,y1);
00161 }
00162
00163 if(line1==-1 && line2==-1 && line3==-1)
00164 return 1;
00165 else if(line1==1 && line2==1 && line3==1)
00166 return 1;
00167 else
00168 return 0;
00169
00170
00171
00172 }
00173
00174
00179 int lineSegmentIntersection(
00180 float Ax, float Ay,
00181 float Bx, float By,
00182 float Cx, float Cy,
00183 float Dx, float Dy,
00184 double *X, double *Y) {
00185
00186 double distAB, theCos, theSin, newX, ABpos ;
00187
00188
00189 if (((Ax==Bx) && (Ay==By)) || ((Cx==Dx) && (Cy==Dy))) return DONT_INTERSECT;
00190
00191
00192 if (((Ax==Cx) && (Ay==Cy)) || ((Bx==Cx) && (By==Cy))
00193 || ((Ax==Dx) && (Ay==Dy)) || ((Bx==Dx) && (By==Dy))) {
00194 return DONT_INTERSECT; }
00195
00196
00197 Bx-=Ax; By-=Ay;
00198 Cx-=Ax; Cy-=Ay;
00199 Dx-=Ax; Dy-=Ay;
00200
00201
00202 distAB=sqrt(Bx*Bx+By*By);
00203
00204
00205 theCos=Bx/distAB;
00206 theSin=By/distAB;
00207 newX=Cx*theCos+Cy*theSin;
00208 Cy =Cy*theCos-Cx*theSin; Cx=newX;
00209 newX=Dx*theCos+Dy*theSin;
00210 Dy =Dy*theCos-Dx*theSin; Dx=newX;
00211
00212
00213 if ((Cy<0. && Dy<0.) || (Cy>=0. && Dy>=0.)) return DONT_INTERSECT;
00214
00215
00216 ABpos=Dx+(Cx-Dx)*Dy/(Dy-Cy);
00217
00218
00219 if (ABpos<0. || ABpos>distAB) return DONT_INTERSECT;
00220
00221
00222 *X=Ax+ABpos*theCos;
00223 *Y=Ay+ABpos*theSin;
00224
00225
00226 return DO_INTERSECT;
00227 }
00228
00229
00230 };
00231
00232 typedef enum
00233 {
00234 FORCE=55,
00235 CHECK
00236 }t_add_method;
00237
00238
00239 #define ADDED_TRIANGLE 1
00240 #define DID_NOT_ADD_TRIANGLE 0
00241
00245 class class_texture_set
00246 {
00247 public:
00248
00249
00250 class_texture_set(void)
00251 {
00252 next_key=0;
00253 };
00254
00255 ~class_texture_set(void){};
00256
00257 int add_triangle(class_textured_vertex v0, class_textured_vertex v1, class_textured_vertex v2, int provenience, float weight, t_add_method method);
00258 int set_transform(tf::Transform* st);
00259 int export_to_pc(void);
00260
00261
00262 std::vector<boost::shared_ptr<class_textured_triangle> > set;
00263 pcl::PointCloud<pcl::PointXYZRGB> pc;
00264 std::vector<int> pc_proveniences;
00265 tf::Transform transform;
00266 size_t next_key;
00267 };
00268
00269
00270 #endif
00271