opennurbs_curveonsurface.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_OBJECT_IMPLEMENT(ON_CurveOnSurface,ON_Curve,"4ED7D4D8-E947-11d3-BFE5-0010830122F0");
00020 
00021 ON_CurveOnSurface::ON_CurveOnSurface() : m_c2(0), m_c3(0), m_s(0)
00022 {}
00023 
00024 ON_CurveOnSurface::ON_CurveOnSurface( ON_Curve* c2, ON_Curve* c3, ON_Surface* s ) 
00025                  : m_c2(c2), m_c3(c3), m_s(s)
00026 {}
00027 
00028 ON_CurveOnSurface::ON_CurveOnSurface( const ON_CurveOnSurface& src ) : m_c2(0), m_c3(0), m_s(0)
00029 {
00030   *this = src;
00031 }
00032 
00033 unsigned int ON_CurveOnSurface::SizeOf() const
00034 {
00035   unsigned int sz = ON_Curve::SizeOf();
00036   sz += sizeof(*this) - sizeof(ON_Curve);
00037   if ( m_c2 )
00038     sz += m_c2->SizeOf();
00039   if ( m_c3 )
00040     sz += m_c3->SizeOf();
00041   if ( m_s )
00042     sz += m_s->SizeOf();
00043   return sz;
00044 }
00045 
00046 ON_CurveOnSurface& ON_CurveOnSurface::operator=( const ON_CurveOnSurface& src )
00047 {
00048   if ( this != &src ) {
00049     ON_Curve::operator=(src);
00050     if ( m_c2 ) {
00051       delete m_c2;
00052       m_c2 = 0;
00053     }
00054     if ( m_c3 ) {
00055       delete m_c3;
00056       m_c3 = 0;
00057     }
00058     if ( m_s ) {
00059       delete m_s;
00060       m_s = 0;
00061     }
00062     if ( ON_Curve::Cast(src.m_c2) ) {
00063       m_c2 = ON_Curve::Cast(src.m_c2->Duplicate());
00064     }
00065     if ( ON_Curve::Cast(src.m_c3) ) {
00066       m_c3 = ON_Curve::Cast(src.m_c3->Duplicate());
00067     }
00068     if ( ON_Surface::Cast(src.m_s) ) {
00069       m_s = ON_Surface::Cast(src.m_s->Duplicate());
00070     }
00071   }
00072   return *this;
00073 }
00074 
00075 ON_CurveOnSurface::~ON_CurveOnSurface()
00076 {
00077   if ( m_c2 ) {
00078     delete m_c2;
00079     m_c2 = 0;
00080   }
00081   if ( m_c3 ) {
00082     delete m_c3;
00083     m_c3 = 0;
00084   }
00085   if ( m_s ) {
00086     delete m_s;
00087     m_s = 0;
00088   }
00089 }
00090 
00091 ON_BOOL32
00092 ON_CurveOnSurface::IsValid( ON_TextLog* text_log ) const
00093 {
00094   if ( !m_c2 )
00095     return false;
00096   if ( !m_s )
00097     return false;
00098   if ( !m_c2->IsValid() )
00099     return false;
00100   if ( m_c2->Dimension() != 2 ) {
00101     ON_ERROR("ON_CurveOnSurface::IsValid() m_c2 is not 2d.");
00102     return false;
00103   }
00104   if ( !m_s->IsValid() )
00105     return false;
00106   if ( m_c3 ) {
00107     if ( !m_c3->IsValid() )
00108       return false;
00109     if ( m_c3->Dimension() != m_s->Dimension() ) {
00110       ON_ERROR("ON_CurveOnSurface::IsValid() m_c3 and m_s have different dimensions.");
00111       return false;
00112     }
00113   }
00114 
00115   return true;
00116 }
00117 
00118 void
00119 ON_CurveOnSurface::Dump( ON_TextLog& dump ) const
00120 {
00121   dump.Print("ON_CurveOnSurface \n");
00122 }
00123 
00124 ON_BOOL32 
00125 ON_CurveOnSurface::Write(
00126        ON_BinaryArchive& file // open binary file
00127      ) const
00128 {
00129   ON_BOOL32 rc = IsValid();
00130   if (rc)
00131     rc = file.WriteObject(*m_c2);
00132   if (rc)
00133     rc = file.WriteInt( m_c3?1:0 );
00134   if ( rc && m_c3 )
00135     rc = file.WriteObject(*m_c3);
00136   if (rc)
00137     rc = file.WriteObject(*m_s);
00138   return rc;
00139 }
00140 
00141 ON_BOOL32 
00142 ON_CurveOnSurface::Read(
00143        ON_BinaryArchive& file // open binary file
00144      )
00145 {
00146   delete m_c2; 
00147   delete m_c3; 
00148   m_c2 = 0;
00149   m_c3 = 0;
00150   delete m_s;
00151   m_s = 0;
00152 
00153   ON_Object *o=0;
00154   ON_BOOL32 rc = file.ReadObject(&o);
00155   if (rc && o) {
00156     m_c2 = ON_Curve::Cast(o);
00157     if ( !m_c2 ) {
00158       delete o;
00159     } rc = false;
00160   }
00161 
00162   o = 0;
00163 
00164   ON_BOOL32 bHasC3 = 0;
00165   rc = file.ReadInt( &bHasC3 );
00166   if ( rc && bHasC3 ) {
00167     if (rc)
00168       rc = file.ReadObject(&o);
00169     if ( rc && o ) {
00170       m_c2 = ON_Curve::Cast(o);
00171       if ( !m_c2 ) {
00172         delete o;
00173       } rc = false;
00174     }
00175   }
00176 
00177   o = 0;
00178 
00179   if (rc)
00180     rc = file.ReadObject(&o);
00181   if (rc&&o) {
00182     m_s = ON_Surface::Cast(o);
00183     if ( !m_s ) {
00184       delete o;
00185       rc = false;
00186     }
00187   }
00188 
00189   return rc;
00190 }
00191 
00192 int 
00193 ON_CurveOnSurface::Dimension() const
00194 {
00195   return ( m_s ) ? m_s->Dimension() : false;
00196 }
00197 
00198 ON_BOOL32 
00199 ON_CurveOnSurface::GetBBox( // returns true if successful
00200          double* boxmin,    // minimum
00201          double* boxmax,    // maximum
00202          ON_BOOL32 bGrowBox
00203          ) const
00204 {
00205   return ( m_s ) ? m_s->GetBBox(boxmin,boxmax,bGrowBox) : false;
00206 }
00207 
00208 ON_BOOL32
00209 ON_CurveOnSurface::Transform( const ON_Xform& xform )
00210 {
00211   TransformUserData(xform);
00212         DestroyCurveTree();
00213   return ( m_s ) ? m_s->Transform(xform) : false;
00214 }
00215 
00216 ON_BOOL32
00217 ON_CurveOnSurface::SwapCoordinates( int i, int j )
00218 {
00219   return ( m_s ) ? m_s->SwapCoordinates(i,j) : false;
00220 }
00221 
00222 ON_Interval ON_CurveOnSurface::Domain() const
00223 {
00224   ON_Interval d;
00225   if ( m_c2 )
00226     d = m_c2->Domain();
00227   return d;
00228 }
00229 
00230 int ON_CurveOnSurface::SpanCount() const
00231 {
00232   return m_c2 ? m_c2->SpanCount() : 0;
00233 }
00234 
00235 ON_BOOL32 ON_CurveOnSurface::GetSpanVector( // span "knots" 
00236        double* s // array of length SpanCount() + 1 
00237        ) const
00238 {
00239   return m_c2 ? m_c2->GetSpanVector(s) : false;
00240 }
00241 
00242 int ON_CurveOnSurface::Degree() const
00243 {
00244   return m_c2 ? m_c2->Degree() : 0;
00245 }
00246 
00247 ON_BOOL32 
00248 ON_CurveOnSurface::GetParameterTolerance(
00249          double t,  // t = parameter in domain
00250          double* tminus, // tminus
00251          double* tplus   // tplus
00252          ) const
00253 {
00254   return (m_c2) ? m_c2->GetParameterTolerance(t,tminus,tplus) : false;
00255 }
00256 
00257 
00258 ON_BOOL32
00259 ON_CurveOnSurface::IsLinear( // true if curve locus is a line segment
00260       double tolerance // tolerance to use when checking linearity
00261       ) const
00262 {
00263   ON_BOOL32 rc = (m_c2&&ON_PlaneSurface::Cast(m_s)) ? (ON_PlaneSurface::Cast(m_s) && m_c2->IsLinear(tolerance)) : false;
00264   if ( rc ) {
00265     // TODO: rc = m_s->IsPlanar(tolerance)
00266   }
00267   return rc;
00268 }
00269 
00270 ON_BOOL32
00271 ON_CurveOnSurface::IsArc( // true if curve locus in an arc or circle
00272       const ON_Plane* plane, // if not NULL, test is performed in this plane
00273       ON_Arc* arc,         // if not NULL and true is returned, then arc
00274                               // arc parameters are filled in
00275       double tolerance // tolerance to use when checking linearity
00276       ) const
00277 {
00278   return (m_c2&&ON_PlaneSurface::Cast(m_s)) ? m_c2->IsArc(plane,arc,tolerance) : false;
00279 }
00280 
00281 ON_BOOL32
00282 ON_CurveOnSurface::IsPlanar(
00283       ON_Plane* plane, // if not NULL and true is returned, then plane parameters
00284                          // are filled in
00285       double tolerance // tolerance to use when checking linearity
00286       ) const
00287 {
00288   return ( ON_PlaneSurface::Cast(m_s) ) ? true : false;
00289 }
00290 
00291 ON_BOOL32
00292 ON_CurveOnSurface::IsInPlane(
00293       const ON_Plane& plane, // plane to test
00294       double tolerance // tolerance to use when checking linearity
00295       ) const
00296 {
00297   return false;
00298 }
00299 
00300 ON_BOOL32 
00301 ON_CurveOnSurface::IsClosed() const
00302 {
00303   ON_BOOL32 rc = ( m_c2 && m_s ) ? m_c2->IsClosed() : false;
00304   if ( !rc )
00305     rc = ON_Curve::IsClosed();
00306   return rc;
00307 }
00308 
00309 ON_BOOL32 
00310 ON_CurveOnSurface::IsPeriodic() const
00311 {
00312   return ( m_c2 && m_s ) ? m_c2->IsPeriodic() : false;
00313 }
00314 
00315 ON_BOOL32
00316 ON_CurveOnSurface::Reverse()
00317 {
00318   ON_BOOL32 rc = ( m_c2 ) ? m_c2->Reverse() : false;
00319   if ( rc && m_c3 ) rc = m_c3->Reverse();
00320         DestroyCurveTree();
00321   return rc;
00322 }
00323 
00324 ON_BOOL32 
00325 ON_CurveOnSurface::Evaluate( // returns false if unable to evaluate
00326        double t,       // evaluation parameter
00327        int der_count,  // number of derivatives (>=0)
00328        int v_stride,   // v[] array stride (>=Dimension())
00329        double* v,      // v[] array of length stride*(ndir+1)
00330        int side,       // optional - determines which side to evaluate from
00331                        //         0 = default
00332                        //      <  0 to evaluate from below, 
00333                        //      >  0 to evaluate from above
00334        int* hint       // optional - evaluation hint (int) used to speed
00335                        //            repeated evaluations
00336        ) const
00337 {
00338   ON_3dVector c[5];
00339   ON_3dVector s[15], d;
00340 
00341   const int dim = Dimension();
00342   ON_BOOL32 rc = (dim > 0 && dim <= 3 ) ? true : false;
00343   if ( rc ) {
00344     int chint=0, shint[2]={0,0};
00345     if(hint) {
00346       chint = (*hint)&0xFFF;
00347       shint[0] = (*hint)>>16;
00348       shint[1] = shint[0]>>8;
00349       shint[0] &= 0xFF;
00350     }
00351 
00352     rc = ( m_c2&&m_s ) ? m_c2->Evaluate(t,der_count,3,c[0],side,&chint) : false;
00353     if (rc) {
00354       side = 0;
00355       if ( der_count>0 ) {
00356         if ( c[1].x >= 0.0 ) {
00357           side = ( c[1].y >= 0.0 ) ? 1 : 4;
00358         }
00359         else {
00360           side = ( c[1].y >= 0.0 ) ? 2 : 3;
00361         }
00362       }
00363       rc = m_s->Evaluate( c[0].x, c[0].y, der_count, 3, s[0], side, shint );
00364       if ( rc ) {
00365         if ( hint ) {
00366           *hint = (chint&0xFFFF) | ((shint[0]&0xFF)<<16) | ((shint[1]&0xFF)<<24);
00367         }
00368 
00369         v[0] = s[0].x;
00370         if ( dim > 1 ) v[1] = s[0].y;
00371         if ( dim > 2 ) v[2] = s[0].z;
00372         v += v_stride;
00373 
00374         if (der_count >= 1 ) {
00375           const double du = c[1].x;
00376           const double dv = c[1].y;
00377           d = du*s[1] + dv*s[2];
00378           v[0] = d.x;
00379           if ( dim > 1 ) v[1] = d.y;
00380           if ( dim > 2 ) v[2] = d.z;
00381           v += v_stride;
00382           if ( der_count >= 2 ) {
00383             const double ddu = c[2].x;
00384             const double ddv = c[2].y;
00385             d = ddu*s[1] + ddv*s[2] + du*du*s[3] + 2.0*du*dv*s[4] + dv*dv*s[5];
00386             v[0] = d.x;
00387             if ( dim > 1 ) v[1] = d.y;
00388             if ( dim > 2 ) v[2] = d.z;
00389             v += v_stride;
00390             if ( der_count >= 3 ) {
00391               const double dddu = c[3].x;
00392               const double dddv = c[3].y;
00393               d = dddu*s[1] + dddv*s[2]
00394                 + 3.0*du*ddu*s[3] + 3.0*(ddu*dv + du*ddv)*s[4] + 3.0*dv*ddv*s[5]
00395                 + du*du*du*s[6] + 3.0*du*du*dv*s[7] + 3.0*du*dv*dv*s[8] + dv*dv*dv*s[9];
00396               v[0] = d.x;
00397               if ( dim > 1 ) v[1] = d.y;
00398               if ( dim > 2 ) v[2] = d.z;
00399               v += v_stride;
00400               if ( der_count >= 4 ) {
00401                 int n;
00402                 for ( n = 4; n <= der_count; n++ ) {
00403                   v[0] = 0.0;
00404                   if ( dim > 1 ) v[1] = 0.0;
00405                   if ( dim > 2 ) v[2] = 0.0;
00406                   v += v_stride;
00407                   rc = false; // TODO - generic chain rule 
00408                 }
00409               }
00410             }
00411           }
00412         }
00413       }
00414     }
00415   }
00416   return rc;
00417 }
00418 
00419 
00420 int 
00421 ON_CurveOnSurface::GetNurbForm( // returns 0: unable to create NURBS representation
00422                  //            with desired accuracy.
00423                  //         1: success - returned NURBS parameterization
00424                  //            matches the curve's to wthe desired accuracy
00425                  //         2: success - returned NURBS point locus matches
00426                  //            the curve's to the desired accuracy but, on
00427                  //            the interior of the curve's domain, the 
00428                  //            curve's parameterization and the NURBS
00429                  //            parameterization may not match to the 
00430                  //            desired accuracy.
00431       ON_NurbsCurve& nurbs,
00432       double tolerance,  // (>=0)
00433       const ON_Interval* subdomain  // OPTIONAL subdomain of 2d curve
00434       ) const
00435 {
00436   ON_ERROR("TODO - finish ON_CurveOnSurface::GetNurbForm().");
00437   return false;
00438 }
00439 


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