$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 */ 00034 00037 #include "collision_checking/intersect.h" 00038 #include <iostream> 00039 #include <limits> 00040 00041 namespace collision_checking 00042 { 00043 const BVH_REAL PolySolver::NEAR_ZERO_THRESHOLD = 1e-9; 00044 00045 00046 bool PolySolver::isZero(BVH_REAL v) 00047 { 00048 return roughlyEqual(v, (BVH_REAL)0, NEAR_ZERO_THRESHOLD); 00049 } 00050 00051 bool PolySolver::cbrt(BVH_REAL v) 00052 { 00053 return powf(v, 1.0 / 3.0); 00054 } 00055 00056 int PolySolver::solveLinear(BVH_REAL c[2], BVH_REAL s[1]) 00057 { 00058 if(isZero(c[1])) 00059 return 0; 00060 s[0] = - c[0] / c[1]; 00061 return 1; 00062 } 00063 00064 int PolySolver::solveQuadric(BVH_REAL c[3], BVH_REAL s[2]) 00065 { 00066 BVH_REAL p, q, D; 00067 00068 // make sure we have a d2 equation 00069 00070 if(isZero(c[2])) 00071 return solveLinear(c, s); 00072 00073 // normal for: x^2 + px + q 00074 p = c[1] / (2.0 * c[2]); 00075 q = c[0] / c[2]; 00076 D = p * p - q; 00077 00078 if(isZero(D)) 00079 { 00080 // one BVH_REAL root 00081 s[0] = s[1] = -p; 00082 return 1; 00083 } 00084 00085 if(D < 0.0) 00086 // no real root 00087 return 0; 00088 else 00089 { 00090 // two real roots 00091 BVH_REAL sqrt_D = sqrt(D); 00092 s[0] = sqrt_D - p; 00093 s[1] = -sqrt_D - p; 00094 return 2; 00095 } 00096 } 00097 00098 int PolySolver::solveCubic(BVH_REAL c[4], BVH_REAL s[3]) 00099 { 00100 int i, num; 00101 BVH_REAL sub, A, B, C, sq_A, p, q, cb_p, D; 00102 const BVH_REAL ONE_OVER_THREE = 1 / 3.0; 00103 const BVH_REAL PI = 3.14159265358979323846; 00104 00105 // make sure we have a d2 equation 00106 if(isZero(c[3])) 00107 return solveQuadric(c, s); 00108 00109 // normalize the equation:x ^ 3 + Ax ^ 2 + Bx + C = 0 00110 A = c[2] / c[3]; 00111 B = c[1] / c[3]; 00112 C = c[0] / c[3]; 00113 00114 // substitute x = y - A / 3 to eliminate the quadratic term: x^3 + px + q = 0 00115 sq_A = A * A; 00116 p = (-ONE_OVER_THREE * sq_A + B) * ONE_OVER_THREE; 00117 q = 0.5 * (2.0 / 27.0 * A * sq_A - ONE_OVER_THREE * A * B + C); 00118 00119 // use Cardano's formula 00120 cb_p = p * p * p; 00121 D = q * q + cb_p; 00122 00123 if(isZero(D)) 00124 { 00125 if(isZero(q)) 00126 { 00127 // one triple solution 00128 s[0] = 0.0; 00129 num = 1; 00130 } 00131 else 00132 { 00133 // one single and one BVH_REAL solution 00134 BVH_REAL u = cbrt(-q); 00135 s[0] = 2.0 * u; 00136 s[1] = -u; 00137 num = 2; 00138 } 00139 } 00140 else 00141 { 00142 if(D < 0.0) 00143 { 00144 // three real solutions 00145 BVH_REAL phi = ONE_OVER_THREE * acos(-q / sqrt(-cb_p)); 00146 BVH_REAL t = 2.0 * sqrt(-p); 00147 s[0] = t * cos(phi); 00148 s[1] = -t * cos(phi + PI / 3.0); 00149 s[2] = -t * cos(phi - PI / 3.0); 00150 num = 3; 00151 } 00152 else 00153 { 00154 // one real solution 00155 BVH_REAL sqrt_D = sqrt(D); 00156 BVH_REAL u = cbrt(sqrt_D + fabs(q)); 00157 if(q > 0.0) 00158 s[0] = - u + p / u ; 00159 else 00160 s[0] = u - p / u; 00161 num = 1; 00162 } 00163 } 00164 00165 // re-substitute 00166 sub = ONE_OVER_THREE * A; 00167 for(i = 0; i < num; i++) 00168 s[i] -= sub; 00169 return num; 00170 } 00171 00172 const BVH_REAL Intersect::EPSILON = 1e-5; 00173 const BVH_REAL Intersect::NEAR_ZERO_THRESHOLD = 1e-7; 00174 const BVH_REAL Intersect::CCD_RESOLUTION = 1e-7; 00175 00176 00177 bool Intersect::isZero(BVH_REAL v) 00178 { 00179 return roughlyEqual(v, (BVH_REAL)0, NEAR_ZERO_THRESHOLD); 00180 } 00181 00185 bool Intersect::solveCubicWithIntervalNewton(const Vec3f& a0, const Vec3f& b0, const Vec3f& c0, const Vec3f& d0, 00186 const Vec3f& va, const Vec3f& vb, const Vec3f& vc, const Vec3f& vd, 00187 BVH_REAL& l, BVH_REAL& r, bool bVF, BVH_REAL coeffs[], Vec3f* data) 00188 { 00189 BVH_REAL v2[2]= {l*l,r*r}; 00190 BVH_REAL v[2]= {l,r}; 00191 BVH_REAL r_backup; 00192 00193 unsigned char min3, min2, min1, max3, max2, max1; 00194 00195 min3= *((unsigned char*)&coeffs[3]+7)>>7; max3=min3^1; 00196 min2= *((unsigned char*)&coeffs[2]+7)>>7; max2=min2^1; 00197 min1= *((unsigned char*)&coeffs[1]+7)>>7; max1=min1^1; 00198 00199 // bound the cubic 00200 00201 BVH_REAL minor = coeffs[3]*v2[min3]*v[min3]+coeffs[2]*v2[min2]+coeffs[1]*v[min1]+coeffs[0]; 00202 BVH_REAL major = coeffs[3]*v2[max3]*v[max3]+coeffs[2]*v2[max2]+coeffs[1]*v[max1]+coeffs[0]; 00203 00204 if(major<0) return false; 00205 if(minor>0) return false; 00206 00207 // starting here, the bounds have opposite values 00208 BVH_REAL m = 0.5 * (r + l); 00209 00210 // bound the derivative 00211 BVH_REAL dminor = 3.0*coeffs[3]*v2[min3]+2.0*coeffs[2]*v[min2]+coeffs[1]; 00212 BVH_REAL dmajor = 3.0*coeffs[3]*v2[max3]+2.0*coeffs[2]*v[max2]+coeffs[1]; 00213 00214 if((dminor > 0)||(dmajor < 0)) // we can use Newton 00215 { 00216 BVH_REAL m2 = m*m; 00217 BVH_REAL fm = coeffs[3]*m2*m+coeffs[2]*m2+coeffs[1]*m+coeffs[0]; 00218 BVH_REAL nl = m; 00219 BVH_REAL nu = m; 00220 if(fm>0) 00221 { 00222 nl-=(fm/dminor); 00223 nu-=(fm/dmajor); 00224 } 00225 else 00226 { 00227 nu-=(fm/dminor); 00228 nl-=(fm/dmajor); 00229 } 00230 00231 //intersect with [l,r] 00232 00233 if(nl>r) return false; 00234 if(nu<l) return false; 00235 if(nl>l) 00236 { 00237 if(nu<r) { l=nl; r=nu; m=0.5*(l+r); } 00238 else { l=nl; m=0.5*(l+r); } 00239 } 00240 else 00241 { 00242 if(nu<r) { r=nu; m=0.5*(l+r); } 00243 } 00244 } 00245 00246 // sufficient temporal resolution, check root validity 00247 if((r-l)< CCD_RESOLUTION) 00248 { 00249 if(bVF) 00250 return checkRootValidity_VF(a0, b0, c0, d0, va, vb, vc, vd, r); 00251 else 00252 return checkRootValidity_EE(a0, b0, c0, d0, va, vb, vc, vd, r, data); 00253 } 00254 00255 r_backup = r, r = m; 00256 if(solveCubicWithIntervalNewton(a0, b0, c0, d0, va, vb, vc, vd, l, r, bVF, coeffs, data)) 00257 return true; 00258 00259 l = m, r = r_backup; 00260 return solveCubicWithIntervalNewton(a0, b0, c0, d0, va, vb, vc, vd, l, r, bVF, coeffs, data); 00261 } 00262 00263 00264 00265 bool Intersect::insideTriangle(const Vec3f& a, const Vec3f& b, const Vec3f& c, const Vec3f&p) 00266 { 00267 Vec3f ab = b - a; 00268 Vec3f ac = c - a; 00269 Vec3f n = ab.cross(ac); 00270 00271 Vec3f pa = a - p; 00272 Vec3f pb = b - p; 00273 Vec3f pc = c - p; 00274 00275 if((pb.cross(pc)).dot(n) < -EPSILON) return false; 00276 if((pc.cross(pa)).dot(n) < -EPSILON) return false; 00277 if((pa.cross(pb)).dot(n) < -EPSILON) return false; 00278 00279 return true; 00280 } 00281 00282 bool Intersect::insideLineSegment(const Vec3f& a, const Vec3f& b, const Vec3f& p) 00283 { 00284 return (p - a).dot(p - b) <= 0; 00285 } 00286 00287 /* \brief Calculate the line segment papb that is the shortest route between 00288 two lines p1p2 and p3p4. Calculate also the values of mua and mub where 00289 pa = p1 + mua (p2 - p1) 00290 pb = p3 + mub (p4 - p3) 00291 Return FALSE if no solution exists. 00292 */ 00293 bool Intersect::linelineIntersect(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3, const Vec3f& p4, 00294 Vec3f* pa, Vec3f* pb, BVH_REAL* mua, BVH_REAL* mub) 00295 { 00296 Vec3f p31 = p1 - p3; 00297 Vec3f p34 = p4 - p3; 00298 if(fabs(p34[0]) < EPSILON && fabs(p34[1]) < EPSILON && fabs(p34[2]) < EPSILON) 00299 return false; 00300 00301 Vec3f p12 = p2 - p1; 00302 if(fabs(p12[0]) < EPSILON && fabs(p12[1]) < EPSILON && fabs(p12[2]) < EPSILON) 00303 return false; 00304 00305 BVH_REAL d3134 = p31.dot(p34); 00306 BVH_REAL d3412 = p34.dot(p12); 00307 BVH_REAL d3112 = p31.dot(p12); 00308 BVH_REAL d3434 = p34.dot(p34); 00309 BVH_REAL d1212 = p12.dot(p12); 00310 00311 BVH_REAL denom = d1212 * d3434 - d3412 * d3412; 00312 if(fabs(denom) < EPSILON) 00313 return false; 00314 BVH_REAL numer = d3134 * d3412 - d3112 * d3434; 00315 00316 *mua = numer / denom; 00317 if(*mua < 0 || *mua > 1) 00318 return false; 00319 00320 *mub = (d3134 + d3412 * (*mua)) / d3434; 00321 if(*mub < 0 || *mub > 1) 00322 return false; 00323 00324 *pa = p1 + p12 * (*mua); 00325 *pb = p3 + p34 * (*mub); 00326 return true; 00327 } 00328 00329 bool Intersect::checkRootValidity_VF(const Vec3f& a0, const Vec3f& b0, const Vec3f& c0, const Vec3f& p0, 00330 const Vec3f& va, const Vec3f& vb, const Vec3f& vc, const Vec3f& vp, 00331 BVH_REAL t) 00332 { 00333 return insideTriangle(a0 + va * t, b0 + vb * t, c0 + vc * t, p0 + vp * t); 00334 } 00335 00336 bool Intersect::checkRootValidity_EE(const Vec3f& a0, const Vec3f& b0, const Vec3f& c0, const Vec3f& d0, 00337 const Vec3f& va, const Vec3f& vb, const Vec3f& vc, const Vec3f& vd, 00338 BVH_REAL t, Vec3f* q_i) 00339 { 00340 Vec3f a = a0 + va * t; 00341 Vec3f b = b0 + vb * t; 00342 Vec3f c = c0 + vc * t; 00343 Vec3f d = d0 + vd * t; 00344 Vec3f p1, p2; 00345 BVH_REAL t_ab, t_cd; 00346 if(linelineIntersect(a, b, c, d, &p1, &p2, &t_ab, &t_cd)) 00347 { 00348 if(q_i) *q_i = p1; 00349 return true; 00350 } 00351 00352 return false; 00353 } 00354 00355 bool Intersect::checkRootValidity_VE(const Vec3f& a0, const Vec3f& b0, const Vec3f& p0, 00356 const Vec3f& va, const Vec3f& vb, const Vec3f& vp, 00357 BVH_REAL t) 00358 { 00359 return insideLineSegment(a0 + va * t, b0 + vb * t, p0 + vp * t); 00360 } 00361 00362 bool Intersect::solveSquare(BVH_REAL a, BVH_REAL b, BVH_REAL c, 00363 const Vec3f& a0, const Vec3f& b0, const Vec3f& c0, const Vec3f& d0, 00364 const Vec3f& va, const Vec3f& vb, const Vec3f& vc, const Vec3f& vd, 00365 bool bVF, 00366 BVH_REAL* ret) 00367 { 00368 BVH_REAL discriminant = b * b - 4 * a * c; 00369 if(discriminant < 0) 00370 return false; 00371 00372 BVH_REAL sqrt_dis = sqrt(discriminant); 00373 BVH_REAL r1 = (-b + sqrt_dis) / (2 * a); 00374 bool v1 = (r1 >= 0.0 && r1 <= 1.0) ? ((bVF) ? checkRootValidity_VF(a0, b0, c0, d0, va, vb, vc, vd, r1) : checkRootValidity_EE(a0, b0, c0, d0, va, vb, vc, vd, r1)) : false; 00375 00376 BVH_REAL r2 = (-b - sqrt_dis) / (2 * a); 00377 bool v2 = (r2 >= 0.0 && r2 <= 1.0) ? ((bVF) ? checkRootValidity_VF(a0, b0, c0, d0, va, vb, vc, vd, r2) : checkRootValidity_EE(a0, b0, c0, d0, va, vb, vc, vd, r2)) : false; 00378 00379 if(v1 && v2) 00380 { 00381 *ret = (r1 > r2) ? r2 : r1; 00382 return true; 00383 } 00384 if(v1) 00385 { 00386 *ret = r1; 00387 return true; 00388 } 00389 if(v2) 00390 { 00391 *ret = r2; 00392 return true; 00393 } 00394 00395 return false; 00396 } 00397 00398 bool Intersect::solveSquare(BVH_REAL a, BVH_REAL b, BVH_REAL c, 00399 const Vec3f& a0, const Vec3f& b0, const Vec3f& p0, 00400 const Vec3f& va, const Vec3f& vb, const Vec3f& vp) 00401 { 00402 if(isZero(a)) 00403 { 00404 BVH_REAL t = -c/b; 00405 return (t >= 0 && t <= 1) ? checkRootValidity_VE(a0, b0, p0, va, vb, vp, t) : false; 00406 } 00407 00408 BVH_REAL discriminant = b*b-4*a*c; 00409 if(discriminant < 0) 00410 return false; 00411 00412 BVH_REAL sqrt_dis = sqrt(discriminant); 00413 00414 BVH_REAL r1 = (-b+sqrt_dis) / (2 * a); 00415 bool v1 = (r1 >= 0.0 && r1 <= 1.0) ? checkRootValidity_VE(a0, b0, p0, va, vb, vp, r1) : false; 00416 if(v1) return true; 00417 00418 BVH_REAL r2 = (-b-sqrt_dis) / (2 * a); 00419 bool v2 = (r2 >= 0.0 && r2 <= 1.0) ? checkRootValidity_VE(a0, b0, p0, va, vb, vp, r2) : false; 00420 return v2; 00421 } 00422 00423 00424 00428 void Intersect::computeCubicCoeff_VF(const Vec3f& a0, const Vec3f& b0, const Vec3f& c0, const Vec3f& p0, 00429 const Vec3f& va, const Vec3f& vb, const Vec3f& vc, const Vec3f& vp, 00430 BVH_REAL* a, BVH_REAL* b, BVH_REAL* c, BVH_REAL* d) 00431 { 00432 Vec3f vavb = vb - va; 00433 Vec3f vavc = vc - va; 00434 Vec3f vavp = vp - va; 00435 Vec3f a0b0 = b0 - a0; 00436 Vec3f a0c0 = c0 - a0; 00437 Vec3f a0p0 = p0 - a0; 00438 00439 Vec3f vavb_cross_vavc = vavb.cross(vavc); 00440 Vec3f vavb_cross_a0c0 = vavb.cross(a0c0); 00441 Vec3f a0b0_cross_vavc = a0b0.cross(vavc); 00442 Vec3f a0b0_cross_a0c0 = a0b0.cross(a0c0); 00443 00444 *a = vavp.dot(vavb_cross_vavc); 00445 *b = a0p0.dot(vavb_cross_vavc) + vavp.dot(vavb_cross_a0c0 + a0b0_cross_vavc); 00446 *c = vavp.dot(a0b0_cross_a0c0) + a0p0.dot(vavb_cross_a0c0 + a0b0_cross_vavc); 00447 *d = a0p0.dot(a0b0_cross_a0c0); 00448 } 00449 00450 void Intersect::computeCubicCoeff_EE(const Vec3f& a0, const Vec3f& b0, const Vec3f& c0, const Vec3f& d0, 00451 const Vec3f& va, const Vec3f& vb, const Vec3f& vc, const Vec3f& vd, 00452 BVH_REAL* a, BVH_REAL* b, BVH_REAL* c, BVH_REAL* d) 00453 { 00454 Vec3f vavb = vb - va; 00455 Vec3f vcvd = vd - vc; 00456 Vec3f vavc = vc - va; 00457 Vec3f c0d0 = d0 - c0; 00458 Vec3f a0b0 = b0 - a0; 00459 Vec3f a0c0 = c0 - a0; 00460 Vec3f vavb_cross_vcvd = vavb.cross(vcvd); 00461 Vec3f vavb_cross_c0d0 = vavb.cross(c0d0); 00462 Vec3f a0b0_cross_vcvd = a0b0.cross(vcvd); 00463 Vec3f a0b0_cross_c0d0 = a0b0.cross(c0d0); 00464 00465 *a = vavc.dot(vavb_cross_vcvd); 00466 *b = a0c0.dot(vavb_cross_vcvd) + vavc.dot(vavb_cross_c0d0 + a0b0_cross_vcvd); 00467 *c = vavc.dot(a0b0_cross_c0d0) + a0c0.dot(vavb_cross_c0d0 + a0b0_cross_vcvd); 00468 *d = a0c0.dot(a0b0_cross_c0d0); 00469 } 00470 00471 void Intersect::computeCubicCoeff_VE(const Vec3f& a0, const Vec3f& b0, const Vec3f& p0, 00472 const Vec3f& va, const Vec3f& vb, const Vec3f& vp, 00473 const Vec3f& L, 00474 BVH_REAL* a, BVH_REAL* b, BVH_REAL* c) 00475 { 00476 Vec3f vbva = va - vb; 00477 Vec3f vbvp = vp - vb; 00478 Vec3f b0a0 = a0 - b0; 00479 Vec3f b0p0 = p0 - b0; 00480 00481 Vec3f L_cross_vbvp = L.cross(vbvp); 00482 Vec3f L_cross_b0p0 = L.cross(b0p0); 00483 00484 *a = L_cross_vbvp.dot(vbva); 00485 *b = L_cross_vbvp.dot(b0a0) + L_cross_b0p0.dot(vbva); 00486 *c = L_cross_b0p0.dot(b0a0); 00487 } 00488 00489 00490 bool Intersect::intersect_VF(const Vec3f& a0, const Vec3f& b0, const Vec3f& c0, const Vec3f& p0, 00491 const Vec3f& a1, const Vec3f& b1, const Vec3f& c1, const Vec3f& p1, 00492 BVH_REAL* collision_time, Vec3f* p_i, bool useNewton) 00493 { 00494 *collision_time = 2.0; 00495 00496 Vec3f vp, va, vb, vc; 00497 vp = p1 - p0; 00498 va = a1 - a0; 00499 vb = b1 - b0; 00500 vc = c1 - c0; 00501 00502 BVH_REAL a, b, c, d; 00503 computeCubicCoeff_VF(a0, b0, c0, p0, va, vb, vc, vp, &a, &b, &c, &d); 00504 00505 if(isZero(a) && isZero(b) && isZero(c) && isZero(d)) 00506 { 00507 return false; 00508 } 00509 00510 /* 00511 if(isZero(a)) 00512 { 00513 return solveSquare(b, c, d, a0, b0, c0, p0, va, vb, vc, vp, true, collision_time); 00514 } 00515 */ 00516 00517 00518 BVH_REAL coeffs[4]; 00519 coeffs[3] = a, coeffs[2] = b, coeffs[1] = c, coeffs[0] = d; 00520 00521 if(useNewton) 00522 { 00523 BVH_REAL l = 0; 00524 BVH_REAL r = 1; 00525 00526 if(solveCubicWithIntervalNewton(a0, b0, c0, p0, va, vb, vc, vp, l, r, true, coeffs)) 00527 { 00528 *collision_time = 0.5 * (l + r); 00529 } 00530 } 00531 else 00532 { 00533 BVH_REAL roots[3]; 00534 int num = PolySolver::solveCubic(coeffs, roots); 00535 for(int i = 0; i < num; ++i) 00536 { 00537 BVH_REAL r = roots[i]; 00538 if(r < 0 || r > 1) continue; 00539 if(checkRootValidity_VF(a0, b0, c0, p0, va, vb, vc, vp, r)) 00540 { 00541 *collision_time = r; 00542 break; 00543 } 00544 } 00545 } 00546 00547 if(*collision_time > 1) 00548 { 00549 return false; 00550 } 00551 00552 *p_i = vp * (*collision_time) + p0; 00553 return true; 00554 } 00555 00556 bool Intersect::intersect_EE(const Vec3f& a0, const Vec3f& b0, const Vec3f& c0, const Vec3f& d0, 00557 const Vec3f& a1, const Vec3f& b1, const Vec3f& c1, const Vec3f& d1, 00558 BVH_REAL* collision_time, Vec3f* p_i, bool useNewton) 00559 { 00560 *collision_time = 2.0; 00561 00562 Vec3f va, vb, vc, vd; 00563 va = a1 - a0; 00564 vb = b1 - b0; 00565 vc = c1 - c0; 00566 vd = d1 - d0; 00567 00568 BVH_REAL a, b, c, d; 00569 computeCubicCoeff_EE(a0, b0, c0, d0, va, vb, vc, vd, &a, &b, &c, &d); 00570 00571 if(isZero(a) && isZero(b) && isZero(c) && isZero(d)) 00572 { 00573 return false; 00574 } 00575 /* 00576 if(isZero(a)) 00577 { 00578 return solveSquare(b, c, d, a0, b0, c0, d0, va, vb, vc, vd, collision_time, false); 00579 } 00580 */ 00581 00582 BVH_REAL coeffs[4]; 00583 coeffs[3] = a, coeffs[2] = b, coeffs[1] = c, coeffs[0] = d; 00584 00585 if(useNewton) 00586 { 00587 BVH_REAL l = 0; 00588 BVH_REAL r = 1; 00589 00590 if(solveCubicWithIntervalNewton(a0, b0, c0, d0, va, vb, vc, vd, l, r, false, coeffs, p_i)) 00591 { 00592 *collision_time = (l + r) * 0.5; 00593 } 00594 } 00595 else 00596 { 00597 BVH_REAL roots[3]; 00598 int num = PolySolver::solveCubic(coeffs, roots); 00599 for(int i = 0; i < num; ++i) 00600 { 00601 BVH_REAL r = roots[i]; 00602 if(r < 0 || r > 1) continue; 00603 00604 if(checkRootValidity_EE(a0, b0, c0, d0, va, vb, vc, vd, r, p_i)) 00605 { 00606 *collision_time = r; 00607 break; 00608 } 00609 } 00610 } 00611 00612 if(*collision_time > 1) 00613 { 00614 return false; 00615 } 00616 00617 return true; 00618 } 00619 00620 00621 bool Intersect::intersect_VE(const Vec3f& a0, const Vec3f& b0, const Vec3f& p0, 00622 const Vec3f& a1, const Vec3f& b1, const Vec3f& p1, 00623 const Vec3f& L) 00624 { 00625 Vec3f va, vb, vp; 00626 va = a1 - a0; 00627 vb = b1 - b0; 00628 vp = p1 - p0; 00629 00630 BVH_REAL a, b, c; 00631 computeCubicCoeff_VE(a0, b0, p0, va, vb, vp, L, &a, &b, &c); 00632 00633 if(isZero(a) && isZero(b) && isZero(c)) 00634 return true; 00635 00636 return solveSquare(a, b, c, a0, b0, p0, va, vb, vp); 00637 00638 } 00639 00640 00642 bool Intersect::intersectPreFiltering(const Vec3f& a0, const Vec3f& b0, const Vec3f& c0, const Vec3f& d0, 00643 const Vec3f& a1, const Vec3f& b1, const Vec3f& c1, const Vec3f& d1) 00644 { 00645 Vec3f n0 = (b0 - a0).cross(c0 - a0); 00646 Vec3f n1 = (b1 - a1).cross(c1 - a1); 00647 Vec3f a0a1 = a1 - a0; 00648 Vec3f b0b1 = b1 - b0; 00649 Vec3f c0c1 = c1 - c0; 00650 Vec3f delta = (b0b1 - a0a1).cross(c0c1 - a0a1); 00651 Vec3f nx = (n0 + n1 - delta) * 0.5; 00652 00653 Vec3f a0d0 = d0 - a0; 00654 Vec3f a1d1 = d1 - a1; 00655 00656 BVH_REAL A = n0.dot(a0d0); 00657 BVH_REAL B = n1.dot(a1d1); 00658 BVH_REAL C = nx.dot(a0d0); 00659 BVH_REAL D = nx.dot(a1d1); 00660 BVH_REAL E = n1.dot(a0d0); 00661 BVH_REAL F = n0.dot(a1d1); 00662 00663 if(A > 0 && B > 0 && (2*C +F) > 0 && (2*D+E) > 0) 00664 return false; 00665 if(A < 0 && B < 0 && (2*C +F) < 0 && (2*D+E) < 0) 00666 return false; 00667 00668 return true; 00669 } 00670 00671 bool Intersect::intersect_VF_filtered(const Vec3f& a0, const Vec3f& b0, const Vec3f& c0, const Vec3f& p0, 00672 const Vec3f& a1, const Vec3f& b1, const Vec3f& c1, const Vec3f& p1, 00673 BVH_REAL* collision_time, Vec3f* p_i, bool useNewton) 00674 { 00675 if(intersectPreFiltering(a0, b0, c0, p0, a1, b1, c1, p1)) 00676 { 00677 return intersect_VF(a0, b0, c0, p0, a1, b1, c1, p1, collision_time, p_i, useNewton); 00678 } 00679 else 00680 return false; 00681 } 00682 00683 bool Intersect::intersect_EE_filtered(const Vec3f& a0, const Vec3f& b0, const Vec3f& c0, const Vec3f& d0, 00684 const Vec3f& a1, const Vec3f& b1, const Vec3f& c1, const Vec3f& d1, 00685 BVH_REAL* collision_time, Vec3f* p_i, bool useNewton) 00686 { 00687 if(intersectPreFiltering(a0, b0, c0, d0, a1, b1, c1, d1)) 00688 { 00689 return intersect_EE(a0, b0, c0, d0, a1, b1, c1, d1, collision_time, p_i, useNewton); 00690 } 00691 else 00692 return false; 00693 } 00694 00695 bool Intersect::intersect_Triangle(const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, 00696 const Vec3f& Q1, const Vec3f& Q2, const Vec3f& Q3, 00697 const Vec3f R[3], const Vec3f& T, 00698 Vec3f* contact_points, 00699 unsigned int* num_contact_points, 00700 BVH_REAL* penetration_depth, 00701 Vec3f* normal) 00702 { 00703 Vec3f Q1_ = Vec3f(R[0].dot(Q1), R[1].dot(Q1), R[2].dot(Q1)) + T; 00704 Vec3f Q2_ = Vec3f(R[0].dot(Q2), R[1].dot(Q2), R[2].dot(Q2)) + T; 00705 Vec3f Q3_ = Vec3f(R[0].dot(Q3), R[1].dot(Q3), R[2].dot(Q3)) + T; 00706 00707 return intersect_Triangle(P1, P2, P3, Q1_, Q2_, Q3_, contact_points, num_contact_points, penetration_depth, normal); 00708 } 00709 00710 #if ODE_STYLE 00711 bool Intersect::intersect_Triangle(const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, 00712 const Vec3f& Q1, const Vec3f& Q2, const Vec3f& Q3, 00713 Vec3f* contact_points, 00714 unsigned int* num_contact_points, 00715 BVH_REAL* penetration_depth, 00716 Vec3f* normal) 00717 { 00718 00719 00720 Vec3f n1; 00721 BVH_REAL t1; 00722 bool b1 = buildTrianglePlane(P1, P2, P3, &n1, &t1); 00723 if(!b1) return false; 00724 00725 Vec3f n2; 00726 BVH_REAL t2; 00727 bool b2 = buildTrianglePlane(Q1, Q2, Q3, &n2, &t2); 00728 if(!b2) return false; 00729 00730 if(sameSideOfPlane(P1, P2, P3, n2, t2)) 00731 return false; 00732 00733 if(sameSideOfPlane(Q1, Q2, Q3, n1, t1)) 00734 return false; 00735 00736 Vec3f clipped_points1[MAX_TRIANGLE_CLIPS]; 00737 unsigned int num_clipped_points1 = 0; 00738 Vec3f clipped_points2[MAX_TRIANGLE_CLIPS]; 00739 unsigned int num_clipped_points2 = 0; 00740 00741 Vec3f deepest_points1[MAX_TRIANGLE_CLIPS]; 00742 unsigned int num_deepest_points1 = 0; 00743 Vec3f deepest_points2[MAX_TRIANGLE_CLIPS]; 00744 unsigned int num_deepest_points2 = 0; 00745 BVH_REAL penetration_depth1 = -1, penetration_depth2 = -1; 00746 00747 clipTriangleByTriangleAndEdgePlanes(Q1, Q2, Q3, P1, P2, P3, n1, t1, clipped_points2, &num_clipped_points2); 00748 00749 if(num_clipped_points2 == 0) 00750 return false; 00751 00752 computeDeepestPoints(clipped_points2, num_clipped_points2, n1, t1, &penetration_depth2, deepest_points2, &num_deepest_points2); 00753 if(num_deepest_points2 == 0) 00754 return false; 00755 00756 clipTriangleByTriangleAndEdgePlanes(P1, P2, P3, Q1, Q2, Q3, n2, t2, clipped_points1, &num_clipped_points1); 00757 if(num_clipped_points1 == 0) 00758 return false; 00759 00760 computeDeepestPoints(clipped_points1, num_clipped_points1, n2, t2, &penetration_depth1, deepest_points1, &num_deepest_points1); 00761 if(num_deepest_points1 == 0) 00762 return false; 00763 00764 00765 /* Return contact information */ 00766 if(contact_points && num_contact_points && penetration_depth && normal) 00767 { 00768 if(penetration_depth1 > penetration_depth2) 00769 { 00770 *num_contact_points = num_deepest_points2; 00771 for(unsigned int i = 0; i < num_deepest_points2; ++i) 00772 { 00773 contact_points[i] = deepest_points2[i]; 00774 } 00775 00776 *normal = -n1; 00777 *penetration_depth = penetration_depth2; 00778 } 00779 else 00780 { 00781 *num_contact_points = num_deepest_points1; 00782 for(unsigned int i = 0; i < num_deepest_points1; ++i) 00783 { 00784 contact_points[i] = deepest_points1[i]; 00785 } 00786 00787 *normal = n2; 00788 *penetration_depth = penetration_depth1; 00789 } 00790 } 00791 00792 return true; 00793 } 00794 #else 00795 bool Intersect::intersect_Triangle(const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, 00796 const Vec3f& Q1, const Vec3f& Q2, const Vec3f& Q3, 00797 Vec3f* contact_points, 00798 unsigned int* num_contact_points, 00799 BVH_REAL* penetration_depth, 00800 Vec3f* normal) 00801 { 00802 Vec3f p1, p2, p3, q1, q2, q3, e1, e2, e3, f1, f2, f3, g1, g2, g3, h1, h2, h3, n1, m1; 00803 Vec3f ef11, ef12, ef13, ef21, ef22, ef23, ef31, ef32, ef33; 00804 00805 p1 = P1 - P1; 00806 p2 = P2 - P1; 00807 p3 = P3 - P1; 00808 q1 = Q1 - P1; 00809 q2 = Q2 - P1; 00810 q3 = Q3 - P1; 00811 e1 = p2 - p1; 00812 e2 = p3 - p2; 00813 e3 = p1 - p3; 00814 f1 = q2 - q1; 00815 f2 = q3 - q2; 00816 f3 = q1 - q3; 00817 00818 n1 = e1.cross(e2); 00819 m1 = f1.cross(f2); 00820 g1 = e1.cross(n1); 00821 g2 = e2.cross(n1); 00822 g3 = e3.cross(n1); 00823 h1 = f1.cross(m1); 00824 h2 = f2.cross(m1); 00825 h3 = f3.cross(m1); 00826 00827 ef11 = e1.cross(f1); 00828 ef12 = e1.cross(f2); 00829 ef13 = e1.cross(f3); 00830 ef21 = e2.cross(f1); 00831 ef22 = e2.cross(f2); 00832 ef23 = e2.cross(f3); 00833 ef31 = e3.cross(f1); 00834 ef32 = e3.cross(f2); 00835 ef33 = e3.cross(f3); 00836 00837 if (!project6(n1, p1, p2, p3, q1, q2, q3)) return 0; 00838 if (!project6(m1, p1, p2, p3, q1, q2, q3)) return 0; 00839 00840 if (!project6(ef11, p1, p2, p3, q1, q2, q3)) return 0; 00841 if (!project6(ef12, p1, p2, p3, q1, q2, q3)) return 0; 00842 if (!project6(ef13, p1, p2, p3, q1, q2, q3)) return 0; 00843 if (!project6(ef21, p1, p2, p3, q1, q2, q3)) return 0; 00844 if (!project6(ef22, p1, p2, p3, q1, q2, q3)) return 0; 00845 if (!project6(ef23, p1, p2, p3, q1, q2, q3)) return 0; 00846 if (!project6(ef31, p1, p2, p3, q1, q2, q3)) return 0; 00847 if (!project6(ef32, p1, p2, p3, q1, q2, q3)) return 0; 00848 if (!project6(ef33, p1, p2, p3, q1, q2, q3)) return 0; 00849 00850 if (!project6(g1, p1, p2, p3, q1, q2, q3)) return 0; 00851 if (!project6(g2, p1, p2, p3, q1, q2, q3)) return 0; 00852 if (!project6(g3, p1, p2, p3, q1, q2, q3)) return 0; 00853 if (!project6(h1, p1, p2, p3, q1, q2, q3)) return 0; 00854 if (!project6(h2, p1, p2, p3, q1, q2, q3)) return 0; 00855 if (!project6(h3, p1, p2, p3, q1, q2, q3)) return 0; 00856 00857 if(contact_points && num_contact_points && penetration_depth && normal) 00858 { 00859 Vec3f n1, n2; 00860 BVH_REAL t1, t2; 00861 buildTrianglePlane(P1, P2, P3, &n1, &t1); 00862 buildTrianglePlane(Q1, Q2, Q3, &n2, &t2); 00863 00864 Vec3f deepest_points1[3]; 00865 unsigned int num_deepest_points1 = 0; 00866 Vec3f deepest_points2[3]; 00867 unsigned int num_deepest_points2 = 0; 00868 BVH_REAL penetration_depth1, penetration_depth2; 00869 00870 Vec3f P[3] = {P1, P2, P3}; 00871 Vec3f Q[3] = {Q1, Q2, Q3}; 00872 00873 computeDeepestPoints(Q, 3, n1, t1, &penetration_depth2, deepest_points2, &num_deepest_points2); 00874 computeDeepestPoints(P, 3, n2, t2, &penetration_depth1, deepest_points1, &num_deepest_points1); 00875 00876 00877 if(penetration_depth1 > penetration_depth2) 00878 { 00879 *num_contact_points = std::min(num_deepest_points2, (unsigned int)2); 00880 for(unsigned int i = 0; i < num_deepest_points2; ++i) 00881 { 00882 contact_points[i] = deepest_points2[i]; 00883 } 00884 00885 *normal = -n1; 00886 *penetration_depth = penetration_depth2; 00887 } 00888 else 00889 { 00890 *num_contact_points = std::min(num_deepest_points1, (unsigned int)2); 00891 for(unsigned int i = 0; i < num_deepest_points1; ++i) 00892 { 00893 contact_points[i] = deepest_points1[i]; 00894 } 00895 00896 *normal = n2; 00897 *penetration_depth = penetration_depth1; 00898 } 00899 } 00900 00901 return 1; 00902 } 00903 #endif 00904 00905 00906 void Intersect::computeDeepestPoints(Vec3f* clipped_points, unsigned int num_clipped_points, const Vec3f& n, BVH_REAL t, BVH_REAL* penetration_depth, Vec3f* deepest_points, unsigned int* num_deepest_points) 00907 { 00908 *num_deepest_points = 0; 00909 BVH_REAL max_depth = -std::numeric_limits<BVH_REAL>::max(); 00910 unsigned int num_deepest_points_ = 0; 00911 unsigned int num_neg = 0; 00912 unsigned int num_pos = 0; 00913 unsigned int num_zero = 0; 00914 00915 for(unsigned int i = 0; i < num_clipped_points; ++i) 00916 { 00917 BVH_REAL dist = -distanceToPlane(n, t, clipped_points[i]); 00918 if(dist > EPSILON) num_pos++; 00919 else if(dist < -EPSILON) num_neg++; 00920 else num_zero++; 00921 if(dist > max_depth) 00922 { 00923 max_depth = dist; 00924 num_deepest_points_ = 1; 00925 deepest_points[num_deepest_points_ - 1] = clipped_points[i]; 00926 } 00927 else if(dist + 1e-6 >= max_depth) 00928 { 00929 num_deepest_points_++; 00930 deepest_points[num_deepest_points_ - 1] = clipped_points[i]; 00931 } 00932 } 00933 00934 if(max_depth < -EPSILON) 00935 num_deepest_points_ = 0; 00936 00937 if(num_zero == 0 && ((num_neg == 0) || (num_pos == 0))) 00938 num_deepest_points_ = 0; 00939 00940 *penetration_depth = max_depth; 00941 *num_deepest_points = num_deepest_points_; 00942 } 00943 00944 void Intersect::clipTriangleByTriangleAndEdgePlanes(const Vec3f& v1, const Vec3f& v2, const Vec3f& v3, 00945 const Vec3f& t1, const Vec3f& t2, const Vec3f& t3, 00946 const Vec3f& tn, BVH_REAL to, 00947 Vec3f clipped_points[], unsigned int* num_clipped_points, 00948 bool clip_triangle) 00949 { 00950 *num_clipped_points = 0; 00951 Vec3f temp_clip[MAX_TRIANGLE_CLIPS]; 00952 Vec3f temp_clip2[MAX_TRIANGLE_CLIPS]; 00953 unsigned int num_temp_clip = 0; 00954 unsigned int num_temp_clip2 = 0; 00955 Vec3f v[3] = {v1, v2, v3}; 00956 00957 Vec3f plane_n; 00958 BVH_REAL plane_dist; 00959 00960 if(buildEdgePlane(t1, t2, tn, &plane_n, &plane_dist)) 00961 { 00962 clipPolygonByPlane(v, 3, plane_n, plane_dist, temp_clip, &num_temp_clip); 00963 if(num_temp_clip > 0) 00964 { 00965 if(buildEdgePlane(t2, t3, tn, &plane_n, &plane_dist)) 00966 { 00967 clipPolygonByPlane(temp_clip, num_temp_clip, plane_n, plane_dist, temp_clip2, &num_temp_clip2); 00968 if(num_temp_clip2 > 0) 00969 { 00970 if(buildEdgePlane(t3, t1, tn, &plane_n, &plane_dist)) 00971 { 00972 if(clip_triangle) 00973 { 00974 num_temp_clip = 0; 00975 clipPolygonByPlane(temp_clip2, num_temp_clip2, plane_n, plane_dist, temp_clip, &num_temp_clip); 00976 if(num_temp_clip > 0) 00977 { 00978 clipPolygonByPlane(temp_clip, num_temp_clip, tn, to, clipped_points, num_clipped_points); 00979 } 00980 } 00981 else 00982 { 00983 clipPolygonByPlane(temp_clip2, num_temp_clip2, plane_n, plane_dist, clipped_points, num_clipped_points); 00984 } 00985 } 00986 } 00987 } 00988 } 00989 } 00990 } 00991 00992 void Intersect::clipPolygonByPlane(Vec3f* polygon_points, unsigned int num_polygon_points, const Vec3f& n, BVH_REAL t, Vec3f clipped_points[], unsigned int* num_clipped_points) 00993 { 00994 *num_clipped_points = 0; 00995 00996 unsigned int num_clipped_points_ = 0; 00997 unsigned int vi; 00998 unsigned int prev_classify = 2; 00999 unsigned int classify; 01000 for(unsigned int i = 0; i <= num_polygon_points; ++i) 01001 { 01002 vi = (i % num_polygon_points); 01003 BVH_REAL d = distanceToPlane(n, t, polygon_points[i]); 01004 classify = ((d > EPSILON) ? 1 : 0); 01005 if(classify == 0) 01006 { 01007 if(prev_classify == 1) 01008 { 01009 if(num_clipped_points_ < MAX_TRIANGLE_CLIPS) 01010 { 01011 Vec3f tmp; 01012 clipSegmentByPlane(polygon_points[i - 1], polygon_points[vi], n, t, &tmp); 01013 if(num_clipped_points_ > 0) 01014 { 01015 if((tmp - clipped_points[num_clipped_points_ - 1]).sqrLength() > EPSILON) 01016 { 01017 clipped_points[num_clipped_points_] = tmp; 01018 num_clipped_points_++; 01019 } 01020 } 01021 else 01022 { 01023 clipped_points[num_clipped_points_] = tmp; 01024 num_clipped_points_++; 01025 } 01026 } 01027 } 01028 01029 if(num_clipped_points_ < MAX_TRIANGLE_CLIPS && i < num_polygon_points) 01030 { 01031 clipped_points[num_clipped_points_] = polygon_points[vi]; 01032 num_clipped_points_++; 01033 } 01034 } 01035 else 01036 { 01037 if(prev_classify == 0) 01038 { 01039 if(num_clipped_points_ < MAX_TRIANGLE_CLIPS) 01040 { 01041 Vec3f tmp; 01042 clipSegmentByPlane(polygon_points[i - 1], polygon_points[vi], n, t, &tmp); 01043 if(num_clipped_points_ > 0) 01044 { 01045 if((tmp - clipped_points[num_clipped_points_ - 1]).sqrLength() > EPSILON) 01046 { 01047 clipped_points[num_clipped_points_] = tmp; 01048 num_clipped_points_++; 01049 } 01050 } 01051 else 01052 { 01053 clipped_points[num_clipped_points_] = tmp; 01054 num_clipped_points_++; 01055 } 01056 } 01057 } 01058 } 01059 01060 prev_classify = classify; 01061 } 01062 01063 if(num_clipped_points_ > 2) 01064 { 01065 if((clipped_points[0] - clipped_points[num_clipped_points_ - 1]).sqrLength() < EPSILON) 01066 { 01067 num_clipped_points_--; 01068 } 01069 } 01070 01071 *num_clipped_points = num_clipped_points_; 01072 } 01073 01074 void Intersect::clipSegmentByPlane(const Vec3f& v1, const Vec3f& v2, const Vec3f& n, BVH_REAL t, Vec3f* clipped_point) 01075 { 01076 BVH_REAL dist1 = distanceToPlane(n, t, v1); 01077 Vec3f tmp = v2 - v1; 01078 BVH_REAL dist2 = tmp.dot(n); 01079 *clipped_point = tmp * (-dist1 / dist2) + v1; 01080 } 01081 01082 BVH_REAL Intersect::distanceToPlane(const Vec3f& n, BVH_REAL t, const Vec3f& v) 01083 { 01084 return n.dot(v) - t; 01085 } 01086 01087 bool Intersect::buildTrianglePlane(const Vec3f& v1, const Vec3f& v2, const Vec3f& v3, Vec3f* n, BVH_REAL* t) 01088 { 01089 Vec3f n_ = (v2 - v1).cross(v3 - v1); 01090 if(n_.normalize()) 01091 { 01092 *n = n_; 01093 *t = n_.dot(v1); 01094 return true; 01095 } 01096 01097 return false; 01098 } 01099 01100 bool Intersect::buildEdgePlane(const Vec3f& v1, const Vec3f& v2, const Vec3f& tn, Vec3f* n, BVH_REAL* t) 01101 { 01102 Vec3f n_ = (v2 - v1).cross(tn); 01103 if(n_.normalize()) 01104 { 01105 *n = n_; 01106 *t = n_.dot(v1); 01107 return true; 01108 } 01109 01110 return false; 01111 } 01112 01113 bool Intersect::sameSideOfPlane(const Vec3f& v1, const Vec3f& v2, const Vec3f& v3, const Vec3f& n, BVH_REAL t) 01114 { 01115 BVH_REAL dist1 = distanceToPlane(n, t, v1); 01116 BVH_REAL dist2 = dist1 * distanceToPlane(n, t, v2); 01117 BVH_REAL dist3 = dist1 * distanceToPlane(n, t, v3); 01118 if((dist2 > 0) && (dist3 > 0)) 01119 return true; 01120 return false; 01121 } 01122 01123 int Intersect::project6(const Vec3f& ax, 01124 const Vec3f& p1, const Vec3f& p2, const Vec3f& p3, 01125 const Vec3f& q1, const Vec3f& q2, const Vec3f& q3) 01126 { 01127 BVH_REAL P1 = ax.dot(p1); 01128 BVH_REAL P2 = ax.dot(p2); 01129 BVH_REAL P3 = ax.dot(p3); 01130 BVH_REAL Q1 = ax.dot(q1); 01131 BVH_REAL Q2 = ax.dot(q2); 01132 BVH_REAL Q3 = ax.dot(q3); 01133 01134 BVH_REAL mx1 = std::max(P1, std::max(P2, P3)); 01135 BVH_REAL mn1 = std::min(P1, std::min(P2, P3)); 01136 BVH_REAL mx2 = std::max(Q1, std::max(Q2, Q3)); 01137 BVH_REAL mn2 = std::min(Q1, std::min(Q2, Q3)); 01138 01139 if(mn1 > mx2) return 0; 01140 if(mn2 > mx1) return 0; 01141 return 1; 01142 } 01143 01144 01145 void TriangleDistance::segPoints(const Vec3f& P, const Vec3f& A, const Vec3f& Q, const Vec3f& B, 01146 Vec3f& VEC, Vec3f& X, Vec3f& Y) 01147 { 01148 Vec3f T; 01149 BVH_REAL A_dot_A, B_dot_B, A_dot_B, A_dot_T, B_dot_T; 01150 Vec3f TMP; 01151 01152 T = Q - P; 01153 A_dot_A = A.dot(A); 01154 B_dot_B = B.dot(B); 01155 A_dot_B = A.dot(B); 01156 A_dot_T = A.dot(T); 01157 B_dot_T = B.dot(T); 01158 01159 // t parameterizes ray P,A 01160 // u parameterizes ray Q,B 01161 01162 BVH_REAL t, u; 01163 01164 // compute t for the closest point on ray P,A to 01165 // ray Q,B 01166 01167 BVH_REAL denom = A_dot_A*B_dot_B - A_dot_B*A_dot_B; 01168 01169 t = (A_dot_T*B_dot_B - B_dot_T*A_dot_B) / denom; 01170 01171 // clamp result so t is on the segment P,A 01172 01173 if((t < 0) || isnan(t)) t = 0; else if(t > 1) t = 1; 01174 01175 // find u for point on ray Q,B closest to point at t 01176 01177 u = (t*A_dot_B - B_dot_T) / B_dot_B; 01178 01179 // if u is on segment Q,B, t and u correspond to 01180 // closest points, otherwise, clamp u, recompute and 01181 // clamp t 01182 01183 if((u <= 0) || isnan(u)) 01184 { 01185 Y = Q; 01186 01187 t = A_dot_T / A_dot_A; 01188 01189 if((t <= 0) || isnan(t)) 01190 { 01191 X = P; 01192 VEC = Q - P; 01193 } 01194 else if(t >= 1) 01195 { 01196 X = P + A; 01197 VEC = Q - X; 01198 } 01199 else 01200 { 01201 X = P + A * t; 01202 TMP = T.cross(A); 01203 VEC = A.cross(TMP); 01204 } 01205 } 01206 else if (u >= 1) 01207 { 01208 Y = Q + B; 01209 01210 t = (A_dot_B + A_dot_T) / A_dot_A; 01211 01212 if((t <= 0) || isnan(t)) 01213 { 01214 X = P; 01215 VEC = Y - P; 01216 } 01217 else if(t >= 1) 01218 { 01219 X = P + A; 01220 VEC = Y - X; 01221 } 01222 else 01223 { 01224 X = P + A * t; 01225 T = Y - P; 01226 TMP = T.cross(A); 01227 VEC= A.cross(TMP); 01228 } 01229 } 01230 else 01231 { 01232 Y = Q + B * u; 01233 01234 if((t <= 0) || isnan(t)) 01235 { 01236 X = P; 01237 TMP = T.cross(B); 01238 VEC = B.cross(TMP); 01239 } 01240 else if(t >= 1) 01241 { 01242 X = P + A; 01243 T = Q - X; 01244 TMP = T.cross(B); 01245 VEC = B.cross(TMP); 01246 } 01247 else 01248 { 01249 X = P + A * t; 01250 VEC = A.cross(B); 01251 if(VEC.dot(T) < 0) 01252 { 01253 VEC = VEC * (-1); 01254 } 01255 } 01256 } 01257 } 01258 01259 01260 BVH_REAL TriangleDistance::triDistance(const Vec3f S[3], const Vec3f T[3], Vec3f& P, Vec3f& Q) 01261 { 01262 // Compute vectors along the 6 sides 01263 01264 Vec3f Sv[3]; 01265 Vec3f Tv[3]; 01266 Vec3f VEC; 01267 01268 Sv[0] = S[1] - S[0]; 01269 Sv[1] = S[2] - S[1]; 01270 Sv[2] = S[0] - S[2]; 01271 01272 Tv[0] = T[1] - T[0]; 01273 Tv[1] = T[2] - T[1]; 01274 Tv[2] = T[0] - T[2]; 01275 01276 // For each edge pair, the vector connecting the closest points 01277 // of the edges defines a slab (parallel planes at head and tail 01278 // enclose the slab). If we can show that the off-edge vertex of 01279 // each triangle is outside of the slab, then the closest points 01280 // of the edges are the closest points for the triangles. 01281 // Even if these tests fail, it may be helpful to know the closest 01282 // points found, and whether the triangles were shown disjoint 01283 01284 Vec3f V, Z, minP, minQ; 01285 BVH_REAL mindd; 01286 int shown_disjoint = 0; 01287 01288 mindd = (S[0] - T[0]).sqrLength() + 1; // Set first minimum safely high 01289 01290 for(int i = 0; i < 3; ++i) 01291 { 01292 for(int j = 0; j < 3; ++j) 01293 { 01294 // Find closest points on edges i & j, plus the 01295 // vector (and distance squared) between these points 01296 segPoints(S[i], Sv[i], T[j], Tv[j], VEC, P, Q); 01297 01298 V = Q - P; 01299 BVH_REAL dd = V.dot(V); 01300 01301 // Verify this closest point pair only if the distance 01302 // squared is less than the minimum found thus far. 01303 01304 if(dd <= mindd) 01305 { 01306 minP = P; 01307 minQ = Q; 01308 mindd = dd; 01309 01310 Z = S[(i+2)%3] - P; 01311 BVH_REAL a = Z.dot(VEC); 01312 Z = T[(j+2)%3] - Q; 01313 BVH_REAL b = Z.dot(VEC); 01314 01315 if((a <= 0) && (b >= 0)) return sqrt(dd); 01316 01317 BVH_REAL p = V.dot(VEC); 01318 01319 if(a < 0) a = 0; 01320 if(b > 0) b = 0; 01321 if((p - a + b) > 0) shown_disjoint = 1; 01322 } 01323 } 01324 } 01325 01326 // No edge pairs contained the closest points. 01327 // either: 01328 // 1. one of the closest points is a vertex, and the 01329 // other point is interior to a face. 01330 // 2. the triangles are overlapping. 01331 // 3. an edge of one triangle is parallel to the other's face. If 01332 // cases 1 and 2 are not true, then the closest points from the 9 01333 // edge pairs checks above can be taken as closest points for the 01334 // triangles. 01335 // 4. possibly, the triangles were degenerate. When the 01336 // triangle points are nearly colinear or coincident, one 01337 // of above tests might fail even though the edges tested 01338 // contain the closest points. 01339 01340 // First check for case 1 01341 01342 Vec3f Sn; 01343 BVH_REAL Snl; 01344 01345 Sn = Sv[0].cross(Sv[1]); // Compute normal to S triangle 01346 Snl = Sn.dot(Sn); // Compute square of length of normal 01347 01348 // If cross product is long enough, 01349 01350 if(Snl > 1e-15) 01351 { 01352 // Get projection lengths of T points 01353 01354 Vec3f Tp; 01355 01356 V = S[0] - T[0]; 01357 Tp[0] = V.dot(Sn); 01358 01359 V = S[0] - T[1]; 01360 Tp[1] = V.dot(Sn); 01361 01362 V = S[0] - T[2]; 01363 Tp[2] = V.dot(Sn); 01364 01365 // If Sn is a separating direction, 01366 // find point with smallest projection 01367 01368 int point = -1; 01369 if((Tp[0] > 0) && (Tp[1] > 0) && (Tp[2] > 0)) 01370 { 01371 if(Tp[0] < Tp[1]) point = 0; else point = 1; 01372 if(Tp[2] < Tp[point]) point = 2; 01373 } 01374 else if((Tp[0] < 0) && (Tp[1] < 0) && (Tp[2] < 0)) 01375 { 01376 if(Tp[0] > Tp[1]) point = 0; else point = 1; 01377 if(Tp[2] > Tp[point]) point = 2; 01378 } 01379 01380 // If Sn is a separating direction, 01381 01382 if(point >= 0) 01383 { 01384 shown_disjoint = 1; 01385 01386 // Test whether the point found, when projected onto the 01387 // other triangle, lies within the face. 01388 01389 V = T[point] - S[0]; 01390 Z = Sn.cross(Sv[0]); 01391 if(V.dot(Z) > 0) 01392 { 01393 V = T[point] - S[1]; 01394 Z = Sn.cross(Sv[1]); 01395 if(V.dot(Z) > 0) 01396 { 01397 V = T[point] - S[2]; 01398 Z = Sn.cross(Sv[2]); 01399 if(V.dot(Z) > 0) 01400 { 01401 // T[point] passed the test - it's a closest point for 01402 // the T triangle; the other point is on the face of S 01403 P = T[point] + Sn * (Tp[point] / Snl); 01404 Q = T[point]; 01405 return (P - Q).length(); 01406 } 01407 } 01408 } 01409 } 01410 } 01411 01412 Vec3f Tn; 01413 BVH_REAL Tnl; 01414 01415 Tn = Tv[0].cross(Tv[1]); 01416 Tnl = Tn.dot(Tn); 01417 01418 if(Tnl > 1e-15) 01419 { 01420 Vec3f Sp; 01421 01422 V = T[0] - S[0]; 01423 Sp[0] = V.dot(Tn); 01424 01425 V = T[0] - S[1]; 01426 Sp[1] = V.dot(Tn); 01427 01428 V = T[0] - S[2]; 01429 Sp[2] = V.dot(Tn); 01430 01431 int point = -1; 01432 if((Sp[0] > 0) && (Sp[1] > 0) && (Sp[2] > 0)) 01433 { 01434 if(Sp[0] < Sp[1]) point = 0; else point = 1; 01435 if(Sp[2] < Sp[point]) point = 2; 01436 } 01437 else if((Sp[0] < 0) && (Sp[1] < 0) && (Sp[2] < 0)) 01438 { 01439 if(Sp[0] > Sp[1]) point = 0; else point = 1; 01440 if(Sp[2] > Sp[point]) point = 2; 01441 } 01442 01443 if(point >= 0) 01444 { 01445 shown_disjoint = 1; 01446 01447 V = S[point] - T[0]; 01448 Z = Tn.cross(Tv[0]); 01449 if(V.dot(Z) > 0) 01450 { 01451 V = S[point] - T[1]; 01452 Z = Tn.cross(Tv[1]); 01453 if(V.dot(Z) > 0) 01454 { 01455 V = S[point] - T[2]; 01456 Z = Tn.cross(Tv[2]); 01457 if(V.dot(Z) > 0) 01458 { 01459 P = S[point]; 01460 Q = S[point] + Tn * (Sp[point] / Tnl); 01461 return (P - Q).length(); 01462 } 01463 } 01464 } 01465 } 01466 } 01467 01468 // Case 1 can't be shown. 01469 // If one of these tests showed the triangles disjoint, 01470 // we assume case 3 or 4, otherwise we conclude case 2, 01471 // that the triangles overlap. 01472 01473 if(shown_disjoint) 01474 { 01475 P = minP; 01476 Q = minQ; 01477 return sqrt(mindd); 01478 } 01479 else return 0; 01480 } 01481 01482 01483 BVH_REAL TriangleDistance::triDistance(const Vec3f& S1, const Vec3f& S2, const Vec3f& S3, 01484 const Vec3f& T1, const Vec3f& T2, const Vec3f& T3, 01485 Vec3f& P, Vec3f& Q) 01486 { 01487 Vec3f S[3]; 01488 Vec3f T[3]; 01489 S[0] = S1; S[1] = S2; S[2] = S3; 01490 T[0] = T1; T[1] = T2; T[2] = T3; 01491 01492 return triDistance(S, T, P, Q); 01493 } 01494 01495 BVH_REAL TriangleDistance::triDistance(const Vec3f S[3], const Vec3f T[3], 01496 const Vec3f R[3], const Vec3f& Tl, 01497 Vec3f& P, Vec3f& Q) 01498 { 01499 Vec3f T_transformed[3]; 01500 T_transformed[0] = MxV(R, T[0]) + Tl; 01501 T_transformed[1] = MxV(R, T[1]) + Tl; 01502 T_transformed[2] = MxV(R, T[2]) + Tl; 01503 01504 return triDistance(S, T_transformed, P, Q); 01505 } 01506 01507 BVH_REAL TriangleDistance::triDistance(const Vec3f& S1, const Vec3f& S2, const Vec3f& S3, 01508 const Vec3f& T1, const Vec3f& T2, const Vec3f& T3, 01509 const Vec3f R[3], const Vec3f& Tl, 01510 Vec3f& P, Vec3f& Q) 01511 { 01512 Vec3f T1_transformed = MxV(R, T1) + Tl; 01513 Vec3f T2_transformed = MxV(R, T2) + Tl; 01514 Vec3f T3_transformed = MxV(R, T3) + Tl; 01515 return triDistance(S1, S2, S3, T1_transformed, T2_transformed, T3_transformed, P, Q); 01516 } 01517 01518 }