$search
00001 /* 00002 * Copyright (C) 2008 00003 * Robert Bosch LLC 00004 * Research and Technology Center North America 00005 * Palo Alto, California 00006 * 00007 * All rights reserved. 00008 * 00009 *------------------------------------------------------------------------------ 00010 * project ....: PUMA: Probablistic Unsupervised Model Acquisition 00011 * file .......: Geometry2D.h 00012 * authors ....: Benjamin Pitzer 00013 * organization: Robert Bosch LLC 00014 * creation ...: 03/28/2008 00015 * modified ...: $Date: 2009-08-25 17:32:44 -0700 (Tue, 25 Aug 2009) $ 00016 * changed by .: $Author: benjaminpitzer $ 00017 * revision ...: $Revision: 893 $ 00018 */ 00019 #ifndef GEOMETRY2D_H 00020 #define GEOMETRY2D_H 00021 00022 //== INCLUDES ================================================================== 00023 #include <rtc/rtcVec2.h> 00024 00025 namespace rtc { 00026 // euclidean distance 00027 float dist(const Vec2f &a, const Vec2f &b); 00028 // squared euclidean distance 00029 float dist2(const Vec2f &a, const Vec2f &b); 00030 // Calculates the closest point to x on a line segmente a-->b 00031 void dist_to_line(const Vec2f &x, const Vec2f &a, const Vec2f &b, float &d, Vec2f &cp); 00032 // Calculates the closest point to x on a line segmente a-->b 00033 float dist_to_line(const Vec2f &x, const Vec2f &a, const Vec2f &b); 00034 // Calculates the projected distance from x on a line segmente a-->b 00035 float proj_dist_to_line(const Vec2f &x, const Vec2f &a, const Vec2f &b); 00036 // Calculates the closest point to x on a line segmente a-->b 00037 // if the distance to closest point is smaller than d2 (squared distance), both 00038 // d2 and cp will be overwritten 00039 bool closer_on_line(const Vec2f &x, const Vec2f &a, const Vec2f &b, float &d2, Vec2f &cp); 00040 // is the circle centered at b with radius r 00041 // fully within the rectangle centered at bc, with radius br? 00042 bool circle_within_bounds(const Vec2f &b, float r, const Vec2f &bc, float br); 00043 // is the circle centered at b with radius r 00044 // fully within the rectangle centered from min to max? 00045 bool circle_within_bounds(const Vec2f &b, float r, const Vec2f &min, const Vec2f &max); 00046 // does the circle centered at b, with radius r, 00047 // intersect the rectangle centered at bc, with radius br? 00048 bool bounds_overlap_circle(const Vec2f &b, float r, const Vec2f &bc, float br); 00049 // Which of the four edges is point P outside of? 00050 long bevel_1d(const Vec2f &p); 00051 // Which of the four edge lines is point P outside of? 00052 long bevel_2d(const Vec2f &p); 00053 // 2D linear interpolation 00054 Vec2f lerp(float t, const Vec2f &a, const Vec2f &b); 00055 // Test the point "alpha" of the way from P1 to P2 00056 // See if it is on a edge of the rectangle 00057 // Consider only faces in "mask" 00058 bool point_on_edge(const Vec2f &p1, const Vec2f &p2, float alpha, long mask); 00059 // Compute intersection of P1 --> P2 line segment with edge lines 00060 // Then test intersection point to see if it is on cube face 00061 // Consider only face planes in "outcode_diff" 00062 // Note: Zero bits in "outcode_diff" means edge is outside of 00063 bool segment_on_edge(const Vec2f &p1, const Vec2f &p2, long outcode_diff); 00064 // true if line t1,t2 is outside a rectangle 00065 // centered at c with length of a side s, 00066 // false if the line intersects rectangle 00067 bool line_outside_of_rect(const Vec2f &c, float s, const Vec2f &t1, const Vec2f &t2); 00068 // true if line p is outside a rectangle 00069 // centered at c with length of a side s, 00070 // false if the line intersects rectangle 00071 bool point_outside_of_rect(const Vec2f &c, float s, const Vec2f &p); 00072 // true if line p is outside a rectangle 00073 // centered at c with length of x side xlen and length of y side ylen, 00074 // rotated rot_angle degree, 00075 // false if the line intersects rectangle 00076 bool point_outside_of_rect(const Vec2f &c, float xlen, float ylen, float rot_angle, const Vec2f &p); 00077 // true if rectangle 1 intersects rectangle 2 00078 // c == center 00079 // theta == angle 00080 // w == width 00081 // l == length 00082 bool rect_rect_X(const Vec2f &c1, float theta1, float w1, float l1, 00083 const Vec2f &c2, float theta2, float w2, float l2); 00084 // true if line intersects rectangle 00085 // line t1-->t2 00086 // c == center 00087 // theta == angle 00088 // w == width 00089 // l == length 00090 bool line_rect_X(const Vec2f &t1, const Vec2f &t2, 00091 const Vec2f &c, float theta, float w, float l); 00092 00093 // calculate barycentric coordinates of the point p on triangle t1 t2 t3 00094 template <class T> inline void rtc_bary(const Vec2<T>& p, const Vec2<T>& t1, const Vec2<T>& t2, const Vec2<T>& t3, T &b1, T &b2, T &b3) 00095 { 00096 const T v10 = t1[0]-t3[0]; 00097 const T v11 = t1[1]-t3[1]; 00098 const T v20 = t2[0]-t3[0]; 00099 const T v21 = t2[1]-t3[1]; 00100 // ignore z 00101 const T d = T(1.0) / (v10*v21-v11*v20); 00102 const T x0 = (p[0]-t3[0]); 00103 const T x1 = (p[1]-t3[1]); 00104 b1 = (x0*v21 - x1*v20) * d; 00105 b2 = (v10*x1 - v11*x0) * d; 00106 b3 = T(1.0) - b1 - b2; 00107 } 00108 00109 // true if poin p is inside the triangle t1 t2 t3 00110 template <class T> inline bool rtc_point_inside_triangle(const Vec2<T> &p, const Vec2<T>& t1, const Vec2<T>& t2, const Vec2<T>& t3) 00111 { 00112 T b1,b2,b3; 00113 // calculate barycentric coordinates 00114 rtc_bary(p, t1, t2, t3, b1, b2, b3); 00115 // all non-negative, the point is within the triangle 00116 if (b1 >= T(0) && b2 >= T(0) && b3 >= T(0)) 00117 return true; 00118 else 00119 return false; 00120 } 00121 00122 // Calculates the euclidian distance from a point to a another point b 00123 template <class T> inline T rtc_distance_point_to_point(const Vec2<T> &a, const Vec2<T> &b) 00124 { 00125 return (a-b).norm(); 00126 } 00127 00128 // Calculates the distance from a point to x to the closest point on a line segment a-->b 00129 template <class T> inline T rtc_distance_point_to_line(const Vec2<T> &x, const Vec2<T> &a, const Vec2<T> &b) 00130 { 00131 Vec2<T> ba(b[0]-a[0], b[1]-a[1]); 00132 Vec2<T> xa(x[0]-a[0], x[1]-a[1]); 00133 00134 T xa_ba = xa.dot(ba); 00135 // if the dot product is negative, the point is closest to a 00136 if (xa_ba < 0.0) { 00137 return rtc_distance_point_to_point(x,a); 00138 } 00139 00140 // if the dot product is greater than squared segment length, 00141 // the point is closest to b 00142 T fact = xa_ba/ba.normSqr(); 00143 if (fact >= 1.0) { 00144 return rtc_distance_point_to_point(x,b); 00145 } 00146 00147 // take the squared dist x-a, squared dot of x-a to unit b-a, 00148 // use Pythagoras' rule 00149 return rtc_sqrt(xa.normSqr() - xa_ba*fact); 00150 } 00151 00152 // Calculates the projected distance from a point to x on a line segment a-->b 00153 template <class T> inline T rtc_distance_point_to_line_projected(const Vec2<T> &x, const Vec2<T> &a, const Vec2<T> &b) 00154 { 00155 Vec2<T> v(b[1]-a[1], a[0]-b[0]); 00156 v.normalize(); 00157 Vec2<T> xa(x[0]-a[0], x[1]-a[1]); 00158 return rtc_abs(v.dot(xa)); 00159 } 00160 00161 // calculates the area of an triangle (t1 t2 t3) 00162 template <class T> inline T rtc_triangle_area(const Vec2<T>& t1, const Vec2<T>& t2, const Vec2<T>& t3) 00163 { 00164 return rtc_abs(rtc_triangle_area_signed(t1,t2,t3)); 00165 } 00166 00167 // calculates the signed area of an triangle (t1 t2 t3) 00168 template <class T> inline T rtc_triangle_area_signed(const Vec2<T>& t1, const Vec2<T>& t2, const Vec2<T>& t3) 00169 { 00170 const T a = (t2(0)-t1(0))*(t3(1)-t1(1))-(t3(0)-t1(0))*(t2(1)-t1(1)); 00171 return T(0.5)*a; 00172 } 00173 00174 //============================================================================== 00175 } // namespace rtc 00176 //============================================================================== 00177 #endif