opennurbs_arc.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_Arc::ON_Arc() : m_angle(0.0,2.0*ON_PI)
00020 {
00021   radius=1.0;
00022 }
00023 
00024 ON_Arc::ON_Arc( const ON_Circle& c, double angle_in_radians ) 
00025        : m_angle(0.0,2.0*ON_PI)
00026 {
00027   Create( c, angle_in_radians );
00028 }
00029 
00030 ON_Arc::ON_Arc( const ON_Circle& c, ON_Interval angle_interval_in_radians ) 
00031        : m_angle(0.0,2.0*ON_PI)
00032 {
00033   Create( c, angle_interval_in_radians );
00034 }
00035 
00036 ON_Arc::ON_Arc( const ON_Plane& p, double r, double angle_in_radians )
00037        : m_angle(0.0,2.0*ON_PI)
00038 {
00039   Create( p, r, angle_in_radians );
00040 }
00041 
00042 ON_Arc::ON_Arc( const ON_3dPoint& C, double r, double angle_in_radians )
00043        : m_angle(0.0,2.0*ON_PI)
00044 {
00045   Create( C, r, angle_in_radians );
00046 }
00047 
00048 ON_Arc::ON_Arc( const ON_Plane& pln, const ON_3dPoint& C, double r, double angle_in_radians )
00049        : m_angle(0.0,2.0*ON_PI)
00050 {
00051   Create( pln, C, r, angle_in_radians );
00052 }
00053 
00054 ON_Arc::ON_Arc( const ON_2dPoint& P, const ON_2dPoint& Q, const ON_2dPoint& R ) 
00055        : m_angle(0.0,2.0*ON_PI)
00056 {
00057   Create( P, Q, R );
00058 }
00059 
00060 ON_Arc::ON_Arc( const ON_3dPoint& P, const ON_3dPoint& Q, const ON_3dPoint& R )
00061        : m_angle(0.0,2.0*ON_PI)
00062 {
00063   Create( P, Q, R );
00064 }
00065 
00066 ON_Arc& ON_Arc::operator=( const ON_Circle& c )
00067 {
00068 
00069 #if defined(ON_COMPILER_IRIX)
00070   plane = c.plane;
00071   radius = c.radius;
00072 #else
00073   ON_Circle::operator=(c);
00074 #endif
00075 
00076   m_angle.Set(0.0,2.0*ON_PI);
00077   return *this;
00078 }
00079 
00080 
00081 bool ON_Arc::Create(
00082   const ON_Circle& circle,
00083   double angle_radians          // angle in radians
00084   )
00085 {
00086   return Create( circle, ON_Interval( 0.0, angle_radians ) );
00087 }
00088 
00089 bool ON_Arc::Create(
00090   const ON_Circle& circle,
00091   ON_Interval angle_interval_in_radians
00092   )
00093 {
00094   bool rc = true;
00095   plane = circle.plane;
00096   plane.UpdateEquation();
00097   radius = circle.radius;
00098   m_angle = angle_interval_in_radians;
00099   if ( m_angle.IsDecreasing() )
00100   {
00101     rc = false; // bogus input
00102     // m_angle must never be decreasing
00103     m_angle.Swap();
00104     Reverse();
00105   }
00106   if ( m_angle.Length() > 2.0*ON_PI )
00107   {
00108     rc = false; // bogus input
00109     m_angle.m_t[1] = m_angle.m_t[0] + 2.0*ON_PI;
00110   }
00111   if ( rc )
00112     rc = IsValid();
00113   return rc;
00114 }
00115 
00116 
00117 bool ON_Arc::Create(
00118   const ON_Plane& pl, // circle is in this plane with center at m_origin
00119   double r,         // radius
00120   double angle_radians   // angle in radians
00121   )
00122 {
00123   return Create( ON_Circle(pl,r), ON_Interval( 0.0, angle_radians ) );
00124 }
00125 
00126 bool ON_Arc::Create( // arc is parallel to XY plane
00127   const ON_3dPoint& center, // center
00128   double r,            // radius
00129   double angle_radians // angle in radians
00130   )
00131 {
00132   ON_Plane p;
00133   p.CreateFromNormal( center, ON_zaxis );
00134   return Create( ON_Circle(p,r), ON_Interval( 0.0, angle_radians ) );
00135 }
00136 
00137 bool ON_Arc::Create(        // arc parallel to a plane
00138   const ON_Plane& pl,       // circle will be parallel to this plane
00139   const ON_3dPoint& center, // center
00140   double r,                 // radius
00141   double angle_radians      // angle in radians
00142   )
00143 {
00144   ON_Plane p = pl;
00145   p.origin = center;
00146   p.UpdateEquation();
00147   return Create( ON_Circle( p, r), ON_Interval( 0.0, angle_radians ) );
00148 }
00149 
00150 bool ON_Arc::Create( // arc through 3 2d points
00151   const ON_2dPoint& P, // point P
00152   const ON_2dPoint& Q, // point Q
00153   const ON_2dPoint& R // point R
00154   )
00155 {
00156   ON_Circle c(P,Q,R);
00157   double a = 0.0;
00158   c.ClosestPointTo( R, &a );
00159   return Create( c, ON_Interval(0.0,a) );
00160 }
00161 
00162 bool ON_Arc::Create( // arc through 3 3d points
00163   const ON_3dPoint& P, // point P
00164   const ON_3dPoint& Q, // point Q
00165   const ON_3dPoint& R  // point R
00166   )
00167 {
00168   ON_Circle c;
00169   double a = 0.0;
00170 
00171   for (;;)
00172   {
00173 
00174     if ( !c.Create(P,Q,R) )
00175       break;
00176 
00177     if ( !c.ClosestPointTo( R, &a ) )
00178       break;
00179 
00180     if ( !(a > 0.0) )
00181       break;
00182     
00183     if ( !Create( c, ON_Interval(0.0,a) ) )
00184       break;
00185 
00186     return true;
00187   }
00188 
00189   plane = ON_Plane::World_xy;
00190   radius = 0.0;
00191   m_angle.Set(0.0,0.0);
00192 
00193   return false;
00194 }
00195 
00197 // Create an arc from a 2d start point, 2d start direction, and 2d end point.
00198 bool ON_Arc::Create(
00199   const ON_2dPoint& P, // [IN] start point
00200   const ON_2dVector& Pdir,  // [IN] arc direction at start
00201   const ON_2dPoint&  Q   // [IN] end point
00202   )
00203 {
00204   return Create( ON_3dPoint(P), ON_3dVector(Pdir), ON_3dPoint(Q) );
00205 }
00206 
00208 // Create an arc from a 3d start point, 3d start direction, and 3d end point.
00209 bool ON_Arc::Create(
00210   const ON_3dPoint& P, // [IN] start point
00211   const ON_3dVector& Pdir,  // [IN] arc direction at start
00212   const ON_3dPoint&  Q   // [IN] end point
00213   )
00214 {
00215   double a=0.0;
00216   bool rc = ON_Circle::Create(P,Pdir,Q);
00217   if ( rc ) {
00218     m_angle.m_t[0] = 0.0;
00219     rc = ON_Circle::ClosestPointTo(Q,&a);
00220     m_angle.m_t[1] = a;
00221     if (a <= ON_ZERO_TOLERANCE || a >= 2.0*ON_PI-ON_ZERO_TOLERANCE )
00222       rc = false;
00223   }
00224   return rc;
00225 }
00226 
00227 
00228 ON_Arc::~ON_Arc()
00229 {}
00230 
00231 void ON_Arc::Dump( ON_TextLog& dump ) const
00232 {
00233   dump.Print("Arc: normal = ");
00234   dump.Print(plane.zaxis);
00235   dump.Print(" center = ");
00236   dump.Print(plane.origin);
00237   dump.Print(" start = ");
00238   dump.Print( StartPoint() );
00239   dump.Print(" end = ");
00240   dump.Print( EndPoint() );
00241   dump.Print(" radius = ");
00242   dump.Print(Radius());
00243   dump.Print(" angle = [");
00244   dump.Print(m_angle[0]);
00245   dump.Print(",");
00246   dump.Print(m_angle[1]);
00247   dump.Print("]\n");
00248 }
00249 
00250 ON_3dPoint ON_Arc::StartPoint() const
00251 {
00252   return PointAt(m_angle[0]);
00253 }
00254 
00255 ON_3dPoint ON_Arc::MidPoint() const
00256 {
00257   return PointAt(m_angle.Mid());
00258 }
00259 
00260 ON_3dPoint ON_Arc::EndPoint() const
00261 {
00262   return PointAt(m_angle[1]);
00263 }
00264 
00265 bool ON_Arc::IsValid() const
00266 {
00267   return (    ON_Circle::IsValid() 
00268            && m_angle.IsValid()
00269            && AngleRadians() > ON_ZERO_TOLERANCE 
00270            && AngleRadians() <= 2.0*ON_PI+ON_ZERO_TOLERANCE) 
00271          ? true : false;
00272 }
00273 
00274 ON_BoundingBox ON_Arc::BoundingBox() const
00275 {
00276   // TODO - compute tight arc bounding box
00277 
00278   // Using these knot[] and cv[] arrays makes this function
00279   // not use any heap memory.
00280   double knot[10];
00281   ON_4dPoint cv[9];
00282   ON_NurbsCurve c;
00283   c.m_knot = knot;
00284   c.m_cv = &cv[0].x;
00285   if ( GetNurbForm(c) )
00286     return c.BoundingBox();
00287   return ON_Circle::BoundingBox();
00288 }
00289 
00290 bool ON_Arc::GetBoundingBox(
00291        ON_BoundingBox& bbox,
00292        int bGrowBox
00293        ) const
00294 {
00295   if (bGrowBox)
00296   {
00297     ON_BoundingBox arc_bbox = BoundingBox();
00298     bbox.Union(arc_bbox);
00299   }
00300   else
00301     bbox = BoundingBox();
00302   return bbox.IsValid();
00303 }
00304 
00305 bool ON_Arc::IsCircle() const
00306 {
00307   return (fabs(fabs(AngleRadians()) - 2.0*ON_PI) <= ON_ZERO_TOLERANCE) 
00308          ? true : false;
00309 }
00310 
00311 double ON_Arc::AngleRadians() const
00312 {
00313   return m_angle[1]-m_angle[0];
00314 }
00315 
00316 double ON_Arc::AngleDegrees() const
00317 {
00318   return (AngleRadians()/ON_PI)*180.0;
00319 }
00320 
00321 ON_Interval ON_Arc::Domain() const
00322 {
00323   return m_angle;
00324 }
00325 
00326 ON_Interval ON_Arc::DomainRadians() const
00327 {
00328   return m_angle;
00329 }
00330 
00331 ON_Interval ON_Arc::DomainDegrees() const
00332 {
00333   const double rtd = 180.0/ON_PI;
00334   ON_Interval ad = m_angle;
00335   ad.m_t[0] *= rtd;
00336   ad.m_t[1] *= rtd;
00337   return ad;
00338 }
00339 
00340 bool ON_Arc::SetAngleRadians( double a )
00341 {
00342   if ( a < 0.0 ) 
00343   {
00344     double a0 = m_angle.m_t[0];
00345     m_angle.Set(a0+a,a0);
00346     Reverse();
00347   }
00348   else
00349   {
00350     m_angle.m_t[1] = m_angle.m_t[0] + a;
00351   }
00352   return ( fabs(m_angle.Length()) <= 2.0*ON_PI ) ? true : false;
00353 }
00354 
00355 bool ON_Arc::SetAngleIntervalRadians( ON_Interval angle_in_radians )
00356 {
00357   bool rc = angle_in_radians.IsIncreasing() 
00358             && angle_in_radians.Length() < (1.0+ON_SQRT_EPSILON)*2.0*ON_PI;
00359   if (rc)
00360   {
00361     m_angle = angle_in_radians;
00362   }
00363   return rc;
00364 }
00365 
00366 bool ON_Arc::SetAngleDegrees( double a )
00367 {
00368   return SetAngleRadians( (a/180.0)*ON_PI );
00369 }
00370 
00371 bool ON_Arc::Trim( ON_Interval domain)
00372 {
00373   bool ok = false;
00374 
00375   if(domain[0]<domain[1] && domain[1]-domain[0]<=2.0 * ON_PI+ON_ZERO_TOLERANCE){
00376                 m_angle = domain;
00377     if (m_angle.Length() > 2.0*ON_PI) m_angle[1] = m_angle[0] + 2.0*ON_PI;
00378     ok = true;
00379   }
00380         return ok;
00381 }
00382 
00383 bool ON_ArcCurve::IsContinuous(
00384     ON::continuity c,
00385     double t, 
00386     int*,   // hint                - formal parameter intentionally ignored in this virtual function
00387     double, // point_tolerance     - formal parameter intentionally ignored in this virtual function
00388     double, // d1_tolerance        - formal parameter intentionally ignored in this virtual function
00389     double, // d2_tolerance        - formal parameter intentionally ignored in this virtual function
00390     double, // cos_angle_tolerance - formal parameter intentionally ignored in this virtual function
00391     double  // curvature_tolerance - formal parameter intentionally ignored in this virtual function
00392     ) const
00393 {
00394   // 20 March 2003 Dale Lear
00395   //      Added this override of IsContinuous() to
00396   //      speed queries and support the
00397   //      locus favors of ON::continuity.
00398 
00399   bool rc = true;
00400 
00401   if ( !IsClosed() )
00402   {
00403     switch(c)
00404     {
00405     case ON::unknown_continuity:
00406     case ON::C0_continuous:
00407     case ON::C1_continuous:
00408     case ON::C2_continuous:
00409     case ON::G1_continuous:
00410     case ON::G2_continuous:
00411     case ON::Cinfinity_continuous:
00412     case ON::Gsmooth_continuous:
00413       // rc = true;
00414       break;
00415 
00416     case ON::C0_locus_continuous:
00417     case ON::C1_locus_continuous:
00418     case ON::C2_locus_continuous:
00419     case ON::G1_locus_continuous:
00420     case ON::G2_locus_continuous:
00421       // open arc is locus discontinuous at end parameter.
00422       // By convention (see ON::continuity comments) it
00423       // is locus continuous at start parameter.
00424       if ( t >= Domain()[1] )
00425         rc = false;
00426       break;
00427     }
00428   }
00429 
00430   return rc;
00431 }
00432 
00433 
00434 
00435 bool ON_Arc::Reverse()
00436 {
00437   m_angle.Reverse();
00438   plane.yaxis = -plane.yaxis;
00439   plane.zaxis = -plane.zaxis;
00440   plane.UpdateEquation();
00441   return true;
00442 }
00443 
00444 double ON_Arc::Length() const
00445 {
00446   return fabs(AngleRadians()*radius);
00447 }
00448 
00449 double ON_Arc::SectorArea() const
00450 {
00451   return fabs(0.5*AngleRadians()*radius*radius);
00452 }
00453 
00454 ON_3dPoint ON_Arc::SectorAreaCentroid() const
00455 {
00456   double a = 0.5*fabs(AngleRadians());
00457   double d = (a > 0.0) ? sin(a)/a : 0.0;
00458   d *= 2.0*radius/3.0;
00459   a = 0.5*(m_angle[1]+m_angle[0]);
00460   return plane.PointAt(d*cos(a),d*sin(a));
00461 }
00462 
00463 double ON_Arc::SegmentArea() const
00464 {
00465   double a = fabs(AngleRadians());
00466   return (0.5*(a - sin(a))*radius*radius);
00467 }
00468 
00469 ON_3dPoint ON_Arc::SegmentAreaCentroid() const
00470 {
00471   double a = fabs(AngleRadians());
00472   double sin_halfa = sin(0.5*a);
00473   double d = 3.0*(a - sin(a));
00474   if ( d > 0.0 )
00475     d = (sin_halfa*sin_halfa*sin_halfa)/d;
00476   d *= 4.0*radius;
00477   a = 0.5*(m_angle[1]+m_angle[0]);
00478   return plane.PointAt(d*cos(a),d*sin(a));
00479 }
00480 
00481 
00482 /* moved to opennurbs_arccurve.cpp
00483 
00484 
00485 int ON_Arc::GetNurbForm( ON_NurbsCurve& nurbscurve ) const
00486 {
00487   int rc = 0;
00488   if ( IsValid() ) {
00489     if ( IsCircle() )
00490       rc = ON_Circle::GetNurbForm( nurbscurve );
00491     else {
00492       double a, b, c, t, dt, angle;
00493       int span_count, i;
00494       angle = m_angle.Length();
00495       if (angle <= 0.5*ON_PI + ON_ZERO_TOLERANCE) {
00496                     span_count = 1;
00497         dt = 0.5;
00498       }
00499       else if (angle <= ON_PI + ON_ZERO_TOLERANCE) {
00500                     span_count = 2;
00501                   angle *= 0.5;
00502         dt = 0.25;
00503       }
00504       else if (angle <= 1.5*ON_PI + ON_ZERO_TOLERANCE) {
00505                     span_count = 3;
00506                   angle /= 3.0;
00507         dt = 1.0/6.0;
00508       }
00509       else {
00510                     span_count = 4;
00511                   angle *= 0.25;
00512         dt = 0.125;
00513       }
00514       nurbscurve.Create( 3, true, 3, 2*span_count+1 );
00515       ON_4dPoint* CV = (ON_4dPoint*)nurbscurve.m_cv;
00516       t = m_angle[0];
00517       for ( i = 0; i < span_count; i++ ) {
00518         nurbscurve.m_knot[2*i] = t;
00519         nurbscurve.m_knot[2*i+1] = t;
00520         CV[2*i] = PointAt(m_angle.ParameterAt(t));
00521         t += dt;
00522         CV[2*i+1] = PointAt(m_angle.ParameterAt(t));
00523         t += dt;
00524       }
00525 
00526       span_count *= 2;
00527       t = m_angle[1];
00528       CV[span_count] = PointAt(t);
00529       nurbscurve.m_knot[span_count] = t;
00530       nurbscurve.m_knot[span_count+1] = t;
00531 
00532             a = cos(0.5*angle);
00533             b = a - 1.0;
00534             c = radius*angle;
00535 
00536             for (i = 1; i < span_count; i += 2) {
00537                     CV[i].x +=  b * plane.origin.x;
00538                     CV[i].y +=  b * plane.origin.y;
00539                     CV[i].z +=  b * plane.origin.z;
00540                     CV[i].w = a;
00541             }
00542       
00543       //for ( i = 1; i < span_count; i += 2 ) {
00544       //  t = CV[i].w;
00545       //  c = 1.0/t;
00546       //  a = CV[i].x*c; b = ArcDeFuzz(a); if ( a != b ) CV[i].x = b*t;
00547       //  a = CV[i].y*c; b = ArcDeFuzz(a); if ( a != b ) CV[i].y = b*t;
00548       //  a = CV[i].z*c; b = ArcDeFuzz(a); if ( a != b ) CV[i].z = b*t;
00549       //}
00550     }
00551     rc = 2;
00552   }
00553         return rc;
00554 }
00555 */
00556 
00557 // returns parameters of point on arc that is closest to given point
00558 bool ON_Arc::ClosestPointTo( 
00559        const ON_3dPoint& pt, 
00560        double* t
00561        ) const
00562 {
00563   /*
00564   double tt, a;
00565   if ( !t )
00566     t =&tt;
00567   ON_BOOL32 rc = ON_Circle::ClosestPointTo(pt,t);
00568   if (rc) {
00569     if ( *t < m_angle[0] ) {
00570       a = 0.5*(m_angle[0] + m_angle[1] - 2.0*ON_PI);
00571       if ( *t < a )
00572         *t = m_angle[1];
00573       else 
00574         *t = m_angle[0];
00575     }
00576     else if ( *t > m_angle[1] ) {
00577       a = 0.5*(m_angle[0] + m_angle[1] + 2.0*ON_PI);
00578       if ( *t > a )
00579         *t = m_angle[0];
00580       else 
00581         *t = m_angle[1];
00582     }
00583   }
00584   */
00585   double s;
00586   double twopi = 2.0*ON_PI;
00587   bool rc = ON_Circle::ClosestPointTo(pt,&s);
00588   if (rc){
00589     s -= m_angle[0];
00590     while (s < 0.0) s += twopi;
00591 
00592                 // Greg Arden April 14 2003. Changed test from ">" to ">=" this ensures that
00593                 // closest point to a circle at the seam will return the least parameter value.
00594     while (s >= twopi) s -= twopi;
00595 
00596     double s1 = m_angle.Length();
00597 
00598     if (s < 0.0) s = 0.0;//shouldn't happen
00599     if (s > s1){
00600       if (s > 0.5*s1 + ON_PI)
00601         s = 0.0;
00602       else
00603         s = s1;
00604     }
00605 
00606     if (t)
00607       *t = m_angle[0] + s;
00608   }
00609 
00610       
00611   return rc;
00612 }
00613 
00614 // returns point on circle that is arc to given point
00615 ON_3dPoint ON_Arc::ClosestPointTo( 
00616        const ON_3dPoint& pt
00617        ) const
00618 {
00619   double t = m_angle[0];
00620   ClosestPointTo( pt, &t );
00621   return PointAt(t);
00622 }
00623 


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