$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/BV_fitter.h" 00038 #include <limits> 00039 00040 namespace collision_checking 00041 { 00042 00044 void getCovariance(Vec3f* ps, Vec3f* ps2, unsigned int* indices, int n, Vec3f M[3]) 00045 { 00046 bool indirect_index = true; 00047 if(!indices) indirect_index = false; 00048 00049 Vec3f S1; 00050 Vec3f S2[3]; 00051 00052 for(int i = 0; i < n; ++i) 00053 { 00054 const Vec3f& p = indirect_index ? ps[indices[i]] : ps[i]; 00055 S1 += p; 00056 S2[0][0] += (p[0] * p[0]); 00057 S2[1][1] += (p[1] * p[1]); 00058 S2[2][2] += (p[2] * p[2]); 00059 S2[0][1] += (p[0] * p[1]); 00060 S2[0][2] += (p[0] * p[2]); 00061 S2[1][2] += (p[1] * p[2]); 00062 00063 if(ps2) // another frame 00064 { 00065 const Vec3f& p = indirect_index ? ps2[indices[i]] : ps2[i]; 00066 S1 += p; 00067 S2[0][0] += (p[0] * p[0]); 00068 S2[1][1] += (p[1] * p[1]); 00069 S2[2][2] += (p[2] * p[2]); 00070 S2[0][1] += (p[0] * p[1]); 00071 S2[0][2] += (p[0] * p[2]); 00072 S2[1][2] += (p[1] * p[2]); 00073 } 00074 } 00075 00076 int n_points = ((ps2 == NULL) ? n : 2*n); 00077 00078 M[0][0] = S2[0][0] - S1[0]*S1[0] / n_points; 00079 M[1][1] = S2[1][1] - S1[1]*S1[1] / n_points; 00080 M[2][2] = S2[2][2] - S1[2]*S1[2] / n_points; 00081 M[0][1] = S2[0][1] - S1[0]*S1[1] / n_points; 00082 M[1][2] = S2[1][2] - S1[1]*S1[2] / n_points; 00083 M[0][2] = S2[0][2] - S1[0]*S1[2] / n_points; 00084 M[1][0] = M[0][1]; 00085 M[2][0] = M[0][2]; 00086 M[2][1] = M[1][2]; 00087 } 00088 00090 void getCovariance(Vec3f* ps, Vec3f* ps2, Triangle* ts, unsigned int* indices, int n, Vec3f M[3]) 00091 { 00092 bool indirect_index = true; 00093 if(!indices) indirect_index = false; 00094 00095 Vec3f S1; 00096 Vec3f S2[3]; 00097 00098 for(int i = 0; i < n; ++i) 00099 { 00100 const Triangle& t = indirect_index ? ts[indices[i]] : ts[i]; 00101 00102 const Vec3f& p1 = ps[t[0]]; 00103 const Vec3f& p2 = ps[t[1]]; 00104 const Vec3f& p3 = ps[t[2]]; 00105 00106 S1[0] += (p1[0] + p2[0] + p3[0]); 00107 S1[1] += (p1[1] + p2[1] + p3[1]); 00108 S1[2] += (p1[2] + p2[2] + p3[2]); 00109 00110 S2[0][0] += (p1[0] * p1[0] + 00111 p2[0] * p2[0] + 00112 p3[0] * p3[0]); 00113 S2[1][1] += (p1[1] * p1[1] + 00114 p2[1] * p2[1] + 00115 p3[1] * p3[1]); 00116 S2[2][2] += (p1[2] * p1[2] + 00117 p2[2] * p2[2] + 00118 p3[2] * p3[2]); 00119 S2[0][1] += (p1[0] * p1[1] + 00120 p2[0] * p2[1] + 00121 p3[0] * p3[1]); 00122 S2[0][2] += (p1[0] * p1[2] + 00123 p2[0] * p2[2] + 00124 p3[0] * p3[2]); 00125 S2[1][2] += (p1[1] * p1[2] + 00126 p2[1] * p2[2] + 00127 p3[1] * p3[2]); 00128 00129 if(ps2) 00130 { 00131 const Vec3f& p1 = ps2[t[0]]; 00132 const Vec3f& p2 = ps2[t[1]]; 00133 const Vec3f& p3 = ps2[t[2]]; 00134 00135 S1[0] += (p1[0] + p2[0] + p3[0]); 00136 S1[1] += (p1[1] + p2[1] + p3[1]); 00137 S1[2] += (p1[2] + p2[2] + p3[2]); 00138 00139 S2[0][0] += (p1[0] * p1[0] + 00140 p2[0] * p2[0] + 00141 p3[0] * p3[0]); 00142 S2[1][1] += (p1[1] * p1[1] + 00143 p2[1] * p2[1] + 00144 p3[1] * p3[1]); 00145 S2[2][2] += (p1[2] * p1[2] + 00146 p2[2] * p2[2] + 00147 p3[2] * p3[2]); 00148 S2[0][1] += (p1[0] * p1[1] + 00149 p2[0] * p2[1] + 00150 p3[0] * p3[1]); 00151 S2[0][2] += (p1[0] * p1[2] + 00152 p2[0] * p2[2] + 00153 p3[0] * p3[2]); 00154 S2[1][2] += (p1[1] * p1[2] + 00155 p2[1] * p2[2] + 00156 p3[1] * p3[2]); 00157 } 00158 } 00159 00160 int n_points = ((ps2 == NULL) ? 3*n : 6*n); 00161 00162 M[0][0] = S2[0][0] - S1[0]*S1[0] / n_points; 00163 M[1][1] = S2[1][1] - S1[1]*S1[1] / n_points; 00164 M[2][2] = S2[2][2] - S1[2]*S1[2] / n_points; 00165 M[0][1] = S2[0][1] - S1[0]*S1[1] / n_points; 00166 M[1][2] = S2[1][2] - S1[1]*S1[2] / n_points; 00167 M[0][2] = S2[0][2] - S1[0]*S1[2] / n_points; 00168 M[1][0] = M[0][1]; 00169 M[2][0] = M[0][2]; 00170 M[2][1] = M[1][2]; 00171 } 00172 00173 00175 void Meigen(Vec3f a[3], BVH_REAL dout[3], Vec3f vout[3]) 00176 { 00177 int n = 3; 00178 int j, iq, ip, i; 00179 BVH_REAL tresh, theta, tau, t, sm, s, h, g, c; 00180 int nrot; 00181 BVH_REAL b[3]; 00182 BVH_REAL z[3]; 00183 BVH_REAL v[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}}; 00184 BVH_REAL d[3]; 00185 00186 for(ip = 0; ip < n; ++ip) 00187 { 00188 b[ip] = a[ip][ip]; 00189 d[ip] = a[ip][ip]; 00190 z[ip] = 0.0; 00191 } 00192 00193 nrot = 0; 00194 00195 for(i = 0; i < 50; ++i) 00196 { 00197 sm = 0.0; 00198 for(ip = 0; ip < n; ++ip) 00199 for(iq = ip + 1; iq < n; ++iq) 00200 sm += fabs(a[ip][iq]); 00201 if(sm == 0.0) 00202 { 00203 vout[0] = v[0]; 00204 vout[1] = v[1]; 00205 vout[2] = v[2]; 00206 dout[0] = d[0]; dout[1] = d[1]; dout[2] = d[2]; 00207 return; 00208 } 00209 00210 if(i < 3) tresh = 0.2 * sm / (n * n); 00211 else tresh = 0.0; 00212 00213 for(ip = 0; ip < n; ++ip) 00214 { 00215 for(iq= ip + 1; iq < n; ++iq) 00216 { 00217 g = 100.0 * fabs(a[ip][iq]); 00218 if(i > 3 && 00219 fabs(d[ip]) + g == fabs(d[ip]) && 00220 fabs(d[iq]) + g == fabs(d[iq])) 00221 a[ip][iq] = 0.0; 00222 else if(fabs(a[ip][iq]) > tresh) 00223 { 00224 h = d[iq] - d[ip]; 00225 if(fabs(h) + g == fabs(h)) t = (a[ip][iq]) / h; 00226 else 00227 { 00228 theta = 0.5 * h / (a[ip][iq]); 00229 t = 1.0 /(fabs(theta) + sqrt(1.0 + theta * theta)); 00230 if(theta < 0.0) t = -t; 00231 } 00232 c = 1.0 / sqrt(1 + t * t); 00233 s = t * c; 00234 tau = s / (1.0 + c); 00235 h = t * a[ip][iq]; 00236 z[ip] -= h; 00237 z[iq] += h; 00238 d[ip] -= h; 00239 d[iq] += h; 00240 a[ip][iq] = 0.0; 00241 for(j = 0; j < ip; ++j) { g = a[j][ip]; h = a[j][iq]; a[j][ip] = g - s * (h + g * tau); a[j][iq] = h + s * (g - h * tau); } 00242 for(j = ip + 1; j < iq; ++j) { g = a[ip][j]; h = a[j][iq]; a[ip][j] = g - s * (h + g * tau); a[j][iq] = h + s * (g - h * tau); } 00243 for(j = iq + 1; j < n; ++j) { g = a[ip][j]; h = a[iq][j]; a[ip][j] = g - s * (h + g * tau); a[iq][j] = h + s * (g - h * tau); } 00244 for(j = 0; j < n; ++j) { g = v[j][ip]; h = v[j][iq]; v[j][ip] = g - s * (h + g * tau); v[j][iq] = h + s * (g - h * tau); } 00245 nrot++; 00246 } 00247 } 00248 } 00249 for(ip = 0; ip < n; ++ip) 00250 { 00251 b[ip] += z[ip]; 00252 d[ip] = b[ip]; 00253 z[ip] = 0.0; 00254 } 00255 } 00256 00257 std::cerr << "eigen: too many iterations in Jacobi transform." << std::endl; 00258 00259 return; 00260 } 00261 00262 00266 void getRadiusAndOriginAndRectangleSize(Vec3f* ps, Vec3f* ps2, unsigned int* indices, int n, Vec3f axis[3], Vec3f& origin, BVH_REAL l[2], BVH_REAL& r) 00267 { 00268 bool indirect_index = true; 00269 if(!indices) indirect_index = false; 00270 00271 int size_P = (ps2 == NULL) ? n : (2 * n); 00272 00273 BVH_REAL (*P)[3] = new BVH_REAL[size_P][3]; 00274 00275 00276 int P_id = 0; 00277 for(int i = 0; i < n; ++i) 00278 { 00279 int index = indirect_index ? indices[i] : i; 00280 00281 const Vec3f& p = ps[index]; 00282 Vec3f v(p[0], p[1], p[2]); 00283 P[P_id][0] = axis[0].dot(v); 00284 P[P_id][1] = axis[1].dot(v); 00285 P[P_id][2] = axis[2].dot(v); 00286 P_id++; 00287 00288 if(ps2) 00289 { 00290 const Vec3f& v = ps2[index]; 00291 P[P_id][0] = axis[0].dot(v); 00292 P[P_id][1] = axis[1].dot(v); 00293 P[P_id][2] = axis[2].dot(v); 00294 P_id++; 00295 } 00296 } 00297 00298 BVH_REAL minx, maxx, miny, maxy, minz, maxz; 00299 00300 BVH_REAL cz, radsqr; 00301 00302 minz = maxz = P[0][2]; 00303 00304 for(int i = 1; i < size_P; ++i) 00305 { 00306 BVH_REAL z_value = P[i][2]; 00307 if(z_value < minz) minz = z_value; 00308 else if(z_value > maxz) maxz = z_value; 00309 } 00310 00311 r = (BVH_REAL)0.5 * (maxz - minz); 00312 radsqr = r * r; 00313 cz = (BVH_REAL)0.5 * (maxz + minz); 00314 00315 // compute an initial length of rectangle along x direction 00316 00317 // find minx and maxx as starting points 00318 00319 int minindex, maxindex; 00320 minindex = maxindex = 0; 00321 BVH_REAL mintmp, maxtmp; 00322 mintmp = maxtmp = P[0][0]; 00323 00324 for(int i = 1; i < size_P; ++i) 00325 { 00326 BVH_REAL x_value = P[i][0]; 00327 if(x_value < mintmp) 00328 { 00329 minindex = i; 00330 mintmp = x_value; 00331 } 00332 else if(x_value > maxtmp) 00333 { 00334 maxindex = i; 00335 maxtmp = x_value; 00336 } 00337 } 00338 00339 BVH_REAL x, dz; 00340 dz = P[minindex][2] - cz; 00341 minx = P[minindex][0] + sqrt(std::max(radsqr - dz * dz, 0.0)); 00342 dz = P[maxindex][2] - cz; 00343 maxx = P[maxindex][0] - sqrt(std::max(radsqr - dz * dz, 0.0)); 00344 00345 00346 // grow minx 00347 00348 for(int i = 0; i < size_P; ++i) 00349 { 00350 if(P[i][0] < minx) 00351 { 00352 dz = P[i][2] - cz; 00353 x = P[i][0] + sqrt(std::max(radsqr - dz * dz, 0.0)); 00354 if(x < minx) minx = x; 00355 } 00356 } 00357 00358 // grow maxx 00359 00360 for(int i = 0; i < size_P; ++i) 00361 { 00362 if(P[i][0] > maxx) 00363 { 00364 dz = P[i][2] - cz; 00365 x = P[i][0] - sqrt(std::max(radsqr - dz * dz, 0.0)); 00366 if(x > maxx) maxx = x; 00367 } 00368 } 00369 00370 // compute an initial length of rectangle along y direction 00371 00372 // find miny and maxy as starting points 00373 00374 minindex = maxindex = 0; 00375 mintmp = maxtmp = P[0][1]; 00376 for(int i = 1; i < size_P; ++i) 00377 { 00378 BVH_REAL y_value = P[i][1]; 00379 if(y_value < mintmp) 00380 { 00381 minindex = i; 00382 mintmp = y_value; 00383 } 00384 else if(y_value > maxtmp) 00385 { 00386 maxindex = i; 00387 maxtmp = y_value; 00388 } 00389 } 00390 00391 BVH_REAL y; 00392 dz = P[minindex][2] - cz; 00393 miny = P[minindex][1] + sqrt(std::max(radsqr - dz * dz, 0.0)); 00394 dz = P[maxindex][2] - cz; 00395 maxy = P[maxindex][1] - sqrt(std::max(radsqr - dz * dz, 0.0)); 00396 00397 // grow miny 00398 00399 for(int i = 0; i < size_P; ++i) 00400 { 00401 if(P[i][1] < miny) 00402 { 00403 dz = P[i][2] - cz; 00404 y = P[i][1] + sqrt(std::max(radsqr - dz * dz, 0.0)); 00405 if(y < miny) miny = y; 00406 } 00407 } 00408 00409 // grow maxy 00410 00411 for(int i = 0; i < size_P; ++i) 00412 { 00413 if(P[i][1] > maxy) 00414 { 00415 dz = P[i][2] - cz; 00416 y = P[i][1] - sqrt(std::max(radsqr - dz * dz, 0.0)); 00417 if(y > maxy) maxy = y; 00418 } 00419 } 00420 00421 // corners may have some points which are not covered - grow lengths if necessary 00422 // quite conservative (can be improved) 00423 00424 BVH_REAL dx, dy, u, t; 00425 BVH_REAL a = sqrt((BVH_REAL)0.5); 00426 for(int i = 0; i < size_P; ++i) 00427 { 00428 if(P[i][0] > maxx) 00429 { 00430 if(P[i][1] > maxy) 00431 { 00432 dx = P[i][0] - maxx; 00433 dy = P[i][1] - maxy; 00434 u = dx * a + dy * a; 00435 t = (a*u - dx)*(a*u - dx) + 00436 (a*u - dy)*(a*u - dy) + 00437 (cz - P[i][2])*(cz - P[i][2]); 00438 u = u - sqrt(std::max(radsqr - t, 0.0)); 00439 if(u > 0) 00440 { 00441 maxx += u*a; 00442 maxy += u*a; 00443 } 00444 } 00445 else if(P[i][1] < miny) 00446 { 00447 dx = P[i][0] - maxx; 00448 dy = P[i][1] - miny; 00449 u = dx * a - dy * a; 00450 t = (a*u - dx)*(a*u - dx) + 00451 (-a*u - dy)*(-a*u - dy) + 00452 (cz - P[i][2])*(cz - P[i][2]); 00453 u = u - sqrt(std::max(radsqr - t, 0.0)); 00454 if(u > 0) 00455 { 00456 maxx += u*a; 00457 miny -= u*a; 00458 } 00459 } 00460 } 00461 else if(P[i][0] < minx) 00462 { 00463 if(P[i][1] > maxy) 00464 { 00465 dx = P[i][0] - minx; 00466 dy = P[i][1] - maxy; 00467 u = dy * a - dx * a; 00468 t = (-a*u - dx)*(-a*u - dx) + 00469 (a*u - dy)*(a*u - dy) + 00470 (cz - P[i][2])*(cz - P[i][2]); 00471 u = u - sqrt(std::max(radsqr - t, 0.0)); 00472 if(u > 0) 00473 { 00474 minx -= u*a; 00475 maxy += u*a; 00476 } 00477 } 00478 else if(P[i][1] < miny) 00479 { 00480 dx = P[i][0] - minx; 00481 dy = P[i][1] - miny; 00482 u = -dx * a - dy * a; 00483 t = (-a*u - dx)*(-a*u - dx) + 00484 (-a*u - dy)*(-a*u - dy) + 00485 (cz - P[i][2])*(cz - P[i][2]); 00486 u = u - sqrt(std::max(radsqr - t, 0.0)); 00487 if (u > 0) 00488 { 00489 minx -= u*a; 00490 miny -= u*a; 00491 } 00492 } 00493 } 00494 } 00495 00496 origin = axis[0] * minx + axis[1] * miny + axis[2] * cz; 00497 00498 l[0] = maxx - minx; 00499 if(l[0] < 0) l[0] = 0; 00500 l[1] = maxy - miny; 00501 if(l[1] < 0) l[1] = 0; 00502 } 00503 00504 00508 void getRadiusAndOriginAndRectangleSize(Vec3f* ps, Vec3f* ps2, Triangle* ts, unsigned int* indices, int n, Vec3f axis[3], Vec3f& origin, BVH_REAL l[2], BVH_REAL& r) 00509 { 00510 bool indirect_index = true; 00511 if(!indices) indirect_index = false; 00512 00513 int size_P = (ps2 == NULL) ? n * 3 : (2 * n * 3); 00514 00515 BVH_REAL (*P)[3] = new BVH_REAL[size_P][3]; 00516 00517 00518 int P_id = 0; 00519 for(int i = 0; i < n; ++i) 00520 { 00521 int index = indirect_index ? indices[i] : i; 00522 const Triangle& t = ts[index]; 00523 00524 for(int j = 0; j < 3; ++j) 00525 { 00526 int point_id = t[j]; 00527 const Vec3f& p = ps[point_id]; 00528 Vec3f v(p[0], p[1], p[2]); 00529 P[P_id][0] = axis[0].dot(v); 00530 P[P_id][1] = axis[1].dot(v); 00531 P[P_id][2] = axis[2].dot(v); 00532 P_id++; 00533 } 00534 00535 if(ps2) 00536 { 00537 for(int j = 0; j < 3; ++j) 00538 { 00539 int point_id = t[j]; 00540 const Vec3f& p = ps2[point_id]; 00541 Vec3f v(p[0], p[1], p[2]); 00542 P[P_id][0] = axis[0].dot(v); 00543 P[P_id][1] = axis[0].dot(v); 00544 P[P_id][2] = axis[1].dot(v); 00545 P_id++; 00546 } 00547 } 00548 } 00549 00550 BVH_REAL minx, maxx, miny, maxy, minz, maxz; 00551 00552 BVH_REAL cz, radsqr; 00553 00554 minz = maxz = P[0][2]; 00555 00556 for(int i = 1; i < size_P; ++i) 00557 { 00558 BVH_REAL z_value = P[i][2]; 00559 if(z_value < minz) minz = z_value; 00560 else if(z_value > maxz) maxz = z_value; 00561 } 00562 00563 r = (BVH_REAL)0.5 * (maxz - minz); 00564 radsqr = r * r; 00565 cz = (BVH_REAL)0.5 * (maxz + minz); 00566 00567 // compute an initial length of rectangle along x direction 00568 00569 // find minx and maxx as starting points 00570 00571 int minindex, maxindex; 00572 minindex = maxindex = 0; 00573 BVH_REAL mintmp, maxtmp; 00574 mintmp = maxtmp = P[0][0]; 00575 00576 for(int i = 1; i < size_P; ++i) 00577 { 00578 BVH_REAL x_value = P[i][0]; 00579 if(x_value < mintmp) 00580 { 00581 minindex = i; 00582 mintmp = x_value; 00583 } 00584 else if(x_value > maxtmp) 00585 { 00586 maxindex = i; 00587 maxtmp = x_value; 00588 } 00589 } 00590 00591 BVH_REAL x, dz; 00592 dz = P[minindex][2] - cz; 00593 minx = P[minindex][0] + sqrt(std::max(radsqr - dz * dz, 0.0)); 00594 dz = P[maxindex][2] - cz; 00595 maxx = P[maxindex][0] - sqrt(std::max(radsqr - dz * dz, 0.0)); 00596 00597 00598 // grow minx 00599 00600 for(int i = 0; i < size_P; ++i) 00601 { 00602 if(P[i][0] < minx) 00603 { 00604 dz = P[i][2] - cz; 00605 x = P[i][0] + sqrt(std::max(radsqr - dz * dz, 0.0)); 00606 if(x < minx) minx = x; 00607 } 00608 } 00609 00610 // grow maxx 00611 00612 for(int i = 0; i < size_P; ++i) 00613 { 00614 if(P[i][0] > maxx) 00615 { 00616 dz = P[i][2] - cz; 00617 x = P[i][0] - sqrt(std::max(radsqr - dz * dz, 0.0)); 00618 if(x > maxx) maxx = x; 00619 } 00620 } 00621 00622 // compute an initial length of rectangle along y direction 00623 00624 // find miny and maxy as starting points 00625 00626 minindex = maxindex = 0; 00627 mintmp = maxtmp = P[0][1]; 00628 for(int i = 1; i < size_P; ++i) 00629 { 00630 BVH_REAL y_value = P[i][1]; 00631 if(y_value < mintmp) 00632 { 00633 minindex = i; 00634 mintmp = y_value; 00635 } 00636 else if(y_value > maxtmp) 00637 { 00638 maxindex = i; 00639 maxtmp = y_value; 00640 } 00641 } 00642 00643 BVH_REAL y; 00644 dz = P[minindex][2] - cz; 00645 miny = P[minindex][1] + sqrt(std::max(radsqr - dz * dz, 0.0)); 00646 dz = P[maxindex][2] - cz; 00647 maxy = P[maxindex][1] - sqrt(std::max(radsqr - dz * dz, 0.0)); 00648 00649 // grow miny 00650 00651 for(int i = 0; i < size_P; ++i) 00652 { 00653 if(P[i][1] < miny) 00654 { 00655 dz = P[i][2] - cz; 00656 y = P[i][1] + sqrt(std::max(radsqr - dz * dz, 0.0)); 00657 if(y < miny) miny = y; 00658 } 00659 } 00660 00661 // grow maxy 00662 00663 for(int i = 0; i < size_P; ++i) 00664 { 00665 if(P[i][1] > maxy) 00666 { 00667 dz = P[i][2] - cz; 00668 y = P[i][1] - sqrt(std::max(radsqr - dz * dz, 0.0)); 00669 if(y > maxy) maxy = y; 00670 } 00671 } 00672 00673 // corners may have some points which are not covered - grow lengths if necessary 00674 // quite conservative (can be improved) 00675 BVH_REAL dx, dy, u, t; 00676 BVH_REAL a = sqrt((BVH_REAL)0.5); 00677 for(int i = 0; i < size_P; ++i) 00678 { 00679 if(P[i][0] > maxx) 00680 { 00681 if(P[i][1] > maxy) 00682 { 00683 dx = P[i][0] - maxx; 00684 dy = P[i][1] - maxy; 00685 u = dx * a + dy * a; 00686 t = (a*u - dx)*(a*u - dx) + 00687 (a*u - dy)*(a*u - dy) + 00688 (cz - P[i][2])*(cz - P[i][2]); 00689 u = u - sqrt(std::max(radsqr - t, 0.0)); 00690 if(u > 0) 00691 { 00692 maxx += u*a; 00693 maxy += u*a; 00694 } 00695 } 00696 else if(P[i][1] < miny) 00697 { 00698 dx = P[i][0] - maxx; 00699 dy = P[i][1] - miny; 00700 u = dx * a - dy * a; 00701 t = (a*u - dx)*(a*u - dx) + 00702 (-a*u - dy)*(-a*u - dy) + 00703 (cz - P[i][2])*(cz - P[i][2]); 00704 u = u - sqrt(std::max(radsqr - t, 0.0)); 00705 if(u > 0) 00706 { 00707 maxx += u*a; 00708 miny -= u*a; 00709 } 00710 } 00711 } 00712 else if(P[i][0] < minx) 00713 { 00714 if(P[i][1] > maxy) 00715 { 00716 dx = P[i][0] - minx; 00717 dy = P[i][1] - maxy; 00718 u = dy * a - dx * a; 00719 t = (-a*u - dx)*(-a*u - dx) + 00720 (a*u - dy)*(a*u - dy) + 00721 (cz - P[i][2])*(cz - P[i][2]); 00722 u = u - sqrt(std::max(radsqr - t, 0.0)); 00723 if(u > 0) 00724 { 00725 minx -= u*a; 00726 maxy += u*a; 00727 } 00728 } 00729 else if(P[i][1] < miny) 00730 { 00731 dx = P[i][0] - minx; 00732 dy = P[i][1] - miny; 00733 u = -dx * a - dy * a; 00734 t = (-a*u - dx)*(-a*u - dx) + 00735 (-a*u - dy)*(-a*u - dy) + 00736 (cz - P[i][2])*(cz - P[i][2]); 00737 u = u - sqrt(std::max(radsqr - t, 0.0)); 00738 if (u > 0) 00739 { 00740 minx -= u*a; 00741 miny -= u*a; 00742 } 00743 } 00744 } 00745 } 00746 00747 origin = axis[0] * minx + axis[1] * miny + axis[2] * cz; 00748 00749 l[0] = maxx - minx; 00750 if(l[0] < 0) l[0] = 0; 00751 l[1] = maxy - miny; 00752 if(l[1] < 0) l[1] = 0; 00753 } 00754 00758 void getExtentAndCenter(Vec3f* ps, Vec3f* ps2, unsigned int* indices, int n, Vec3f axis[3], Vec3f& center, Vec3f& extent) 00759 { 00760 bool indirect_index = true; 00761 if(!indices) indirect_index = false; 00762 00763 BVH_REAL real_max = std::numeric_limits<BVH_REAL>::max(); 00764 00765 BVH_REAL min_coord[3] = {real_max, real_max, real_max}; 00766 BVH_REAL max_coord[3] = {-real_max, -real_max, -real_max}; 00767 00768 for(int i = 0; i < n; ++i) 00769 { 00770 int index = indirect_index ? indices[i] : i; 00771 00772 const Vec3f& p = ps[index]; 00773 Vec3f v(p[0], p[1], p[2]); 00774 BVH_REAL proj[3]; 00775 proj[0] = axis[0].dot(v); 00776 proj[1] = axis[1].dot(v); 00777 proj[2] = axis[2].dot(v); 00778 00779 for(int j = 0; j < 3; ++j) 00780 { 00781 if(proj[j] > max_coord[j]) max_coord[j] = proj[j]; 00782 if(proj[j] < min_coord[j]) min_coord[j] = proj[j]; 00783 } 00784 00785 if(ps2) 00786 { 00787 const Vec3f& v = ps2[index]; 00788 proj[0] = axis[0].dot(v); 00789 proj[1] = axis[1].dot(v); 00790 proj[2] = axis[2].dot(v); 00791 00792 for(int j = 0; j < 3; ++j) 00793 { 00794 if(proj[j] > max_coord[j]) max_coord[j] = proj[j]; 00795 if(proj[j] < min_coord[j]) min_coord[j] = proj[j]; 00796 } 00797 } 00798 } 00799 00800 Vec3f o = Vec3f((max_coord[0] + min_coord[0]) / 2, 00801 (max_coord[1] + min_coord[1]) / 2, 00802 (max_coord[2] + min_coord[2]) / 2); 00803 00804 center = axis[0] * o[0] + axis[1] * o[1] + axis[2] * o[2]; 00805 00806 extent = Vec3f((max_coord[0] - min_coord[0]) / 2, 00807 (max_coord[1] - min_coord[1]) / 2, 00808 (max_coord[2] - min_coord[2]) / 2); 00809 00810 } 00811 00812 00816 void getExtentAndCenter(Vec3f* ps, Vec3f* ps2, Triangle* ts, unsigned int* indices, int n, Vec3f axis[3], Vec3f& center, Vec3f& extent) 00817 { 00818 bool indirect_index = true; 00819 if(!indices) indirect_index = false; 00820 00821 BVH_REAL real_max = std::numeric_limits<BVH_REAL>::max(); 00822 00823 BVH_REAL min_coord[3] = {real_max, real_max, real_max}; 00824 BVH_REAL max_coord[3] = {-real_max, -real_max, -real_max}; 00825 00826 for(int i = 0; i < n; ++i) 00827 { 00828 unsigned int index = indirect_index? indices[i] : i; 00829 const Triangle& t = ts[index]; 00830 00831 for(int j = 0; j < 3; ++j) 00832 { 00833 int point_id = t[j]; 00834 const Vec3f& p = ps[point_id]; 00835 Vec3f v(p[0], p[1], p[2]); 00836 BVH_REAL proj[3]; 00837 proj[0] = axis[0].dot(v); 00838 proj[1] = axis[1].dot(v); 00839 proj[2] = axis[2].dot(v); 00840 00841 for(int k = 0; k < 3; ++k) 00842 { 00843 if(proj[k] > max_coord[k]) max_coord[k] = proj[k]; 00844 if(proj[k] < min_coord[k]) min_coord[k] = proj[k]; 00845 } 00846 } 00847 00848 if(ps2) 00849 { 00850 for(int j = 0; j < 3; ++j) 00851 { 00852 int point_id = t[j]; 00853 const Vec3f& p = ps2[point_id]; 00854 Vec3f v(p[0], p[1], p[2]); 00855 BVH_REAL proj[3]; 00856 proj[0] = axis[0].dot(v); 00857 proj[1] = axis[1].dot(v); 00858 proj[2] = axis[2].dot(v); 00859 00860 for(int k = 0; k < 3; ++k) 00861 { 00862 if(proj[k] > max_coord[k]) max_coord[k] = proj[k]; 00863 if(proj[k] < min_coord[k]) min_coord[k] = proj[k]; 00864 } 00865 } 00866 } 00867 } 00868 00869 Vec3f o = Vec3f((max_coord[0] + min_coord[0]) / 2, 00870 (max_coord[1] + min_coord[1]) / 2, 00871 (max_coord[2] + min_coord[2]) / 2); 00872 00873 center = axis[0] * o[0] + axis[1] * o[1] + axis[2] * o[2]; 00874 00875 extent = Vec3f((max_coord[0] - min_coord[0]) / 2, 00876 (max_coord[1] - min_coord[1]) / 2, 00877 (max_coord[2] - min_coord[2]) / 2); 00878 00879 } 00880 00881 00882 00883 00884 00885 00886 OBB BVFitter<OBB>::fit(Vec3f* ps, int n) 00887 { 00888 switch(n) 00889 { 00890 case 1: 00891 return fit1(ps); 00892 break; 00893 case 2: 00894 return fit2(ps); 00895 break; 00896 case 3: 00897 return fit3(ps); 00898 break; 00899 case 6: 00900 return fit6(ps); 00901 break; 00902 default: 00903 return fitn(ps, n); 00904 } 00905 } 00906 00907 00908 OBB BVFitter<OBB>::fit(unsigned int* primitive_indices, int num_primitives) 00909 { 00910 OBB bv; 00911 00912 Vec3f M[3]; // row first matrix 00913 Vec3f E[3]; // row first eigen-vectors 00914 BVH_REAL s[3]; // three eigen values 00915 00916 if(type == BVH_MODEL_TRIANGLES) 00917 { 00918 getCovariance(vertices, prev_vertices, tri_indices, primitive_indices, num_primitives, M); 00919 Meigen(M, s, E); 00920 } 00921 else if(type == BVH_MODEL_POINTCLOUD) 00922 { 00923 getCovariance(vertices, prev_vertices, primitive_indices, num_primitives, M); 00924 Meigen(M, s, E); 00925 } 00926 00927 int min, mid, max; 00928 if(s[0] > s[1]) { max = 0; min = 1; } 00929 else { min = 0; max = 1; } 00930 if(s[2] < s[min]) { mid = min; min = 2; } 00931 else if(s[2] > s[max]) { mid = max; max = 2; } 00932 else { mid = 2; } 00933 00934 Vec3f R[3]; // column first matrix, as the axis in OBB 00935 R[0] = Vec3f(E[0][max], E[1][max], E[2][max]); 00936 R[1] = Vec3f(E[0][mid], E[1][mid], E[2][mid]); 00937 R[2] = Vec3f(E[1][max]*E[2][mid] - E[1][mid]*E[2][max], 00938 E[0][mid]*E[2][max] - E[0][max]*E[2][mid], 00939 E[0][max]*E[1][mid] - E[0][mid]*E[1][max]); 00940 00941 00942 // set obb axes 00943 bv.axis[0] = R[0]; 00944 bv.axis[1] = R[1]; 00945 bv.axis[2] = R[2]; 00946 00947 // set obb centers and extensions 00948 Vec3f center, extent; 00949 if(type == BVH_MODEL_TRIANGLES) 00950 { 00951 getExtentAndCenter(vertices, prev_vertices, tri_indices, primitive_indices, num_primitives, R, center, extent); 00952 } 00953 else if(type == BVH_MODEL_POINTCLOUD) 00954 { 00955 getExtentAndCenter(vertices, prev_vertices, primitive_indices, num_primitives, R, center, extent); 00956 } 00957 00958 bv.To = center; 00959 bv.extent = extent; 00960 00961 return bv; 00962 } 00963 00964 00965 00966 OBB BVFitter<OBB>::fit1(Vec3f* ps) 00967 { 00968 OBB bv; 00969 bv.To = ps[0]; 00970 bv.axis[0] = Vec3f(1, 0, 0); 00971 bv.axis[1] = Vec3f(0, 1, 0); 00972 bv.axis[2] = Vec3f(0, 0, 1); 00973 bv.extent = Vec3f(0, 0, 0); 00974 return bv; 00975 } 00976 00977 OBB BVFitter<OBB>::fit2(Vec3f* ps) 00978 { 00979 OBB bv; 00980 Vec3f p1(ps[0][0], ps[0][1], ps[0][2]); 00981 Vec3f p2(ps[1][0], ps[1][1], ps[1][2]); 00982 Vec3f p1p2 = p1 - p2; 00983 float len_p1p2 = p1p2.length(); 00984 Vec3f w = p1p2; 00985 w.normalize(); 00986 00987 // then generate other two axes orthonormal to w 00988 Vec3f u, v; 00989 float inv_length; 00990 if(fabs(w[0]) >= fabs(w[1])) 00991 { 00992 inv_length = 1.0 / sqrt(w[0] * w[0] + w[2] * w[2]); 00993 u[0] = -w[2] * inv_length; 00994 u[1] = 0; 00995 u[2] = w[0] * inv_length; 00996 v[0] = w[1] * u[2]; 00997 v[1] = w[2] * u[0] - w[0] * u[2]; 00998 v[2] = -w[1] * u[0]; 00999 } 01000 else 01001 { 01002 inv_length = 1.0 / sqrt(w[1] * w[1] + w[2] * w[2]); 01003 u[0] = 0; 01004 u[1] = w[2] * inv_length; 01005 u[2] = -w[1] * inv_length; 01006 v[0] = w[1] * u[2] - w[2] * u[1]; 01007 v[1] = -w[0] * u[2]; 01008 v[2] = w[0] * u[1]; 01009 } 01010 01011 bv.axis[0] = w; 01012 bv.axis[1] = u; 01013 bv.axis[2] = v; 01014 01015 bv.extent = Vec3f(len_p1p2 * 0.5, 0, 0); 01016 bv.To = Vec3f(0.5 * (p1[0] + p2[0]), 01017 0.5 * (p1[1] + p2[1]), 01018 0.5 * (p1[2] + p2[2])); 01019 01020 return bv; 01021 } 01022 01023 OBB BVFitter<OBB>::fit3(Vec3f* ps) 01024 { 01025 OBB bv; 01026 Vec3f p1(ps[0][0], ps[0][1], ps[0][2]); 01027 Vec3f p2(ps[1][0], ps[1][1], ps[1][2]); 01028 Vec3f p3(ps[2][0], ps[2][1], ps[2][2]); 01029 Vec3f e[3]; 01030 e[0] = p1 - p2; 01031 e[1] = p2 - p3; 01032 e[2] = p3 - p1; 01033 float len[3]; 01034 len[0] = e[0].sqrLength(); 01035 len[1] = e[1].sqrLength(); 01036 len[2] = e[2].sqrLength(); 01037 01038 int imax = 0; 01039 if(len[1] > len[0]) imax = 1; 01040 if(len[2] > len[imax]) imax = 2; 01041 01042 Vec3f w = e[0].cross(e[1]); 01043 w.normalize(); 01044 Vec3f u = e[imax]; 01045 u.normalize(); 01046 Vec3f v = w.cross(u); 01047 bv.axis[0] = u; 01048 bv.axis[1] = v; 01049 bv.axis[2] = w; 01050 01051 getExtentAndCenter(ps, NULL, NULL, 3, bv.axis, bv.To, bv.extent); 01052 01053 return bv; 01054 } 01055 01056 OBB BVFitter<OBB>::fit6(Vec3f* ps) 01057 { 01058 OBB bv1, bv2; 01059 bv1 = fit3(ps); 01060 bv2 = fit3(ps + 3); 01061 return (bv1 + bv2); 01062 } 01063 01064 01065 OBB BVFitter<OBB>::fitn(Vec3f* ps, int n) 01066 { 01067 OBB bv; 01068 01069 Vec3f M[3]; // row first matrix 01070 Vec3f E[3]; // row first eigen-vectors 01071 BVH_REAL s[3] = {0, 0, 0}; // three eigen values 01072 01073 getCovariance(ps, NULL, NULL, n, M); 01074 Meigen(M, s, E); 01075 01076 int min, mid, max; 01077 if(s[0] > s[1]) { max = 0; min = 1; } 01078 else { min = 0; max = 1; } 01079 if(s[2] < s[min]) { mid = min; min = 2; } 01080 else if(s[2] > s[max]) { mid = max; max = 2; } 01081 else { mid = 2; } 01082 01083 Vec3f R[3]; // column first matrix, as the axis in OBB 01084 R[0] = Vec3f(E[0][max], E[1][max], E[2][max]); 01085 R[1] = Vec3f(E[0][mid], E[1][mid], E[2][mid]); 01086 R[2] = Vec3f(E[1][max]*E[2][mid] - E[1][mid]*E[2][max], 01087 E[0][mid]*E[2][max] - E[0][max]*E[2][mid], 01088 E[0][max]*E[1][mid] - E[0][mid]*E[1][max]); 01089 01090 01091 // set obb axes 01092 bv.axis[0] = R[0]; 01093 bv.axis[1] = R[1]; 01094 bv.axis[2] = R[2]; 01095 01096 // set obb centers and extensions 01097 Vec3f center, extent; 01098 getExtentAndCenter(ps, NULL, NULL, n, R, center, extent); 01099 01100 bv.To = center; 01101 bv.extent = extent; 01102 01103 return bv; 01104 } 01105 01106 RSS BVFitter<RSS>::fit(Vec3f* ps, int n) 01107 { 01108 switch(n) 01109 { 01110 case 1: 01111 return fit1(ps); 01112 break; 01113 case 2: 01114 return fit2(ps); 01115 break; 01116 case 3: 01117 return fit3(ps); 01118 break; 01119 default: 01120 return fit(ps, n); 01121 } 01122 } 01123 01124 01125 RSS BVFitter<RSS>::fit(unsigned int* primitive_indices, int num_primitives) 01126 { 01127 RSS bv; 01128 01129 Vec3f M[3]; // row first matrix 01130 Vec3f E[3]; // row first eigen-vectors 01131 BVH_REAL s[3]; // three eigen values 01132 01133 if(type == BVH_MODEL_TRIANGLES) 01134 { 01135 getCovariance(vertices, prev_vertices, tri_indices, primitive_indices, num_primitives, M); 01136 Meigen(M, s, E); 01137 } 01138 else if(type == BVH_MODEL_POINTCLOUD) 01139 { 01140 getCovariance(vertices, prev_vertices, primitive_indices, num_primitives, M); 01141 Meigen(M, s, E); 01142 } 01143 01144 int min, mid, max; 01145 if(s[0] > s[1]) { max = 0; min = 1; } 01146 else { min = 0; max = 1; } 01147 if(s[2] < s[min]) { mid = min; min = 2; } 01148 else if(s[2] > s[max]) { mid = max; max = 2; } 01149 else { mid = 2; } 01150 01151 Vec3f R[3]; // column first matrix, as the axis in OBB 01152 R[0] = Vec3f(E[0][max], E[1][max], E[2][max]); 01153 R[1] = Vec3f(E[0][mid], E[1][mid], E[2][mid]); 01154 R[2] = Vec3f(E[1][max]*E[2][mid] - E[1][mid]*E[2][max], 01155 E[0][mid]*E[2][max] - E[0][max]*E[2][mid], 01156 E[0][max]*E[1][mid] - E[0][mid]*E[1][max]); 01157 01158 // set rss axes 01159 bv.axis[0] = R[0]; 01160 bv.axis[1] = R[1]; 01161 bv.axis[2] = R[2]; 01162 01163 // set rss origin, rectangle size and radius 01164 01165 Vec3f origin; 01166 BVH_REAL l[2]; 01167 BVH_REAL r; 01168 01169 if(type == BVH_MODEL_TRIANGLES) 01170 { 01171 getRadiusAndOriginAndRectangleSize(vertices, prev_vertices, tri_indices, primitive_indices, num_primitives, R, origin, l, r); 01172 } 01173 else if(type == BVH_MODEL_POINTCLOUD) 01174 { 01175 getRadiusAndOriginAndRectangleSize(vertices, prev_vertices, primitive_indices, num_primitives, R, origin, l, r); 01176 } 01177 01178 bv.Tr = origin; 01179 bv.l[0] = l[0]; 01180 bv.l[1] = l[1]; 01181 bv.r = r; 01182 01183 01184 return bv; 01185 } 01186 01187 RSS BVFitter<RSS>::fit1(Vec3f* ps) 01188 { 01189 RSS bv; 01190 bv.Tr = ps[0]; 01191 bv.axis[0] = Vec3f(1, 0, 0); 01192 bv.axis[1] = Vec3f(0, 1, 0); 01193 bv.axis[2] = Vec3f(0, 0, 1); 01194 bv.l[0] = 0; 01195 bv.l[1] = 0; 01196 bv.r = 0; 01197 01198 return bv; 01199 } 01200 01201 RSS BVFitter<RSS>::fit2(Vec3f* ps) 01202 { 01203 RSS bv; 01204 01205 Vec3f p1(ps[0][0], ps[0][1], ps[0][2]); 01206 Vec3f p2(ps[1][0], ps[1][1], ps[1][2]); 01207 Vec3f p1p2 = p1 - p2; 01208 float len_p1p2 = p1p2.length(); 01209 Vec3f w = p1p2; 01210 w.normalize(); 01211 01212 // then generate other two axes orthonormal to w 01213 Vec3f u, v; 01214 float inv_length; 01215 if(fabs(w[0]) >= fabs(w[1])) 01216 { 01217 inv_length = 1.0 / sqrt(w[0] * w[0] + w[2] * w[2]); 01218 u[0] = -w[2] * inv_length; 01219 u[1] = 0; 01220 u[2] = w[0] * inv_length; 01221 v[0] = w[1] * u[2]; 01222 v[1] = w[2] * u[0] - w[0] * u[2]; 01223 v[2] = -w[1] * u[0]; 01224 } 01225 else 01226 { 01227 inv_length = 1.0 / sqrt(w[1] * w[1] + w[2] * w[2]); 01228 u[0] = 0; 01229 u[1] = w[2] * inv_length; 01230 u[2] = -w[1] * inv_length; 01231 v[0] = w[1] * u[2] - w[2] * u[1]; 01232 v[1] = -w[0] * u[2]; 01233 v[2] = w[0] * u[1]; 01234 } 01235 01236 bv.axis[0] = w; 01237 bv.axis[1] = u; 01238 bv.axis[2] = v; 01239 01240 bv.l[0] = len_p1p2; 01241 bv.l[1] = 0; 01242 01243 bv.Tr = p2; 01244 01245 return bv; 01246 } 01247 01248 RSS BVFitter<RSS>::fit3(Vec3f* ps) 01249 { 01250 RSS bv; 01251 01252 Vec3f p1(ps[0][0], ps[0][1], ps[0][2]); 01253 Vec3f p2(ps[1][0], ps[1][1], ps[1][2]); 01254 Vec3f p3(ps[2][0], ps[2][1], ps[2][2]); 01255 Vec3f e[3]; 01256 e[0] = p1 - p2; 01257 e[1] = p2 - p3; 01258 e[2] = p3 - p1; 01259 float len[3]; 01260 len[0] = e[0].sqrLength(); 01261 len[1] = e[1].sqrLength(); 01262 len[2] = e[2].sqrLength(); 01263 01264 int imax = 0; 01265 if(len[1] > len[0]) imax = 1; 01266 if(len[2] > len[imax]) imax = 2; 01267 01268 Vec3f w = e[0].cross(e[1]); 01269 w.normalize(); 01270 Vec3f u = e[imax]; 01271 u.normalize(); 01272 Vec3f v = w.cross(u); 01273 bv.axis[0] = u; 01274 bv.axis[1] = v; 01275 bv.axis[2] = w; 01276 01277 getRadiusAndOriginAndRectangleSize(ps, NULL, NULL, 3, bv.axis, bv.Tr, bv.l, bv.r); 01278 01279 return bv; 01280 } 01281 01282 RSS BVFitter<RSS>::fitn(Vec3f* ps, int n) 01283 { 01284 RSS bv; 01285 01286 Vec3f M[3]; // row first matrix 01287 Vec3f E[3]; // row first eigen-vectors 01288 BVH_REAL s[3] = {0, 0, 0}; 01289 01290 getCovariance(ps, NULL, NULL, n, M); 01291 Meigen(M, s, E); 01292 01293 int min, mid, max; 01294 if(s[0] > s[1]) { max = 0; min = 1; } 01295 else { min = 0; max = 1; } 01296 if(s[2] < s[min]) { mid = min; min = 2; } 01297 else if(s[2] > s[max]) { mid = max; max = 2; } 01298 else { mid = 2; } 01299 01300 Vec3f R[3]; // column first matrix, as the axis in RSS 01301 R[0] = Vec3f(E[0][max], E[1][max], E[2][max]); 01302 R[1] = Vec3f(E[0][mid], E[1][mid], E[2][mid]); 01303 R[2] = Vec3f(E[1][max]*E[2][mid] - E[1][mid]*E[2][max], 01304 E[0][mid]*E[2][max] - E[0][max]*E[2][mid], 01305 E[0][max]*E[1][mid] - E[0][mid]*E[1][max]); 01306 01307 // set obb axes 01308 bv.axis[0] = R[0]; 01309 bv.axis[1] = R[1]; 01310 bv.axis[2] = R[2]; 01311 01312 // set rss origin, rectangle size and radius 01313 getRadiusAndOriginAndRectangleSize(ps, NULL, NULL, n, R, bv.Tr, bv.l, bv.r); 01314 01315 return bv; 01316 } 01317 01318 01319 }