opennurbs_circle.cpp
Go to the documentation of this file.
00001 /* $NoKeywords: $ */
00002 /*
00003 //
00004 // Copyright (c) 1993-2012 Robert McNeel & Associates. All rights reserved.
00005 // OpenNURBS, Rhinoceros, and Rhino3D are registered trademarks of Robert
00006 // McNeel & Associates.
00007 //
00008 // THIS SOFTWARE IS PROVIDED "AS IS" WITHOUT EXPRESS OR IMPLIED WARRANTY.
00009 // ALL IMPLIED WARRANTIES OF FITNESS FOR ANY PARTICULAR PURPOSE AND OF
00010 // MERCHANTABILITY ARE HEREBY DISCLAIMED.
00011 //                              
00012 // For complete openNURBS copyright information see <http://www.opennurbs.org>.
00013 //
00015 */
00016 
00017 #include "pcl/surface/3rdparty/opennurbs/opennurbs.h"
00018 
00019 ON_Circle::ON_Circle() 
00020                   : radius(1.0)
00021 {
00022   //m_point[0].Zero();
00023   //m_point[1].Zero();
00024   //m_point[2].Zero();
00025 }
00026 
00027 ON_Circle::~ON_Circle()
00028 {}
00029 
00030 ON_Circle::ON_Circle( const ON_Plane& p, double r )
00031 {
00032   Create( p, r );
00033 }
00034 
00035 ON_Circle::ON_Circle( const ON_3dPoint& C, double r )
00036 {
00037   Create( C, r );
00038 }
00039 
00040 ON_Circle::ON_Circle( const ON_Plane& pln, const ON_3dPoint& C, double r )
00041 {
00042   Create( pln, C, r );
00043 }
00044 
00045 ON_Circle::ON_Circle( const ON_2dPoint& P, const ON_2dPoint& Q, const ON_2dPoint& R )
00046 {
00047   Create(P,Q,R);
00048 }
00049 
00050 ON_Circle::ON_Circle( const ON_3dPoint& P, const ON_3dPoint& Q, const ON_3dPoint& R )
00051 {
00052   Create(P,Q,R);
00053 }
00054 
00055 
00056 double ON_Circle::Radius() const
00057 {
00058   return radius;
00059 }
00060 
00061 double ON_Circle::Diameter() const
00062 {
00063   return 2.0*radius;
00064 }
00065 
00066 const ON_3dPoint& ON_Circle::Center() const
00067 {
00068   return plane.origin;
00069 }
00070 
00071 const ON_3dVector& ON_Circle::Normal() const
00072 {
00073   return plane.zaxis;
00074 }
00075 
00076 const ON_Plane& ON_Circle::Plane() const
00077 {
00078   return plane;
00079 }
00080 
00081 ON_BoundingBox ON_Circle::BoundingBox() const
00082 {
00083   ON_BoundingBox bbox;
00084   ON_3dPoint corners[4]; // = corners of square that contains circle
00085   corners[0] = plane.PointAt( radius, radius );
00086   corners[1] = plane.PointAt( radius,-radius );
00087   corners[2] = plane.PointAt(-radius, radius );
00088   corners[3] = plane.PointAt(-radius,-radius );
00089   bbox.Set(3,0,4,3,&corners[0].x,false);   
00090   return bbox;
00091 }
00092 
00093 bool ON_Circle::Transform( const ON_Xform& xform )
00094 {
00095   const ON_Plane plane0(plane);
00096   const bool rc = plane.Transform(xform);
00097   if (!rc)
00098   {
00099     // restore original
00100     plane = plane0;
00101   }
00102   else
00103   {
00104     const double ztol = 1.0e-12;
00105     double a,b,c,d,r1,r2,s;
00106     // determine scale factor in circle's plane
00107     // In practice, transformation are either rotations,
00108     // the scale factor is clearly distinct from 1,
00109     // or the transformation does not map a circle
00110     // to a circle.  The code below has tolerance checks
00111     // so that anything that is close to a rotation gets
00112     // treated does not change the radius.  If it is
00113     // clearly a uniform scale in the plane of the circle
00114     // the scale factor is calculated without using a
00115     // determinant.  Sine "2d scales" are common, it doesn't
00116     // work well use the cubed root of the xform'd determinant.
00117     ON_3dVector V = xform*plane0.xaxis;
00118     a = V*plane.xaxis;
00119     b = V*plane.yaxis;
00120     if (fabs(a) >= fabs(b))
00121     {
00122       r1 = fabs(a);
00123       if ( r1 > 0.0)
00124       {
00125         a = (a>0.0) ? 1.0 : -1.0;
00126         b /= r1;
00127         if ( fabs(b) <= ztol )
00128         {
00129           b = 0.0;
00130           if ( fabs(1.0-r1) <= ztol )
00131             r1 = 1.0;
00132         }
00133       }
00134     }
00135     else
00136     {
00137       r1 = fabs(b);
00138       b = (b>0.0) ? 1.0 : -1.0;
00139       a /= r1;
00140       if ( fabs(a) <= ztol )
00141       {
00142         a = 0.0;
00143         if ( fabs(1.0-r1) <= ztol )
00144           r1 = 1.0;
00145       }
00146     }
00147     V = xform*plane0.yaxis;
00148     c = V*plane.xaxis;
00149     d = V*plane.yaxis;
00150     if (fabs(d) >= fabs(c))
00151     {
00152       r2 = fabs(d);
00153       if (r2 > 0.0)
00154       {
00155         d = (d>0.0) ? 1.0 : -1.0;
00156         c /= r2;
00157         if ( fabs(c) <= ztol )
00158         {
00159           c = 0.0;
00160           if ( fabs(1.0-r2) <= ztol )
00161             r2 = 1.0;
00162         }
00163       }
00164     }
00165     else
00166     {
00167       r2 = fabs(c);
00168       c = (c>0.0) ? 1.0 : -1.0;
00169       d /= r2;
00170       if ( fabs(d) <= ztol )
00171       {
00172         d = 0.0;
00173         if ( fabs(1.0-r2) <= ztol )
00174           r2 = 1.0;
00175       }
00176     }
00177     if (    0.0 == b 
00178          && 0.0 == c 
00179          && fabs(r1-r1) <= ON_SQRT_EPSILON*(r1+r2) 
00180        )
00181     {
00182       // transform is a similarity
00183       s = 0.5*(r1+r2); // = sqrt(r1*r2) but more accurate
00184     }
00185     else
00186     {
00187       // non-uniform scaling or skew in circle's plane
00188       // do something reasonable
00189       s = sqrt(fabs(r1*r2*(a*d-b*c)));
00190     }
00191 
00192     if ( s > 0.0 )
00193     {
00194       //#if defined(ON_DEBUG) && !defined(ON_COMPILER_GNU)
00195       //double det = fabs(xform.Determinant());
00196       //double s0 = pow(det,1.0/3.0);
00197       //if ( fabs(s-s0) > ON_SQRT_EPSILON*s0 )
00198       //{
00199       //  // non-uniform scale or a bug
00200       //  // In the non-uniform scal case, b and c should be
00201       //  // "zero".
00202       //  int breakpointhere = 0; // (generates gcc warning)
00203       //}
00204       //#endif
00205       if ( fabs(s-1.0) > ON_SQRT_EPSILON )
00206         radius *= s;
00207     }
00208   }
00209 
00210   return rc;
00211 }
00212 
00213 
00214 double ON_Circle::Circumference() const
00215 {
00216   return fabs(2.0*ON_PI*radius);
00217 }
00218 
00219 bool ON_Circle::Create( const ON_Plane& p, double r )
00220 {
00221   plane = p;
00222   if ( !plane.IsValid() )
00223     plane.UpdateEquation(); // people often forget to set equation
00224   radius = r;
00225   //m_point[0] = plane.PointAt( radius, 0.0 );
00226   //m_point[1] = plane.PointAt( 0.0, radius );
00227   //m_point[2] = plane.PointAt( -radius, 0.0 );
00228   return ( radius > 0.0 );
00229 }
00230 
00231 bool ON_Circle::Create( const ON_3dPoint& C, double r )
00232 {
00233   ON_Plane p = ON_xy_plane;
00234   p.origin = C;
00235   p.UpdateEquation();
00236   return Create( p, r );
00237 }
00238 
00239 bool ON_Circle::Create( const ON_Plane& pln,
00240                           const ON_3dPoint& C,
00241                           double r 
00242                           )
00243 {
00244   ON_Plane p = pln;
00245   p.origin = C;
00246   p.UpdateEquation();
00247   return Create( p, r );
00248 }
00249 
00250 bool ON_Circle::Create( // circle through three 3d points
00251     const ON_2dPoint& P,
00252     const ON_2dPoint& Q,
00253     const ON_2dPoint& R
00254     )
00255 {
00256   return Create(ON_3dPoint(P),ON_3dPoint(Q),ON_3dPoint(R));
00257 }
00258 
00259 bool ON_Circle::Create( // circle through three 3d points
00260     const ON_3dPoint& P,
00261     const ON_3dPoint& Q,
00262     const ON_3dPoint& R
00263     )
00264 {
00265   ON_3dPoint C;
00266   ON_3dVector X, Y, Z;
00267   // return ( radius > 0.0 && plane.IsValid() );
00268   //m_point[0] = P;
00269   //m_point[1] = Q;
00270   //m_point[2] = R;
00271 
00272   // get normal
00273   for(;;)
00274   {
00275     if ( !Z.PerpendicularTo( P, Q, R ) )
00276       break;
00277 
00278     // get center as the intersection of 3 planes
00279     ON_Plane plane0( P, Z );
00280     ON_Plane plane1( 0.5*(P+Q), P-Q );
00281     ON_Plane plane2( 0.5*(R+Q), R-Q );
00282     if ( !ON_Intersect( plane0, plane1, plane2, C ) )
00283       break;
00284 
00285     X = P - C;
00286     radius = X.Length();
00287     if ( !(radius > 0.0) )
00288       break;
00289 
00290     if ( !X.Unitize() )
00291       break;
00292     
00293     Y = ON_CrossProduct( Z, X );
00294     if ( !Y.Unitize() )
00295       break;
00296 
00297     plane.origin = C;
00298     plane.xaxis = X;
00299     plane.yaxis = Y;
00300     plane.zaxis = Z;
00301 
00302     plane.UpdateEquation();
00303 
00304     return true;
00305   }
00306 
00307   plane = ON_Plane::World_xy;
00308   radius = 0.0;
00309   return false;
00310 }
00311 
00313 // Create an circle from two 2d points and a tangent at the first point.
00314 bool ON_Circle::Create(
00315   const ON_2dPoint& P,     // [IN] point P
00316   const ON_2dVector& Pdir, // [IN] tangent at P
00317   const ON_2dPoint& Q      // [IN] point Q
00318   )
00319 {
00320   return Create( ON_3dPoint(P), ON_3dVector(Pdir), ON_3dPoint(Q) );
00321 }
00322 
00324 // Create an circle from two 3d points and a tangent at the first point.
00325 bool ON_Circle::Create(
00326   const ON_3dPoint& P,      // [IN] point P
00327   const ON_3dVector& Pdir, // [IN] tangent at P
00328   const ON_3dPoint& Q      // [IN] point Q
00329   )
00330 {
00331   bool rc = false;
00332   double a, b;
00333   ON_3dVector QP, RM, RP, X, Y, Z;
00334   ON_3dPoint M, C;
00335   ON_Line A, B;
00336 
00337   // n = normal to circle
00338   QP = Q-P;
00339   Z = ON_CrossProduct( QP, Pdir );
00340   if ( Z.Unitize() ) {
00341     M = 0.5*(P+Q);
00342     RM = ON_CrossProduct( QP, Z ); // vector parallel to center-M
00343     A.Create(M,M+RM);
00344     RP = ON_CrossProduct( Pdir, Z ); //  vector parallel to center-P
00345     B.Create(P,P+RP);
00346     if ( ON_Intersect( A, B, &a, &b ) ) {
00347       C = A.PointAt( a ); // center = intersection of lines A and B
00348       X = P-C;
00349       radius = C.DistanceTo(P);
00350       if ( X.Unitize() ) {
00351         Y = ON_CrossProduct( Z, X );
00352         if ( Y*Pdir < 0.0 ) {
00353           Z.Reverse();
00354           Y.Reverse();
00355           RM.Reverse();
00356         }
00357         plane.origin = C;
00358         plane.xaxis = X;
00359         plane.yaxis = Y;
00360         plane.zaxis = Z;
00361         plane.UpdateEquation();
00362         //m_point[0] = P;
00363         //m_point[1] = C + radius*RM/RM.Length();
00364         //m_point[2] = Q;
00365         rc = IsValid();
00366       }
00367     }
00368   }
00369   return rc;
00370 }
00371 
00372 
00373 bool ON_Circle::IsValid() const
00374 {
00375   bool rc = (    ON_IsValid(radius) 
00376               && radius > 0.0
00377               && plane.IsValid()
00378             );
00379   return rc;
00380 }
00381 
00382 bool ON_Circle::IsInPlane( const ON_Plane& plane, double tolerance ) const
00383 {
00384   double d;
00385   int i;
00386   for ( i = 0; i < 8; i++ ) {
00387     d = plane.plane_equation.ValueAt( PointAt(0.25*i*ON_PI) );
00388     if ( fabs(d) > tolerance )
00389       return false;
00390   }
00391   return true;
00392 }
00393 
00394 ON_3dPoint ON_Circle::PointAt( double t ) const
00395 {
00396   return plane.PointAt( cos(t)*radius, sin(t)*radius );
00397 }
00398 
00399 ON_3dVector ON_Circle::DerivativeAt( 
00400                  int d, // desired derivative ( >= 0 )
00401                  double t // parameter
00402                  ) const
00403 {
00404   double r0 = radius;
00405   double r1 = radius;
00406   switch (abs(d)%4) {
00407   case 0:
00408     r0 *=  cos(t);
00409     r1 *=  sin(t);
00410     break;
00411   case 1:
00412     r0 *= -sin(t);
00413     r1 *=  cos(t);
00414     break;
00415   case 2:
00416     r0 *= -cos(t);
00417     r1 *= -sin(t);
00418     break;
00419   case 3:
00420     r0 *=  sin(t);
00421     r1 *= -cos(t);
00422     break;
00423   }
00424   return ( r0*plane.xaxis + r1*plane.yaxis );
00425 }
00426 
00427 ON_3dVector ON_Circle::TangentAt( double t ) const
00428 {
00429   ON_3dVector T = DerivativeAt(1,t);
00430   T.Unitize();
00431   return T;
00432 }
00433 
00434 bool ON_Circle::ClosestPointTo( const ON_3dPoint& point, double* t ) const
00435 {
00436   bool rc = true;
00437   if ( t ) {
00438     double u, v;
00439     rc = plane.ClosestPointTo( point, &u, &v );
00440     if ( u == 0.0 && v == 0.0 ) {
00441       *t = 0.0;
00442     }
00443     else {
00444       *t = atan2( v, u );
00445       if ( *t < 0.0 )
00446         *t += 2.0*ON_PI;
00447     }
00448   }
00449   return rc;
00450 }
00451 
00452 ON_3dPoint ON_Circle::ClosestPointTo( const ON_3dPoint& point ) const
00453 {
00454   ON_3dPoint P;
00455   ON_3dVector V = plane.ClosestPointTo( point ) - Center();
00456   if ( V.Unitize() ) {
00457     V.Unitize();
00458     P = Center() + Radius()*V;
00459   }
00460   else {
00461     P = PointAt(0.0);
00462   }
00463   return P;
00464 }
00465 
00466 double ON_Circle::EquationAt( 
00467                  const ON_2dPoint& p // coordinates in plane
00468                  ) const
00469 {
00470   double e, x, y;
00471   if ( radius != 0.0 ) {
00472     x = p.x/radius;
00473     y = p.y/radius;
00474     e = x*x + y*y - 1.0;
00475   }
00476   else {
00477     e = 0.0;
00478   }
00479   return e;
00480 }
00481 
00482 ON_2dVector ON_Circle::GradientAt( 
00483                  const ON_2dPoint& p // coordinates in plane
00484                  ) const
00485 {
00486   ON_2dVector g;
00487   if ( radius != 0.0 ) {
00488     const double rr = 2.0/(radius*radius);
00489     g.x = rr*p.x;
00490     g.y = rr*p.y;
00491   }
00492   else {
00493     g.Zero();
00494   }
00495   return g;
00496 }
00497 
00498 bool ON_Circle::Rotate( 
00499                           double sin_angle, double cos_angle, 
00500                           const ON_3dVector& axis
00501                           )
00502 {
00503   return plane.Rotate( sin_angle, cos_angle, axis );
00504 }
00505 
00506 bool ON_Circle::Rotate( 
00507                           double angle, 
00508                           const ON_3dVector& axis
00509                           )
00510 {
00511   return plane.Rotate( angle, axis );
00512 }
00513 
00514 bool ON_Circle::Rotate( 
00515                           double sin_angle, double cos_angle, 
00516                           const ON_3dVector& axis,
00517                           const ON_3dPoint& point
00518                           )
00519 {
00520   return plane.Rotate( sin_angle, cos_angle, axis, point );
00521 }
00522 
00523 bool ON_Circle::Rotate( 
00524                           double angle, 
00525                           const ON_3dVector& axis,
00526                           const ON_3dPoint& point
00527                           )
00528 {
00529   return plane.Rotate( angle, axis, point );
00530 }
00531 
00532 
00533 bool ON_Circle::Translate(
00534                           const ON_3dVector& delta
00535                             )
00536 {
00537   //m_point[0] += delta;
00538   //m_point[1] += delta;
00539   //m_point[2] += delta;
00540   return plane.Translate( delta );
00541 }
00542 
00543 bool ON_Circle::Reverse()
00544 {
00545   //ON_3dPoint P = m_point[0];
00546   //m_point[0] = m_point[2];
00547   //m_point[2] = P;
00548   plane.yaxis = -plane.yaxis;
00549   plane.zaxis = -plane.zaxis;
00550   plane.UpdateEquation();
00551   return true;
00552 }
00553 
00554 int ON_Circle::GetNurbForm( ON_NurbsCurve& nurbscurve ) const
00555 {
00556   int rc = 0;
00557   if ( IsValid() ) {
00558     nurbscurve.Create( 3, true, 3, 9 );
00559     nurbscurve.m_knot[0] = nurbscurve.m_knot[1] = 0.0;
00560     nurbscurve.m_knot[2] = nurbscurve.m_knot[3] = 0.5*ON_PI;
00561     nurbscurve.m_knot[4] = nurbscurve.m_knot[5] = ON_PI;
00562     nurbscurve.m_knot[6] = nurbscurve.m_knot[7] = 1.5*ON_PI;
00563     nurbscurve.m_knot[8] = nurbscurve.m_knot[9] = 2.0*ON_PI;
00564     ON_4dPoint* CV = (ON_4dPoint*)nurbscurve.m_cv;
00565 
00566     CV[0] = plane.PointAt( radius,     0.0);
00567     CV[1] = plane.PointAt( radius,  radius);
00568     CV[2] = plane.PointAt(    0.0,  radius);
00569     CV[3] = plane.PointAt(-radius,  radius);
00570     CV[4] = plane.PointAt(-radius,     0.0);
00571     CV[5] = plane.PointAt(-radius, -radius);
00572     CV[6] = plane.PointAt(    0.0, -radius);
00573     CV[7] = plane.PointAt( radius, -radius);
00574     CV[8] = CV[0];
00575     
00576     const double w = 1.0/sqrt(2.0);
00577     int i;
00578     for ( i = 1; i < 8; i += 2 ) {
00579       CV[i].x *= w;
00580       CV[i].y *= w;
00581       CV[i].z *= w;
00582       CV[i].w = w;
00583     }
00584     rc = 2;
00585   }
00586   return rc;
00587 }
00588 
00589 
00590 
00591 bool ON_Circle::GetRadianFromNurbFormParameter( double NurbParameter, double* RadianParameter ) const
00592 //returns false unless   0<= NurbParameter,  <= 2*PI*Radius
00593 {
00594         if(!IsValid()) 
00595                 return false;
00596 
00597         ON_Arc arc(*this, 2*ON_PI);
00598         return arc.GetRadianFromNurbFormParameter( NurbParameter, RadianParameter);
00599 }
00600 
00601 
00602 
00603 bool ON_Circle::GetNurbFormParameterFromRadian( double RadianParameter, double* NurbParameter) const
00604 {
00605         if(!IsValid()) 
00606                 return false;
00607 
00608         ON_Arc arc(*this, 2*ON_PI);
00609         return arc.GetNurbFormParameterFromRadian(  RadianParameter, NurbParameter);
00610 }
00611 
00612 
00613 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:27:00