00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00015
00016
00017 #include "pcl/surface/3rdparty/opennurbs/opennurbs.h"
00018
00019
00020 bool ON_IntersectLineLine(
00021 const ON_Line& lineA,
00022 const ON_Line& lineB,
00023 double* a,
00024 double* b,
00025 double tolerance,
00026 bool bIntersectSegments
00027 )
00028 {
00029 bool rc = ON_Intersect(lineA,lineB,a,b) ? true : false;
00030 if (rc)
00031 {
00032 if ( bIntersectSegments )
00033 {
00034 if ( *a < 0.0 )
00035 *a = 0.0;
00036 else if ( *a > 1.0 )
00037 *a = 1.0;
00038 if ( *b < 0.0 )
00039 *b = 0.0;
00040 else if ( *b > 1.0 )
00041 *b = 1.0;
00042 }
00043 if ( tolerance > 0.0 )
00044 {
00045 rc = (lineA.PointAt(*a).DistanceTo(lineB.PointAt(*b)) <= tolerance);
00046 }
00047 }
00048 return rc;
00049 }
00050
00051
00052 bool ON_Intersect( const ON_BoundingBox& bbox,
00053 const ON_Line& line,
00054 double tol,
00055 ON_Interval* line_parameters)
00056 {
00057 double a,b,d,mn,mx,s0,s1, t0, t1;
00058 const double M = 1.0e308;
00059
00060
00061
00062 ON_3dVector v = line.Direction();
00063 const int i = v.MaximumCoordinateIndex();
00064
00065
00066 if ( !(tol >= 0.0) )
00067 tol = 0.0;
00068
00069
00070 a = line.from[i];
00071 b = line.to[i];
00072 mn = bbox.m_min[i];
00073 mx = bbox.m_max[i];
00074 if ( !(mn <= mx) )
00075 return false;
00076 mn -= (tol+a);
00077 mx += (tol-a);
00078 if ( !(mn <= mx) )
00079 return false;
00080 d = b-a;
00081 if ( 0.0 == d )
00082 {
00083
00084 if ( 0.0 < mn || 0.0 > mx )
00085 {
00086
00087 if ( line_parameters )
00088 {
00089
00090
00091 line_parameters->Set(0.0,0.0);
00092 }
00093 return true;
00094 }
00095 return false;
00096 }
00097 if ( fabs(d) < 1.0 && (fabs(mn) >= fabs(d)*M || fabs(mx) >= fabs(d)*M) )
00098 {
00099
00100 return false;
00101 }
00102 d = 1.0/d;
00103 t0 = mn*d;
00104 t1 = mx*d;
00105
00106
00107
00108 ON_Line chord(line.PointAt(t0),line.PointAt(t1));
00109
00110
00111 const int j = (i + (fabs(v[(i+1)%3])>fabs(v[(i+2)%3])?1:2) ) % 3;
00112 a = chord.from[j];
00113 b = chord.to[j];
00114 mn = bbox.m_min[j];
00115 mx = bbox.m_max[j];
00116 if ( !(mn <= mx) )
00117 return false;
00118 mn -= (tol+a);
00119 mx += (tol-a);
00120 if ( !(mn <= mx) )
00121 return false;
00122 d = b-a;
00123 if ( (0.0 < mn && d < mn) || (0.0 > mx && d > mx) )
00124 {
00125
00126 return false;
00127 }
00128
00129 while ( fabs(d) >= 1.0 || (fabs(mn) <= fabs(d)*M && fabs(mx) <= fabs(d)*M) )
00130 {
00131
00132
00133 d = 1.0/d;
00134 s0 = mn*d;
00135 s1 = mx*d;
00136 if ( s0 > 1.0 )
00137 {
00138 if ( s1 > 1.0 )
00139 {
00140
00141
00142
00143 break;
00144 }
00145 s0 = 1.0;
00146 }
00147 else if ( s0 < 0.0 )
00148 {
00149 if (s1 < 0.0)
00150 {
00151
00152
00153
00154 break;
00155 }
00156 s0 = 0.0;
00157 }
00158 if ( s1 < 0.0 ) s1 = 0.0; else if ( s1 > 1.0 ) s1 = 1.0;
00159 d = (1.0-s0)*t0 + s0*t1;
00160 t1 = (1.0-s1)*t0 + s1*t1;
00161 t0 = d;
00162 v = chord.PointAt(s0);
00163 chord.to = chord.PointAt(s1);
00164 chord.from = v;
00165 break;
00166 }
00167
00168
00169 const int k = (i&&j) ? 0 : ((i!=1&&j!=1)?1:2);
00170 a = chord.from[k];
00171 b = chord.to[k];
00172 mn = bbox.m_min[k];
00173 mx = bbox.m_max[k];
00174 if ( !(mn <= mx) )
00175 return false;
00176 mn -= (tol+a);
00177 mx += (tol-a);
00178 if ( !(mn <= mx) )
00179 return false;
00180 d = b-a;
00181 if ( (0.0 < mn && d < mn) || (0.0 > mx && d > mx) )
00182 {
00183
00184 return false;
00185 }
00186
00187 if ( line_parameters )
00188 {
00189
00190 while ( fabs(d) >= 1.0 || (fabs(mn) <= fabs(d)*M && fabs(mx) <= fabs(d)*M) )
00191 {
00192
00193
00194 d = 1.0/d;
00195 s0 = mn*d;
00196 s1 = mx*d;
00197 if ( s0 > 1.0 )
00198 {
00199 if ( s1 > 1.0 )
00200 {
00201
00202
00203
00204 break;
00205 }
00206 s0 = 1.0;
00207 }
00208 else if ( s0 < 0.0 )
00209 {
00210 if (s1 < 0.0)
00211 {
00212
00213
00214
00215 break;
00216 }
00217 s0 = 0.0;
00218 }
00219
00220 if ( s1 < 0.0 ) s1 = 0.0; else if ( s1 > 1.0 ) s1 = 1.0;
00221 d = (1.0-s0)*t0 + s0*t1;
00222 t1 = (1.0-s1)*t0 + s1*t1;
00223 t0 = d;
00224 break;
00225 }
00226
00227 if (t0 > t1 )
00228 {
00229 line_parameters->Set(t1,t0);
00230 }
00231 else
00232 {
00233 line_parameters->Set(t0,t1);
00234 }
00235 }
00236
00237 return true;
00238 }
00239
00240
00241
00242 bool ON_Intersect( const ON_Line& lineA, const ON_Line& lineB,
00243 double* lineA_parameter,
00244 double* lineB_parameter
00245 )
00246 {
00247
00248
00249
00250
00251 bool rc = false;
00252 double M_zero_tol = 0.0;
00253 int i, rank;
00254 double pr_tolerance, pivot, X[2], Y[2];
00255
00256 ON_3dVector A = lineA.Direction();
00257 ON_3dVector B = lineB.Direction();
00258 ON_3dVector C = lineB[0] - lineA[0];
00259
00260 ON_Matrix M(2,2);
00261 M[0][0] = ON_DotProduct( A, A );
00262 M[1][1] = ON_DotProduct( B, B );
00263 M[0][1] = M[1][0] = -ON_DotProduct( A, B );
00264
00265
00266 if ( M[0][0] < M[1][1] ) {
00267 M.SwapCols(0,1);
00268 i = 1;
00269 }
00270 else {
00271 i = 0;
00272 }
00273 pr_tolerance = fabs(M[1][1])*ON_SQRT_EPSILON;
00274 M_zero_tol = fabs(M[1][1])*ON_EPSILON;
00275
00276 Y[0] = ON_DotProduct( A, C );
00277 Y[1] = -ON_DotProduct( B, C );
00278
00279 rank = M.RowReduce( M_zero_tol, Y, &pivot );
00280 if ( rank == 2 )
00281 {
00282
00283
00284
00285
00286 rc = true;
00287 if ( lineA.from == lineB.from )
00288 {
00289 if ( lineA_parameter )
00290 *lineA_parameter = 0.0;
00291 if ( lineB_parameter )
00292 *lineB_parameter = 0.0;
00293 }
00294 else if ( lineA.from == lineB.to )
00295 {
00296 if ( lineA_parameter )
00297 *lineA_parameter = 0.0;
00298 if ( lineB_parameter )
00299 *lineB_parameter = 1.0;
00300 }
00301 else if ( lineA.to == lineB.from )
00302 {
00303 if ( lineA_parameter )
00304 *lineA_parameter = 1.0;
00305 if ( lineB_parameter )
00306 *lineB_parameter = 0.0;
00307 }
00308 else if ( lineA.to == lineB.to )
00309 {
00310 if ( lineA_parameter )
00311 *lineA_parameter = 1.0;
00312 if ( lineB_parameter )
00313 *lineB_parameter = 1.0;
00314 }
00315 else
00316 {
00317 rc = M.BackSolve( 0.0, 2, Y, X );
00318 if ( rc )
00319 {
00320 if ( lineA_parameter )
00321 *lineA_parameter = X[i];
00322 if ( lineB_parameter )
00323 *lineB_parameter = X[1-i];
00324 if ( fabs(pivot) <= pr_tolerance )
00325 {
00326
00327
00328 ON_3dPoint pA = lineA.PointAt(X[i]);
00329 ON_3dPoint pB = lineB.PointAt(X[1-i]);
00330 double d = pA.DistanceTo(pB);
00331 if ( d > pr_tolerance && d > ON_ZERO_TOLERANCE ) {
00332 ON_3dPoint qA = lineA.ClosestPointTo(pB);
00333 ON_3dPoint qB = lineB.ClosestPointTo(pA);
00334 double dA = pA.DistanceTo(qB);
00335 double dB = pB.DistanceTo(qA);
00336 if ( 1.1*dA < d ) {
00337 rc = false;
00338 }
00339 else if ( 1.1*dB < d ) {
00340 rc = false;
00341 }
00342 }
00343 }
00344 }
00345 }
00346 }
00347
00348 return rc;
00349 }
00350
00351
00352 bool ON_Intersect( const ON_Line& line, const ON_Plane& plane,
00353 double* line_parameter
00354 )
00355 {
00356 bool rc = false;
00357 double a, b, d, fd, t;
00358
00359 a = plane.plane_equation.ValueAt(line[0]);
00360 b = plane.plane_equation.ValueAt(line[1]);
00361 d = a-b;
00362 if ( d == 0.0 ) {
00363 if ( fabs(a) < fabs(b) ) {
00364 t = 0.0;
00365 }
00366 else if ( fabs(b) < fabs(a) ) {
00367 t = 1.0;
00368 }
00369 else {
00370 t = 0.5;
00371 }
00372 }
00373 else {
00374 d = 1.0/d;
00375 fd = fabs(d);
00376 if ( fd > 1.0 && (fabs(a) >= ON_DBL_MAX/fd || fabs(b) >= ON_DBL_MAX/fd ) ) {
00377
00378 t = 0.5;
00379 }
00380 else {
00381 t = a*d;
00382 rc = true;
00383 }
00384 }
00385 if ( line_parameter )
00386 *line_parameter = t;
00387 return rc;
00388 }
00389
00390
00391 bool ON_Intersect( const ON_Plane& R, const ON_Plane& S,
00392 ON_Line& L )
00393 {
00394 ON_3dVector d = ON_CrossProduct( S.zaxis, R.zaxis );
00395 ON_3dPoint p = 0.5*(R.origin + S.origin);
00396 ON_Plane T( p, d );
00397 bool rc = ON_Intersect( R, S, T, L.from );
00398 L.to = L.from + d;
00399 return rc;
00400 }
00401
00402
00403 bool ON_Intersect( const ON_Plane& R, const ON_Plane& S, const ON_Plane& T,
00404 ON_3dPoint& P )
00405 {
00406 double pr = 0.0;
00407 const int rank = ON_Solve3x3(
00408 &R.plane_equation.x, &S.plane_equation.x, &T.plane_equation.x,
00409 -R.plane_equation.d, -S.plane_equation.d, -T.plane_equation.d,
00410 &P.x, &P.y, &P.z, &pr );
00411 return (rank == 3) ? true : false;
00412 }
00413
00414
00415 int ON_Intersect(
00416 const ON_Plane& plane,
00417 const ON_Sphere& sphere,
00418 ON_Circle& circle
00419 )
00420 {
00421
00422
00423
00424 int rc = 0;
00425 const double sphere_radius = fabs(sphere.radius);
00426 double tol = sphere_radius*ON_SQRT_EPSILON;
00427 if ( !(tol >= ON_ZERO_TOLERANCE) )
00428 tol = ON_ZERO_TOLERANCE;
00429 const ON_3dPoint sphere_center = sphere.Center();
00430 ON_3dPoint circle_center = plane.ClosestPointTo(sphere_center);
00431 double d = circle_center.DistanceTo(sphere_center);
00432
00433 circle.radius = 0.0;
00434
00435 if ( ON_IsValid(sphere_radius) && ON_IsValid(d) && d <= sphere_radius + tol )
00436 {
00437 if ( sphere_radius > 0.0 )
00438 {
00439 d /= sphere_radius;
00440 d = 1.0 - d*d;
00441
00442
00443
00444 circle.radius = (d > 4.0*ON_EPSILON) ? sphere_radius*sqrt(d) : 0.0;
00445 }
00446 else
00447 circle.radius = 0.0;
00448
00449 if ( circle.radius <= ON_ZERO_TOLERANCE )
00450 {
00451
00452 rc = 1;
00453
00454 circle.radius = 0.0;
00455
00456
00457
00458
00459 ON_3dVector R = circle_center - sphere_center;
00460 double r0 = R.Length();
00461 if ( r0 > 0.0 )
00462 {
00463 R.Unitize();
00464 ON_3dPoint C1 = sphere_center + sphere_radius*R;
00465 double r1 = C1.DistanceTo(sphere_center);
00466 if ( fabs(sphere.radius-r1) < fabs(sphere.radius-r0) )
00467 circle_center = C1;
00468 }
00469 }
00470 else
00471 {
00472
00473 rc = 2;
00474 }
00475 }
00476
00477
00478
00479 circle.plane = plane;
00480 circle.plane.origin = circle_center;
00481 circle.plane.UpdateEquation();
00482
00483 return rc;
00484 }
00485
00486
00487
00488 int ON_Intersect(
00489
00490
00491
00492
00493
00494
00495
00496
00497 const ON_Line& line, const ON_Sphere& sphere,
00498 ON_3dPoint& A, ON_3dPoint& B
00499 )
00500 {
00501 int rc = 0;
00502 const ON_3dPoint sphere_center = sphere.plane.origin;
00503 const double sphere_radius = fabs(sphere.radius);
00504 double tol = sphere_radius*ON_SQRT_EPSILON;
00505 if ( tol < ON_ZERO_TOLERANCE )
00506 tol = ON_ZERO_TOLERANCE;
00507 ON_3dPoint line_center = line.ClosestPointTo(sphere_center);
00508 double d = line_center.DistanceTo(sphere_center);
00509 if ( d >= sphere_radius-tol ) {
00510 rc = ( d <= sphere_radius-tol ) ? 1 : 0;
00511 A = line_center;
00512 B = sphere.ClosestPointTo(line_center);
00513 }
00514 else {
00515 d /= sphere_radius;
00516 double h = sphere_radius*sqrt(1.0 - d*d);
00517 ON_3dVector V = line.Direction();
00518 V.Unitize();
00519 A = sphere.ClosestPointTo(line_center - h*V);
00520 B = sphere.ClosestPointTo(line_center + h*V);
00521 d = A.DistanceTo(B);
00522 if ( d <= ON_ZERO_TOLERANCE ) {
00523 A = line_center;
00524 B = sphere.ClosestPointTo(line_center);
00525 rc = 1;
00526 }
00527 else
00528 rc = 2;
00529 }
00530 return rc;
00531 }
00532
00533 static
00534 int Intersect2dLineCircle(ON_2dPoint line_from,
00535 ON_2dPoint line_to,
00536 double r,
00537 double tol,
00538 double* t0,
00539 double* t1
00540 )
00541 {
00542
00543
00544
00545
00546 int xcnt = 0;
00547 ON_BOOL32 bRev;
00548 double t, d, c, s, x, y, dx, dy;
00549 ON_2dVector v;
00550
00551 if ( line_from.x*line_from.x + line_from.y*line_from.y > line_to.x*line_to.x + line_to.y*line_to.y )
00552 {
00553 v = line_from;
00554 line_from = line_to;
00555 line_to = v;
00556 bRev = true;
00557 }
00558 else
00559 bRev = false;
00560 dx = line_to.x - line_from.x;
00561 dy = line_to.y - line_from.y;
00562 if ( fabs(dx) >= fabs(dy) )
00563 {
00564 if ( dx == 0.0 )
00565 {
00566 *t0 = 0.0;
00567 *t1 = 0.0;
00568 return 0;
00569 }
00570 else
00571 {
00572 d = dy/dx;
00573 d = fabs(dx)*sqrt(1.0+d*d);
00574 }
00575 }
00576 else
00577 {
00578 d = dx/dy;
00579 d = fabs(dy)*sqrt(1.0+d*d);
00580 }
00581 c = dx/d;
00582 s = dy/d;
00583
00584
00585 x = line_from.x;
00586 y = line_from.y;
00587 line_from.x = c*x + s*y;
00588 line_from.y = c*y - s*x;
00589
00590 x = line_to.x;
00591 y = line_to.y;
00592 line_to.x = c*x + s*y;
00593 line_to.y = c*y - s*x;
00594
00595
00596
00597 dx = line_to.x - line_from.x;
00598 if ( dx == 0.0 )
00599 {
00600 *t0 = 0.0;
00601 *t1 = 0.0;
00602 return 0;
00603 }
00604 dy = line_to.y - line_from.y;
00605 t = -line_from.x/dx;
00606 x = (1.0-t)*line_from.x + t*line_to.x;
00607 y = (1.0-t)*line_from.y + t*line_to.y;
00608 d = fabs(y);
00609 if ( d < r-tol )
00610 {
00611
00612 d /= r;
00613 d = r*sqrt(1.0-d*d);
00614 x = -(d + line_from.x)/dx;
00615 y = (d - line_from.x)/dx;
00616 if ( bRev )
00617 {
00618 x = 1.0-x;
00619 y = 1.0-y;
00620 }
00621 if (x<=y)
00622 {
00623 *t0 = x;
00624 *t1 = y;
00625 }
00626 else
00627 {
00628 *t0 = y;
00629 *t1 = x;
00630 }
00631 xcnt = ( x == y ) ? 1 : 2;
00632 }
00633 else if ( d > r+tol )
00634 {
00635
00636 xcnt = 3;
00637 if ( bRev )
00638 t = 1.0-t;
00639 *t0 = t;
00640 *t1 = t;
00641 }
00642 else
00643 {
00644
00645 xcnt = 1;
00646 if ( bRev )
00647 t = 1.0-t;
00648 *t0 = t;
00649 *t1 = t;
00650 }
00651 return xcnt;
00652 }
00653
00654
00655
00656
00657 int ON_Intersect(
00658
00659
00660
00661
00662
00663
00664
00665
00666
00667 const ON_Line& line,
00668 const ON_Cylinder& cylinder,
00669
00670
00671 ON_3dPoint& A, ON_3dPoint& B
00672 )
00673 {
00674 ON_BOOL32 bFiniteCyl = true;
00675 int rc = 0;
00676 const double cylinder_radius = fabs(cylinder.circle.radius);
00677 double tol = cylinder_radius*ON_SQRT_EPSILON;
00678 if ( tol < ON_ZERO_TOLERANCE )
00679 tol = ON_ZERO_TOLERANCE;
00680
00681 ON_Line axis;
00682 axis.from = cylinder.circle.plane.origin + cylinder.height[0]*cylinder.circle.plane.zaxis;
00683 axis.to = cylinder.circle.plane.origin + cylinder.height[1]*cylinder.circle.plane.zaxis;
00684 if ( axis.Length() <= tol ) {
00685 axis.to = cylinder.circle.plane.origin + cylinder.circle.plane.zaxis;
00686 bFiniteCyl = false;
00687 }
00688
00689
00690
00691 double line_t, axis_t;
00692 if ( !ON_Intersect(line,axis,&line_t,&axis_t) ) {
00693 axis.ClosestPointTo( cylinder.circle.plane.origin, &axis_t );
00694 line.ClosestPointTo( cylinder.circle.plane.origin, &line_t );
00695 }
00696 ON_3dPoint line_point = line.PointAt(line_t);
00697 ON_3dPoint axis_point = axis.PointAt(axis_t);
00698 double d = line_point.DistanceTo(axis_point);
00699 if ( bFiniteCyl ) {
00700 if ( axis_t < 0.0 )
00701 axis_t = 0.0;
00702 else if ( axis_t > 1.0 )
00703 axis_t = 1.0;
00704 axis_point = axis.PointAt(axis_t);
00705 }
00706
00707 if ( d >= cylinder_radius-tol) {
00708 rc = ( d <= cylinder_radius+tol ) ? 1 : 0;
00709 A = line_point;
00710 ON_3dVector V = line_point - axis_point;
00711 if ( bFiniteCyl ) {
00712 V = V - (V*cylinder.circle.plane.zaxis)*cylinder.circle.plane.zaxis;
00713 }
00714 V.Unitize();
00715 B = axis_point + cylinder_radius*V;
00716 if ( rc == 1 ) {
00717
00718 ON_3dPoint P = axis.ClosestPointTo(line.from);
00719 d = P.DistanceTo(line.from);
00720 if ( fabs(d-cylinder_radius) <= tol ) {
00721 P = axis.ClosestPointTo(line.to);
00722 d = P.DistanceTo(line.to);
00723 if ( fabs(d-cylinder_radius) <= tol ) {
00724 rc = 3;
00725 A = cylinder.ClosestPointTo(line.from);
00726 B = cylinder.ClosestPointTo(line.to);
00727 }
00728 }
00729 }
00730 }
00731 else {
00732
00733
00734 ON_Xform xform;
00735 xform.Rotation( cylinder.circle.plane, ON_xy_plane );
00736 ON_Line L = line;
00737 L.Transform(xform);
00738
00739 const double x0 = L.from.x;
00740 const double x1 = L.to.x;
00741 const double x1mx0 = x1-x0;
00742 double ax = x1mx0*x1mx0;
00743 double bx = 2.0*x1mx0*x0;
00744 double cx = x0*x0;
00745
00746 const double y0 = L.from.y;
00747 const double y1 = L.to.y;
00748 const double y1my0 = y1-y0;
00749 double ay = y1my0*y1my0;
00750 double by = 2.0*y1my0*y0;
00751 double cy = y0*y0;
00752
00753 double t0, t1;
00754 int qerc = ON_SolveQuadraticEquation(ax+ay, bx+by, cx+cy-cylinder_radius*cylinder_radius,
00755 &t0,&t1);
00756 if ( qerc == 2 ) {
00757
00758 t1 = t0;
00759 }
00760 A = cylinder.ClosestPointTo(line.PointAt(t0));
00761 B = cylinder.ClosestPointTo(line.PointAt(t1));
00762
00763 d = A.DistanceTo(B);
00764 if ( d <= ON_ZERO_TOLERANCE ) {
00765 A = line_point;
00766 ON_3dVector V = line_point - axis_point;
00767 if ( bFiniteCyl ) {
00768 V = V - (V*cylinder.circle.plane.zaxis)*cylinder.circle.plane.zaxis;
00769 }
00770 V.Unitize();
00771 B = axis_point + cylinder_radius*V;
00772 rc = 1;
00773 }
00774 else
00775 rc = 2;
00776 }
00777 return rc;
00778 }
00779
00780
00781 int ON_Intersect(
00782 const ON_Line& line,
00783 const ON_Circle& circle,
00784 double* line_t0,
00785 ON_3dPoint& circle_point0,
00786 double* line_t1,
00787 ON_3dPoint& circle_point1
00788 )
00789 {
00790
00791
00792 ON_Xform xform;
00793 xform.ChangeBasis( circle.plane, ON_xy_plane );
00794 xform.ChangeBasis( ON_xy_plane, circle.plane );
00795 ON_Line L = line;
00796 L.Transform(xform);
00797 double r = fabs(circle.radius);
00798 double tol = r*ON_SQRT_EPSILON;
00799 if ( tol < ON_ZERO_TOLERANCE )
00800 tol = ON_ZERO_TOLERANCE;
00801 int xcnt;
00802 if ( fabs(L.from.x - L.to.x) <= tol
00803 && fabs(L.from.y - L.to.y) <= tol
00804 && fabs(L.from.z - L.to.z) > tol )
00805 {
00806 xcnt = 0;
00807 }
00808 else
00809 {
00810 xcnt = Intersect2dLineCircle( L.from, L.to, r, tol, line_t0, line_t1 );
00811 if ( xcnt == 3 )
00812 xcnt = 1;
00813 }
00814
00815 if ( xcnt == 0 )
00816 {
00817 if ( L.ClosestPointTo( circle.Center(), line_t0 ) )
00818 {
00819 xcnt = 1;
00820 *line_t1 = *line_t0;
00821 }
00822 }
00823 ON_3dPoint line_point1, line_point0 = line.PointAt(*line_t0);
00824 circle_point0 = circle.ClosestPointTo(line_point0);
00825 double d1, d0 = line_point0.DistanceTo(circle_point0);
00826 if ( xcnt == 2 )
00827 {
00828 line_point1 = line.PointAt(*line_t1);
00829 circle_point1 = circle.ClosestPointTo(line_point1);
00830 d1 = line_point1.DistanceTo(circle_point1);
00831 }
00832 else
00833 {
00834 line_point1 = line_point0;
00835 circle_point1 = circle_point0;
00836 d1 = d0;
00837 }
00838 if ( xcnt==2 && (d0 > tol && d1 > tol) )
00839 {
00840 xcnt = 1;
00841 if ( d0 <= d1 )
00842 {
00843 *line_t1 = *line_t0;
00844 line_point1 = line_point0;
00845 circle_point1 = circle_point0;
00846 d1 = d0;
00847 }
00848 else
00849 {
00850 *line_t0 = *line_t1;
00851 line_point0 = line_point1;
00852 circle_point0 = circle_point1;
00853 d0 = d1;
00854 }
00855 }
00856 if ( xcnt == 1 && d0 > tol )
00857 {
00858
00859 }
00860 return xcnt;
00861 }
00862
00863 int ON_Intersect(
00864 const ON_Plane& plane,
00865 const ON_Circle& circle,
00866 ON_3dPoint& point0,
00867 ON_3dPoint& point1
00868 )
00869 {
00870 int rval = -1;
00871 ON_Line xline;
00872 double a,b;
00873 bool rc = ON_Intersect(plane, circle.Plane(), xline);
00874 if(rc)
00875 {
00876 rval = ON_Intersect(xline, circle, &a, point0, &b, point1);
00877 }
00878 else
00879 {
00880 double d = plane.plane_equation.ValueAt( circle.Center() );
00881 if(d<ON_ZERO_TOLERANCE)
00882 rval =3;
00883 else
00884 rval = 0;
00885 }
00886 return rval;
00887 }
00888
00889 int ON_Intersect(
00890 const ON_Plane& plane,
00891 const ON_Arc& arc,
00892 ON_3dPoint& point0,
00893 ON_3dPoint& point1
00894 )
00895 {
00896 int rval = -1;
00897 ON_Line xline;
00898 double a,b;
00899 bool rc = ON_Intersect(plane, arc.Plane(), xline);
00900 if(rc)
00901 {
00902 rval = ON_Intersect(xline, arc, &a, point0, &b, point1);
00903 }
00904 else
00905 {
00906 double d = plane.plane_equation.ValueAt( arc.StartPoint() );
00907 if(d<ON_ZERO_TOLERANCE)
00908 rval =3;
00909 else
00910 rval = 0;
00911 }
00912 return rval;
00913 }
00914
00915 int ON_Intersect(
00916 const ON_Line& line,
00917 const ON_Arc& arc,
00918 double* line_t0,
00919 ON_3dPoint& arc_point0,
00920 double* line_t1,
00921 ON_3dPoint& arc_point1
00922 )
00923 {
00924 ON_Circle c = arc;
00925 ON_3dPoint p[2];
00926 double t[2], a[2], s;
00927 ON_BOOL32 b[2] = {false,false};
00928 int i, xcnt = ON_Intersect( line, c, &t[0], p[0], &t[1], p[1] );
00929 if ( xcnt > 0 )
00930 {
00931
00932 ON_Interval arc_domain = arc.DomainRadians();
00933 for ( i = 0; i < xcnt; i++ )
00934 {
00935 b[i] = c.ClosestPointTo(p[i], &a[i]);
00936 if ( b[i] )
00937 {
00938 s = arc_domain.NormalizedParameterAt(a[i]);
00939 if ( s < 0.0 )
00940 {
00941 if ( s >= -ON_SQRT_EPSILON )
00942 {
00943 a[i] = arc_domain[0];
00944 p[i] = c.PointAt(a[i]);
00945 b[i] = line.ClosestPointTo( p[i], &t[i] );
00946 }
00947 else
00948 b[i] = false;
00949 }
00950 else if ( s > 1.0 )
00951 {
00952 if ( s <= 1.0+ON_SQRT_EPSILON )
00953 {
00954 a[i] = arc_domain[1];
00955 p[i] = c.PointAt(a[i]);
00956 b[i] = line.ClosestPointTo( p[i], &t[i] );
00957 }
00958 else
00959 b[i] = false;
00960 }
00961 }
00962 }
00963 if ( !b[0] && !b[1] )
00964 xcnt = 0;
00965
00966 if ( xcnt == 2 )
00967 {
00968 if ( !b[1] )
00969 xcnt = 1;
00970 if ( !b[0] )
00971 {
00972 xcnt = 1;
00973 b[0] = b[1];
00974 t[0] = t[1];
00975 a[0] = a[1];
00976 p[0] = p[1];
00977 b[1] = 0;
00978 }
00979 if ( xcnt == 2 && t[0] == t[1] )
00980 {
00981 xcnt = 1;
00982 b[1] = 0;
00983 ON_3dPoint q = line.PointAt(t[0]);
00984 if ( p[0].DistanceTo(q) > p[1].DistanceTo(q) )
00985 {
00986 a[0] = a[1];
00987 t[0] = t[1];
00988 p[0] = p[1];
00989 }
00990 }
00991 }
00992 if ( xcnt == 1 && !b[0] )
00993 xcnt = 0;
00994 if ( xcnt >= 1 )
00995 {
00996 if ( line_t0 )
00997 *line_t0 = t[0];
00998 arc_point0 = p[0];
00999 }
01000 if ( xcnt == 2 )
01001 {
01002 if ( line_t1 )
01003 *line_t1 = t[1];
01004 arc_point1 = p[1];
01005 }
01006 }
01007 return xcnt;
01008 }
01009
01010 int ON_Intersect( const ON_Sphere& sphere0,
01011 const ON_Sphere& sphere1,
01012 ON_Circle& circle
01013 )
01014
01015 {
01016 double r0 = sphere0.Radius();
01017 double r1 = sphere1.Radius();
01018 ON_3dPoint C0 = sphere0.Center();
01019 ON_3dPoint C1 = sphere1.Center();
01020 ON_3dVector D = C1-C0;
01021 double d = D.Length();
01022 if (!D.Unitize()){
01023 if (fabs(r1-r0) > ON_ZERO_TOLERANCE)
01024 return 0;
01025 return 3;
01026 }
01027
01028
01029 if (d > r0 + r1)
01030 return 0;
01031
01032
01033 if (d == r0+r1){
01034 ON_3dPoint P = C0 + r0*D;
01035 circle.Create(P, 0.0);
01036 return 1;
01037 }
01038
01039
01040 if (d == fabs(r0-r1)){
01041 ON_3dPoint P = (r0 > r1) ? C0 + r0*D : C0 - r0*D;
01042 circle.Create(P, 0.0);
01043 return 1;
01044 }
01045
01046
01047 if (d < fabs(r0-r1))
01048 return 0;
01049
01050
01051 double x = 0.5*(d*d + r0*r0 - r1*r1)/d;
01052 if (x >= r0){
01053 ON_3dPoint P = C0 + r0*D;
01054 circle.Create(P, 0.0);
01055 return 1;
01056 }
01057 if (x <= -r0){
01058 ON_3dPoint P = C0 - r0*D;
01059 circle.Create(P, 0.0);
01060 return 1;
01061 }
01062 double y = r0*r0 - x*x;
01063 if (y < 0.0)
01064 return 0;
01065 y = sqrt(y);
01066
01067 ON_3dPoint P = C0 + x*D;
01068 ON_Plane plane(P, D);
01069 circle.Create(plane, y);
01070 return 2;
01071 }
01072
01073