opennurbs_nurbssurface.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_NurbsSurface,ON_Surface,"4ED7D4DE-E947-11d3-BFE5-0010830122F0");
00020 
00021 
00022 ON_NurbsSurface* ON_NurbsSurface::New()
00023 {
00024   // static function replaces new ON_NurbsSurface();
00025   return new ON_NurbsSurface();
00026 }
00027 
00028 ON_NurbsSurface* ON_NurbsSurface::New(
00029         const ON_NurbsSurface& nurbs_surface
00030         )
00031 {
00032   // static function replaces new ON_NurbsSurface(const ON_NurbsSurface& nurbs_surface);
00033   return new ON_NurbsSurface(nurbs_surface);
00034 }
00035 
00036 ON_NurbsSurface* ON_NurbsSurface::New(
00037         const ON_BezierSurface& bezier_surface
00038         )
00039 {
00040   // static function replaces new ON_NurbsSurface(const ON_BezierSurface& bezier_surface);
00041   return new ON_NurbsSurface(bezier_surface);
00042 }
00043 
00044 ON_NurbsSurface* ON_NurbsSurface::New(
00045         int dimension,
00046         ON_BOOL32 bIsRational,
00047         int order0,
00048         int order1,
00049         int cv_count0,
00050         int cv_count1
00051         )
00052 {
00053   // static function replaces new ON_NurbsSurface(dim, is_rat, order0, ..., cv_count1 );
00054   return new ON_NurbsSurface(dimension,bIsRational,order0,order1,cv_count0,cv_count1);
00055 }
00056 
00057 ON_NurbsSurface::ON_NurbsSurface()
00058 {
00059   ON__SET__THIS__PTR(m_s_ON_NurbsSurface_ptr);
00060   Initialize();
00061 }
00062 
00063 ON_NurbsSurface::ON_NurbsSurface( const ON_NurbsSurface& src )
00064 {
00065   ON__SET__THIS__PTR(m_s_ON_NurbsSurface_ptr);
00066   Initialize();
00067   *this = src;
00068 }
00069 
00070 ON_NurbsSurface::ON_NurbsSurface( const ON_BezierSurface& bezier_surface )
00071 {
00072   ON__SET__THIS__PTR(m_s_ON_NurbsSurface_ptr);
00073   Initialize();
00074   *this = bezier_surface;
00075 }
00076 
00077 ON_NurbsSurface::ON_NurbsSurface(
00078         int dim,      // dimension (>= 1)
00079         ON_BOOL32 is_rat,  // true to make a rational NURBS
00080         int order0,    // order (>= 2)
00081         int order1,    // order (>= 2)
00082         int cv_count0,  // cv count0 (>= order0)
00083         int cv_count1   // cv count1 (>= order1)
00084         )
00085 {
00086   ON__SET__THIS__PTR(m_s_ON_NurbsSurface_ptr);
00087   Initialize();
00088   Create( dim, is_rat, order0, order1, cv_count0, cv_count1 );
00089 }
00090 
00091 ON_NurbsSurface::~ON_NurbsSurface()
00092 {
00093   Destroy();
00094 }
00095 
00096 
00097 unsigned int ON_NurbsSurface::SizeOf() const
00098 {
00099   unsigned int sz = ON_Surface::SizeOf();
00100   sz += (sizeof(*this) - sizeof(ON_Surface));
00101   sz += m_knot_capacity[0]*sizeof(*m_knot[0]);
00102   sz += m_knot_capacity[1]*sizeof(*m_knot[1]);
00103   sz += m_cv_capacity*sizeof(*m_cv);
00104   return sz;
00105 }
00106 
00107 ON__UINT32 ON_NurbsSurface::DataCRC(ON__UINT32 current_remainder) const
00108 {
00109   current_remainder = ON_CRC32(current_remainder,sizeof(m_dim),&m_dim);
00110   current_remainder = ON_CRC32(current_remainder,sizeof(m_is_rat),&m_is_rat);
00111   current_remainder = ON_CRC32(current_remainder,2*sizeof(m_order[0]),&m_order[0]);
00112   current_remainder = ON_CRC32(current_remainder,2*sizeof(m_cv_count[0]),&m_cv_count[0]);
00113   if (   m_cv_count[0] > 0 && m_cv_count[1] > 0 
00114       && m_cv_stride[0] > 0 && m_cv_stride[1] > 0 
00115       && m_cv )
00116   {
00117     size_t sizeof_cv = CVSize()*sizeof(m_cv[0]);
00118     const double* cv = m_cv;
00119     int i, j;
00120     for ( i = 0; i < m_cv_count[0]; i++ )
00121     {
00122       cv = CV(i,0);
00123       for ( j = 0; j < m_cv_count[1]; j++ )
00124       {
00125         current_remainder = ON_CRC32(current_remainder,sizeof_cv,cv);
00126         cv += m_cv_stride[1];
00127       }
00128     }
00129   }
00130   current_remainder = ON_CRC32(current_remainder,KnotCount(0)*sizeof(m_knot[0][0]),m_knot[0]);
00131   current_remainder = ON_CRC32(current_remainder,KnotCount(1)*sizeof(m_knot[1][0]),m_knot[1]);
00132 
00133   return current_remainder;
00134 }
00135 
00136 
00137 ON_BOOL32 ON_NurbsSurface::SetDomain( 
00138             int dir, // 0 sets first parameter's domain, 1 gets second parameter's domain
00139             double t0, 
00140             double t1
00141             )
00142 {
00143   bool rc = false;
00144   if ( m_order[dir] >= 2 && m_cv_count[dir] >= m_order[dir] && m_knot && t0 < t1 ) {
00145     const double k0 = m_knot[dir][m_order[dir]-2];
00146     const double k1 = m_knot[dir][m_cv_count[dir]-1];
00147     if ( k0 == t0 && k1 == t1 )
00148       rc = true;
00149     else if ( k0 < k1 ) {
00150       const double d = (t1-t0)/(k1-k0);
00151       const double km = 0.5*(k0+k1);
00152       const int knot_count = KnotCount(dir);
00153       int i;
00154       for ( i = 0; i < knot_count; i++ ) {
00155         if ( m_knot[dir][i] <= km ) {
00156           m_knot[dir][i] = (m_knot[dir][i] - k0)*d + t0;
00157         }
00158         else {
00159           m_knot[dir][i] = (m_knot[dir][i] - k1)*d + t1;
00160         }
00161       }
00162                         rc = true;
00163       DestroySurfaceTree();
00164     }
00165   }
00166   return rc;
00167 
00168 }
00169 
00170 
00171 int ON_NurbsSurface::Dimension() const
00172 {
00173   return m_dim;
00174 }
00175 
00176 bool ON_NurbsSurface::IsRational() const
00177 {
00178   return m_is_rat?true:false;
00179 }
00180 
00181 int ON_NurbsSurface::CVSize() const
00182 {
00183   return (m_is_rat) ? m_dim+1 : m_dim;
00184 }
00185 
00186 int ON_NurbsSurface::Order( int dir ) const
00187 {
00188   return m_order[dir?1:0];
00189 }
00190 
00191 int ON_NurbsSurface::Degree( int dir ) const
00192 {
00193   return (m_order[dir?1:0]>=2) ? m_order[dir?1:0]-1 : 0;
00194 }
00195 
00196 int ON_NurbsSurface::CVCount( int dir ) const
00197 {
00198   return m_cv_count[dir?1:0];
00199 }
00200 
00201 int ON_NurbsSurface::CVCount( void ) const
00202 {
00203   return m_cv_count[0]*m_cv_count[1];
00204 }
00205 
00206 int ON_NurbsSurface::KnotCount( int dir ) const
00207 {
00208   return ON_KnotCount( m_order[dir?1:0], m_cv_count[dir?1:0] );
00209 }
00210 
00211 double* ON_NurbsSurface::CV( int i, int j ) const
00212 {
00213   return (m_cv) ? (m_cv + i*m_cv_stride[0] + j*m_cv_stride[1]) : NULL;
00214 }
00215 
00216 ON::point_style ON_NurbsSurface::CVStyle() const
00217 {
00218   return m_is_rat ? ON::homogeneous_rational : ON::not_rational;
00219 }
00220 
00221 
00222 double ON_NurbsSurface::Weight( int i, int j ) const
00223 {
00224   return (m_cv && m_is_rat) ? m_cv[i*m_cv_stride[0] + j*m_cv_stride[1] + m_dim] : 1.0;
00225 }
00226 
00227 
00228 double ON_NurbsSurface::Knot( int dir, int i ) const
00229 {
00230   return (m_knot[dir?1:0]) ? m_knot[dir?1:0][i] : 0.0;
00231 }
00232 
00233 int ON_NurbsSurface::KnotMultiplicity( int dir, int i ) const
00234 {
00235   dir = dir?1:0;
00236   return ON_KnotMultiplicity( m_order[dir], m_cv_count[dir], m_knot[dir], i );
00237 }
00238 
00239 const double* ON_NurbsSurface::Knot( int dir ) const
00240 {
00241   return m_knot[dir?1:0];
00242 }
00243 
00244 bool ON_NurbsSurface::MakeClampedUniformKnotVector( 
00245   int dir,
00246   double delta
00247   )
00248 {
00249   if ( dir < 0 || dir > 1 )
00250     return false;
00251         DestroySurfaceTree();
00252   ReserveKnotCapacity( dir, ON_KnotCount( m_order[dir], m_cv_count[dir] ) );
00253   return ON_MakeClampedUniformKnotVector( m_order[dir], m_cv_count[dir], m_knot[dir], delta );
00254 }
00255 
00256 bool ON_NurbsSurface::MakePeriodicUniformKnotVector( 
00257   int dir,
00258   double delta
00259   )
00260 {
00261   if ( dir < 0 || dir > 1 )
00262     return false;
00263         DestroySurfaceTree();
00264   ReserveKnotCapacity( dir, ON_KnotCount( m_order[dir], m_cv_count[dir] ) );
00265   return ON_MakePeriodicUniformKnotVector( m_order[dir], m_cv_count[dir], m_knot[dir], delta );
00266 }
00267 
00268 
00269 double ON_NurbsSurface::SuperfluousKnot( int dir, int end ) const
00270   { return(m_knot[dir?1:0]) ? ON_SuperfluousKnot(m_order[dir?1:0],m_cv_count[dir?1:0],m_knot[dir?1:0],end) : 0.0;}
00271 
00272 ON_BOOL32 ON_NurbsSurface::Create(
00273         int dim,      // dimension (>= 1)
00274         ON_BOOL32 is_rat,  // true to make a rational NURBS
00275         int order0,    // order (>= 2)
00276         int order1,    // order (>= 2)
00277         int cv_count0,  // cv count0 (>= order0)
00278         int cv_count1   // cv count1 (>= order1)
00279         )
00280 {
00281   DestroySurfaceTree();
00282   if ( dim < 1 )
00283     return false;
00284   if ( order0 < 2 )
00285     return false;
00286   if ( order1 < 2 )
00287     return false;
00288   if ( cv_count0 < order0 )
00289     return false;
00290   if ( cv_count1 < order1 )
00291     return false;
00292   m_dim = dim;
00293   m_is_rat = (is_rat) ? true : false;
00294   m_order[0] = order0;
00295   m_order[1] = order1;
00296   m_cv_count[0] = cv_count0;
00297   m_cv_count[1] = cv_count1;
00298   m_cv_stride[1] = (m_is_rat) ? m_dim+1 : m_dim;
00299   m_cv_stride[0] = m_cv_stride[1]*m_cv_count[1];
00300   ON_BOOL32 rc = ReserveKnotCapacity( 0, KnotCount(0) );
00301   if ( !ReserveKnotCapacity( 1, KnotCount(1) ) )
00302     rc = false;
00303   if ( !ReserveCVCapacity( m_cv_count[0]*m_cv_count[1]*m_cv_stride[1] ) )
00304     rc = false;
00305   return rc;
00306 }
00307 
00308 void ON_NurbsSurface::Destroy()
00309 {
00310   double* cv = ( m_cv && m_cv_capacity ) ? m_cv : NULL;
00311   double* knot0 = ( m_knot[0] && m_knot_capacity[0] ) ? m_knot[0] : NULL;
00312   double* knot1 = ( m_knot[1] && m_knot_capacity[1] ) ? m_knot[1] : NULL;
00313   Initialize();
00314   if ( cv )
00315     onfree(cv);
00316   if ( knot0 )
00317     onfree(knot0);
00318   if ( knot1 )
00319     onfree(knot1);
00320 }
00321 
00322 void ON_NurbsSurface::EmergencyDestroy()
00323 {
00324   Initialize();
00325 }
00326 
00327 
00328 void ON_NurbsSurface::Initialize()
00329 {
00330   m_dim = 0;
00331   m_is_rat = 0;
00332   m_order[0] = 0;
00333   m_order[1] = 0;
00334   m_cv_count[0] = 0;
00335   m_cv_count[1] = 0;
00336   m_knot_capacity[0] = 0;
00337   m_knot_capacity[1] = 0;
00338   m_knot[0] = 0;
00339   m_knot[1] = 0;
00340   m_cv_stride[0] = 0;
00341   m_cv_stride[1] = 0;
00342   m_cv_capacity = 0;
00343   m_cv = 0;
00344 }
00345 
00346 
00347 
00348 ON_BOOL32 ON_NurbsSurface::ReserveKnotCapacity( int dir, int capacity )
00349 {
00350   if (dir)
00351     dir = 1;
00352   if ( m_knot_capacity[dir] < capacity ) {
00353     if ( m_knot[dir] ) {
00354       if ( m_knot_capacity[dir] ) {
00355         m_knot[dir] = (double*)onrealloc( m_knot[dir], capacity*sizeof(*m_knot[dir]) );
00356         m_knot_capacity[dir] = (m_knot[dir]) ? capacity : 0;
00357       }
00358       // else user supplied m_knot[] array
00359     }
00360     else {
00361       m_knot[dir] = (double*)onmalloc( capacity*sizeof(*m_knot[dir]) );
00362       m_knot_capacity[dir] = (m_knot[dir]) ? capacity : 0;
00363     }
00364   }
00365   return ( m_knot[dir] ) ? true : false;
00366 }
00367 
00368 ON_BOOL32 ON_NurbsSurface::ReserveCVCapacity( int capacity )
00369 {
00370   if ( m_cv_capacity < capacity ) {
00371     if ( m_cv ) {
00372       if ( m_cv_capacity ) {
00373         m_cv = (double*)onrealloc( m_cv, capacity*sizeof(*m_cv) );
00374         m_cv_capacity = (m_cv) ? capacity : 0;
00375       }
00376       // else user supplied m_cv[] array
00377     }
00378     else {
00379       m_cv = (double*)onmalloc( capacity*sizeof(*m_cv) );
00380       m_cv_capacity = (m_cv) ? capacity : 0;
00381     }
00382   }
00383   return ( m_cv ) ? true : false;
00384 }
00385 
00386 static void ON_NurbsSurfaceCopyHelper( const ON_NurbsSurface& src, ON_NurbsSurface& dest )
00387 {
00388   dest.m_dim          = src.m_dim;
00389   dest.m_is_rat       = src.m_is_rat;
00390   dest.m_order[0]     = src.m_order[0];
00391   dest.m_order[1]     = src.m_order[1];
00392   dest.m_cv_count[0]  = src.m_cv_count[0];
00393   dest.m_cv_count[1]  = src.m_cv_count[1];
00394   dest.m_cv_stride[1] = dest.m_is_rat ? dest.m_dim+1 : dest.m_dim;
00395   dest.m_cv_stride[0] = dest.m_cv_count[1]*dest.m_cv_stride[1];
00396   if ( src.m_knot[0] ) 
00397   {
00398     // copy knot array
00399     dest.ReserveKnotCapacity( 0, dest.KnotCount(0) );
00400     memcpy( dest.m_knot[0], src.m_knot[0], dest.KnotCount(0)*sizeof(*dest.m_knot[0]) );
00401   }
00402   if ( src.m_knot[1] ) 
00403   {
00404     // copy knot array
00405     dest.ReserveKnotCapacity( 1, dest.KnotCount(1) );
00406     memcpy( dest.m_knot[1], src.m_knot[1], dest.KnotCount(1)*sizeof(*dest.m_knot[1]) );
00407   }
00408   if ( src.m_cv ) 
00409   {
00410     // copy cv array
00411     dest.ReserveCVCapacity( dest.m_cv_count[0]*dest.m_cv_count[1]*dest.m_cv_stride[1] );
00412     const int dst_cv_size = dest.CVSize()*sizeof(*dest.m_cv);
00413     const int src_stride[2] = {src.m_cv_stride[0],src.m_cv_stride[1]};
00414     if ( src_stride[0] == dest.m_cv_stride[0] && src_stride[1] == dest.m_cv_stride[1] ) 
00415     {
00416       memcpy( dest.m_cv, src.m_cv, dest.m_cv_count[0]*dest.m_cv_count[1]*dest.m_cv_stride[1]*sizeof(*dest.m_cv) );
00417     }
00418     else 
00419     {
00420       const double *src_cv;
00421       double *dst_cv = dest.m_cv;
00422       int i, j;
00423       for ( i = 0; i < dest.m_cv_count[0]; i++ ) 
00424       {
00425         src_cv = src.CV(i,0);
00426         for ( j = 0; j < dest.m_cv_count[1]; j++ ) 
00427         {
00428           memcpy( dst_cv, src_cv, dst_cv_size );
00429           dst_cv += dest.m_cv_stride[1];
00430           src_cv += src_stride[1];
00431         }
00432       }
00433     }
00434   }
00435 }
00436 
00437 
00438 ON_NurbsSurface& ON_NurbsSurface::operator=( const ON_NurbsSurface& src )
00439 {
00440   if ( this != &src ) 
00441   {
00442     ON_Surface::operator=(src);
00443     ON_NurbsSurfaceCopyHelper(src,*this);
00444   }
00445   return *this;
00446 }
00447 
00448 ON_NurbsSurface& ON_NurbsSurface::operator=( const ON_BezierSurface& bezier_surface )
00449 {
00450   int i, j;
00451   DestroySurfaceTree();
00452 
00453   m_dim = bezier_surface.m_dim;
00454   m_is_rat = bezier_surface.m_is_rat;
00455   m_order[0] = bezier_surface.m_order[0];
00456   m_order[1] = bezier_surface.m_order[1];
00457   m_cv_count[0] = m_order[0];
00458   m_cv_count[1] = m_order[1];
00459   m_cv_stride[1] = m_is_rat ? (m_dim+1) : m_dim;
00460   m_cv_stride[0] = m_cv_stride[1]*m_cv_count[1];
00461 
00462   // copy control points
00463   if ( bezier_surface.m_cv )
00464   {
00465     ReserveCVCapacity(m_cv_count[0]*m_cv_count[1]*m_cv_stride[1]);
00466     const int sizeof_cv = m_cv_stride[1]*sizeof(*m_cv);
00467     const double* src_cv;
00468     double* dst_cv;
00469     for ( i = 0; i < m_order[0]; i++ ) for( j = 0; j < m_order[1]; j++ )
00470     {
00471       src_cv = bezier_surface.CV(i,j);
00472       dst_cv = CV(i,j);
00473       memcpy( dst_cv, src_cv, sizeof_cv );
00474     }
00475   }
00476 
00477   // set clamped knots for domain [0,1]
00478   for ( j = 0; j < 2; j++ )
00479   {
00480     const int knot_count = KnotCount(j);
00481     ReserveKnotCapacity( j, knot_count );
00482     for ( i = 0; i <= m_order[j]-2; i++ )
00483       m_knot[j][i] = 0.0;
00484     for ( i = m_order[j]-1; i < knot_count; i++ )
00485       m_knot[j][i] = 1.0;
00486   }
00487 
00488   return *this;
00489 }
00490 
00491 void ON_NurbsSurface::Dump( ON_TextLog& dump ) const
00492 {
00493   dump.Print( "ON_NurbsSurface dim = %d is_rat = %d\n"
00494                "        order = %d X %d cv_count = %d X %d\n",
00495                m_dim, m_is_rat, m_order[0], m_order[1], m_cv_count[0], m_cv_count[1] );
00496   int dir;
00497   for ( dir = 0; dir < 2; dir++ ) 
00498   {
00499     dump.Print( "Knot Vector %d ( %d knots )\n", dir, KnotCount(dir) );
00500     dump.PrintKnotVector( m_order[dir], m_cv_count[dir], m_knot[dir] );
00501   }
00502 
00503   dump.Print( "Control Points  %d %s points\n"
00504                "  index               value\n",
00505                m_cv_count[0]*m_cv_count[1], 
00506                (m_is_rat) ? "rational" : "non-rational" );
00507   if ( !m_cv ) 
00508   {
00509     dump.Print("  NULL cv array\n");
00510   }
00511   else 
00512   {
00513     int i;
00514     char sPreamble[128]; 
00515     memset(sPreamble,0,sizeof(sPreamble));
00516     for ( i = 0; i < m_cv_count[0]; i++ )
00517     {
00518       if ( i > 0 )
00519         dump.Print("\n");
00520       sPreamble[0] = 0;
00521       sprintf(sPreamble,"  CV[%2d]",i);
00522       dump.PrintPointList( m_dim, m_is_rat, 
00523                         m_cv_count[1], m_cv_stride[1],
00524                         CV(i,0), 
00525                         sPreamble );
00526     }
00527   }
00528 }
00529 
00530 ON_BOOL32 ON_NurbsSurface::IsValid( ON_TextLog* text_log ) const
00531 {
00532   ON_BOOL32 rc = false;
00533 
00534   if ( m_dim <= 0 )
00535   {
00536     if ( text_log )
00537     {
00538       text_log->Print("ON_NurbsSurface.m_dim = %d (should be > 0).\n",m_dim);
00539     }
00540   }
00541   else if ( m_cv == NULL )
00542   {
00543     if ( text_log )
00544     {
00545       text_log->Print("ON_NurbsSurface.m_cv is NULL.\n",m_dim);
00546     }
00547   }
00548   else
00549   {
00550     rc = true;
00551     int i;
00552     for ( i = 0; i < 2 && rc; i++ )
00553     {
00554       rc = false;
00555       if (m_order[i] < 2 )
00556       {
00557         if ( text_log )
00558         {
00559           text_log->Print("ON_NurbsSurface.m_order[i] = %d (should be >= 2).\n",i,m_order[i]);
00560         }
00561       }
00562       else if (m_cv_count[i] < m_order[i] )
00563       {
00564         if ( text_log )
00565         {
00566           text_log->Print("ON_NurbsSurface.m_cv_count[%d] = %d (should be >= m_order[%d]=%d).\n",i,m_cv_count[i],i,m_order[i]);
00567         }
00568       }
00569       else if (m_knot[i] == NULL)
00570       {
00571         if ( text_log )
00572         {
00573           text_log->Print("ON_NurbsSurface.m_knot[i] is NULL.\n");
00574         }
00575       }
00576       else if ( !ON_IsValidKnotVector( m_order[i], m_cv_count[i], m_knot[i], text_log ) )
00577       {
00578         if ( text_log )
00579         {
00580           text_log->Print("ON_NurbsSurface.m_knot[%d] is not a valid knot vector.\n",i);
00581         }
00582       }
00583       else if ( m_cv_stride[i] < CVSize() )
00584       {
00585         if ( text_log )
00586         {
00587           text_log->Print("ON_NurbsSurface.m_cv_stride[%d]=%d is too small (should be >= %d).\n",i,m_cv_stride[i],CVSize());
00588         }
00589       }
00590       else
00591         rc = true;
00592     }
00593     if ( rc )
00594     {
00595       int a0 = CVSize();
00596       int a1 = m_cv_count[0]*a0;
00597       int b1 = CVSize();
00598       int b0 = m_cv_count[1]*b1;
00599       if ( m_cv_stride[0] < a0 || m_cv_stride[1] < a1 )
00600       {
00601         if ( m_cv_stride[0] < b0 || m_cv_stride[1] < b1 )
00602         {
00603           if ( text_log )
00604           {
00605             text_log->Print("ON_NurbsSurface.m_cv_stride[] = {%d,%d} is not valid.\n",m_cv_stride[0],m_cv_stride[1]);
00606           }
00607           rc = false;
00608         }
00609       }
00610     }
00611   }
00612 
00613   return rc;
00614 }
00615 
00616 ON_BOOL32 ON_NurbsSurface::GetBBox( // returns true if successful
00617        double* boxmin,    // minimum
00618        double* boxmax,    // maximum
00619        ON_BOOL32 bGrowBox  // true means grow box
00620        ) const
00621 {
00622   return ON_GetPointGridBoundingBox( m_dim, m_is_rat, 
00623             m_cv_count[0], m_cv_count[1],
00624             m_cv_stride[0], m_cv_stride[1], 
00625             m_cv, 
00626             boxmin, boxmax, bGrowBox?true:false );
00627 }
00628 
00629 ON_BOOL32 ON_NurbsSurface::Transform( const ON_Xform& xform )
00630 {
00631   DestroySurfaceTree();
00632   TransformUserData(xform);
00633   if ( 0 == m_is_rat )
00634   {
00635     if ( xform.m_xform[3][0] != 0.0 || xform.m_xform[3][1] != 0.0 || xform.m_xform[3][2] != 0.0 )
00636     {
00637       MakeRational();
00638     }
00639   }
00640   return ON_TransformPointGrid( m_dim, m_is_rat, m_cv_count[0], m_cv_count[1], m_cv_stride[0], m_cv_stride[1], m_cv, xform );
00641 }
00642 
00643 bool ON_NurbsSurface::IsDeformable() const
00644 {
00645   return true;
00646 }
00647 
00648 bool ON_NurbsSurface::MakeDeformable()
00649 {
00650   return true;
00651 }
00652 
00653 
00654 ON_BOOL32 ON_NurbsSurface::Write(
00655        ON_BinaryArchive&  file // open binary file
00656      ) const
00657 {
00658   // NOTE - check legacy I/O code if changed
00659   ON_BOOL32 rc = file.Write3dmChunkVersion(1,0);
00660   if (rc) {
00661     if (rc) rc = file.WriteInt( m_dim );
00662     if (rc) rc = file.WriteInt( m_is_rat );
00663     if (rc) rc = file.WriteInt( m_order[0] );
00664     if (rc) rc = file.WriteInt( m_order[1] );
00665     if (rc) rc = file.WriteInt( m_cv_count[0] );
00666     if (rc) rc = file.WriteInt( m_cv_count[1] );
00667 
00668     if (rc) rc = file.WriteInt(0); // reserved1
00669     if (rc) rc = file.WriteInt(0); // reserved2
00670 
00671     if (rc) {
00672       ON_BoundingBox bbox; // write invalid bounding box - may be used in future
00673       rc = file.WriteBoundingBox(bbox);
00674     }
00675     
00676     int count = m_knot[0] ? KnotCount(0) : 0;
00677     if (rc) rc = file.WriteInt(count);
00678     if (rc) rc = file.WriteDouble( count, m_knot[0] );
00679 
00680     count = m_knot[1] ? KnotCount(1) : 0;
00681     if (rc) rc = file.WriteInt(count);
00682     if (rc) rc = file.WriteDouble( count, m_knot[1] );
00683 
00684     const int cv_size = CVSize();
00685     count = ( m_cv && cv_size > 0
00686               && m_cv_count[0] > 0 && m_cv_count[1] > 0 
00687               && m_cv_stride[0] >= cv_size && m_cv_stride[1] >= cv_size) 
00688           ? m_cv_count[0]*m_cv_count[1]
00689           : 0;
00690     if (rc) rc = file.WriteInt(count);
00691     if (rc && count > 0 ) {
00692       int i, j;
00693       for ( i = 0; i < m_cv_count[0] && rc; i++ ) {
00694         for ( j = 0; j < m_cv_count[1] && rc; j++ ) {
00695           rc = file.WriteDouble( cv_size, CV(i,j) );
00696         }
00697       }
00698     }
00699   }
00700   return rc;
00701 }
00702 
00703 ON_BOOL32 ON_NurbsSurface::Read(
00704        ON_BinaryArchive&  file // open binary file
00705      )
00706 {
00707   DestroySurfaceTree();
00708   // NOTE - check legacy I/O code if changed
00709   int major_version = 0;
00710   int minor_version = 0;
00711   ON_BOOL32 rc = file.Read3dmChunkVersion(&major_version,&minor_version);
00712   if (rc && major_version==1) {
00713     // common to all 1.x versions
00714     int dim = 0, is_rat = 0, order0 = 0, order1 = 0, cv_count0 = 0, cv_count1 = 0;
00715     int reserved1 = 0, reserved2 = 0;
00716     if (rc) rc = file.ReadInt( &dim );
00717     if (rc) rc = file.ReadInt( &is_rat );
00718     if (rc) rc = file.ReadInt( &order0 );
00719     if (rc) rc = file.ReadInt( &order1 );
00720     if (rc) rc = file.ReadInt( &cv_count0 );
00721     if (rc) rc = file.ReadInt( &cv_count1 );
00722 
00723     if (rc) rc = file.ReadInt(&reserved1);
00724     if (rc) rc = file.ReadInt(&reserved2);
00725 
00726     if (rc) {
00727       ON_BoundingBox bbox; // read bounding box - may be used in future
00728       rc = file.ReadBoundingBox(bbox);
00729     }
00730     
00731     Create( dim, is_rat, order0, order1, cv_count0, cv_count1 );
00732 
00733     int count = 0;
00734     if (rc) rc = file.ReadInt(&count);
00735     if (rc ) rc = ReserveKnotCapacity(0,count);
00736     if (rc) rc = file.ReadDouble( count, m_knot[0] );
00737 
00738     count = 0;
00739     if (rc) rc = file.ReadInt(&count);
00740     if (rc ) rc = ReserveKnotCapacity(1,count);
00741     if (rc) rc = file.ReadDouble( count, m_knot[1] );
00742 
00743     count = 0;
00744     if (rc) rc = file.ReadInt(&count);
00745     const int cv_size = CVSize();
00746     if (rc) rc = ReserveCVCapacity( count*cv_size );
00747     if (count > 0 && cv_size > 0 && rc ) {
00748       int i, j;
00749       for ( i = 0; i < m_cv_count[0] && rc; i++ ) {
00750         for ( j = 0; j < m_cv_count[1] && rc; j++ ) {
00751           rc = file.ReadDouble( cv_size, CV(i,j) );
00752         }
00753       }
00754     }
00755   }
00756   if ( !rc )
00757     Destroy();
00758   return rc;
00759 }
00760 
00761 ON_Interval ON_NurbsSurface::Domain( int dir ) const
00762 {
00763   ON_Interval d;
00764   if (dir) dir = 1;
00765   ON_GetKnotVectorDomain( m_order[dir], m_cv_count[dir], m_knot[dir], &d.m_t[0], &d.m_t[1] );
00766   return d;
00767 }
00768 
00769 double ON_NurbsSurface::ControlPolygonLength( int dir ) const
00770 {
00771   double max_length = 0.0;
00772   if ( dir >= 0 && dir <= 1 && m_cv_count[0] >= 2 && m_cv_count[1] >= 2 && m_cv != NULL )
00773   {
00774     double length;
00775     const double* p;
00776     int i;
00777     for( i = 0; i < m_cv_count[1-dir]; i++ )
00778     {
00779       length = 0.0;
00780       p = (dir) ? CV(i,0) : CV(0,i);
00781       ON_GetPolylineLength( m_dim, m_is_rat, m_cv_count[dir], m_cv_stride[dir], p, &length );
00782       if ( length > max_length )
00783         max_length = length;
00784     }
00785   }
00786 
00787   return max_length;
00788 }
00789 
00790 
00791 ON_BOOL32 ON_NurbsSurface::GetSurfaceSize( 
00792     double* width, 
00793     double* height 
00794     ) const
00795 {
00796   // TODO - get lengths of polygon
00797   ON_BOOL32 rc = true;
00798   if ( width )
00799   {
00800     *width = ControlPolygonLength( 0 );
00801   }
00802   if ( height )
00803   {
00804     *height = ControlPolygonLength( 1 );
00805   }
00806   return rc;
00807 }
00808 
00809 int ON_NurbsSurface::SpanCount( int dir ) const
00810 {
00811   if (dir) dir = 1;
00812   return ON_KnotVectorSpanCount( m_order[dir], m_cv_count[dir], m_knot[dir] );
00813 }
00814 
00815 ON_BOOL32 ON_NurbsSurface::GetSpanVector( int dir, double* s ) const
00816 {
00817   if (dir) dir = 1;
00818   return ON_GetKnotVectorSpanVector( m_order[dir], m_cv_count[dir], m_knot[dir], s );
00819 }
00820 
00821 ON_BOOL32 ON_NurbsSurface::GetParameterTolerance( // returns tminus < tplus: parameters tminus <= s <= tplus
00822        int dir,
00823        double t,       // t = parameter in domain
00824        double* tminus, // tminus
00825        double* tplus   // tplus
00826        ) const
00827 {
00828   ON_BOOL32 rc = false;
00829   ON_Interval d = Domain(dir);
00830   double t0 = d.Min();
00831   double t1 = d.Max();
00832   if ( t0 <= t1 ) {
00833     const double* knot = Knot(dir);
00834     const int order = Order(dir);
00835     const int cv_count = CVCount(dir);
00836     if ( t < knot[order-1] )
00837       t1 = knot[order-1];
00838     else if ( t > knot[cv_count-2] )
00839       t0 = knot[cv_count-2];
00840     rc = ON_GetParameterTolerance( t0, t1, t, tminus, tplus );
00841   }
00842   return rc;
00843 }
00844 
00845 
00846 ON_BOOL32
00847 ON_NurbsSurface::Evaluate( // returns false if unable to evaluate
00848        double s, double t,       // evaluation parameter
00849        int der_count,  // number of derivatives (>=0)
00850        int v_stride,   // v[] array stride (>=Dimension())
00851        double* v,      // v[] array of length stride*(ndir+1)
00852        int side,       // optional - determines which side to evaluate from
00853                        //         0 = default
00854                        //         1 = from NE quadrant
00855                        //         2 = from NW quadrant
00856                        //         3 = from SW quadrant
00857                        //         4 = from SE quadrant
00858        int hint[2]       // optional - evaluation hint (int) used to speed
00859                        //            repeated evaluations
00860        ) const
00861 {
00862   ON_BOOL32 rc = false;
00863   int span_index[2];
00864   span_index[0] = ON_NurbsSpanIndex(m_order[0],m_cv_count[0],m_knot[0],s,(side==2||side==3)?-1:1,(hint)?hint[0]:0);
00865   span_index[1] = ON_NurbsSpanIndex(m_order[1],m_cv_count[1],m_knot[1],t,(side==3||side==4)?-1:1,(hint)?hint[1]:0);
00866   rc = ON_EvaluateNurbsSurfaceSpan(
00867      m_dim, m_is_rat, 
00868      m_order[0], m_order[1],
00869      m_knot[0] + span_index[0], 
00870      m_knot[1] + span_index[1],
00871      m_cv_stride[0], m_cv_stride[1],
00872      m_cv + (span_index[0]*m_cv_stride[0] + span_index[1]*m_cv_stride[1]),
00873      der_count, 
00874      s, t,
00875      v_stride, v 
00876      );
00877   if ( hint ) {
00878     hint[0] = span_index[0];
00879     hint[1] = span_index[1];
00880   }
00881   return rc;
00882 }
00883 
00884 
00885 ON_Curve* ON_NurbsSurface::IsoCurve(
00886        int dir,          // 0 first parameter varies and second parameter is constant
00887                          //   e.g., point on IsoCurve(0,c) at t is srf(t,c)
00888                          // 1 first parameter is constant and second parameter varies
00889                          //   e.g., point on IsoCurve(1,c) at t is srf(c,t)
00890        double c          // value of constant parameter 
00891        ) const
00892 {
00893   ON_Curve* crv = 0;
00894   int i,j,k,Scvsize,span_index;
00895   double* Ncv;
00896   const double* Scv;
00897   if ( (dir == 0 || dir == 1) && IsValid() )
00898   {
00899     Scvsize = CVSize();
00900     ON_NurbsCurve* nurbscrv = new ON_NurbsCurve( m_dim, m_is_rat, m_order[dir], m_cv_count[dir] );
00901     memcpy( nurbscrv->m_knot, m_knot[dir], nurbscrv->KnotCount()*sizeof(*nurbscrv->m_knot) );
00902     span_index = ON_NurbsSpanIndex(m_order[1-dir],m_cv_count[1-dir],m_knot[1-dir],c,1,0);
00903     if ( span_index < 0 )
00904       span_index = 0;
00905     else if ( span_index > m_cv_count[1-dir]-m_order[1-dir] )
00906       span_index = m_cv_count[1-dir]-m_order[1-dir];
00907     ON_NurbsCurve N( Scvsize*nurbscrv->CVCount(), 0, m_order[1-dir], m_order[1-dir] );
00908     memcpy( N.m_knot, m_knot[1-dir]+span_index, N.KnotCount()*sizeof(*N.m_knot) );
00909     for ( i = 0; i < N.m_cv_count; i++ ) {
00910       Ncv = N.CV(i);
00911       for ( j = 0; j < m_cv_count[dir]; j++ ) {
00912         Scv = (dir) ? CV(i+span_index,j) : CV(j,i+span_index);
00913         for ( k = 0; k < Scvsize; k++ )
00914           *Ncv++ = *Scv++;
00915       }
00916     }
00917     N.Evaluate( c, 0, N.Dimension(), nurbscrv->m_cv );
00918     crv = nurbscrv;
00919   }
00920   return crv;
00921 }
00922 
00923 // Converts a surface to a high degree NURBS curve.
00924 // Use FromCurve to convert back to a surface.
00925 static ON_NurbsCurve* ToCurve( const ON_NurbsSurface& srf, int dir, 
00926                                ON_NurbsCurve* crv )
00927 {
00928   double* tmp_cv = NULL;
00929   if ( dir < 0 || dir > 1 )
00930     return NULL;
00931   if ( !srf.m_cv )
00932     return NULL;
00933   if ( !crv )
00934     crv = new ON_NurbsCurve();
00935   int srf_cv_size = srf.CVSize();
00936   if ( !crv->Create(
00937           srf_cv_size*srf.m_cv_count[1-dir], // dim
00938           false, // is_rat
00939           srf.m_order[dir],
00940           srf.m_cv_count[dir]
00941           ) )
00942     return NULL;
00943   if ( crv->m_cv == srf.m_cv )
00944   {
00945     tmp_cv = (double*)onmalloc( crv->m_dim*crv->m_cv_stride*sizeof(tmp_cv[0]) );
00946     crv->m_cv = tmp_cv;
00947   }
00948   double* pdst;
00949   const double* psrc;
00950   int i, j;
00951   size_t sz = srf_cv_size*sizeof(pdst[0]);
00952   for ( i = 0; i < srf.m_cv_count[dir]; i++ )
00953   {
00954     pdst = crv->CV(i);
00955     psrc = dir ? srf.CV(0,i) : srf.CV(i,0);
00956     for ( j = 0; j < srf.m_cv_count[1-dir]; j++ )
00957     {
00958       memcpy( pdst, psrc, sz );
00959       psrc += srf.m_cv_stride[1-dir];
00960       pdst += srf_cv_size;
00961     }
00962   }
00963   if ( tmp_cv )
00964   {
00965     crv->m_cv = srf.m_cv;
00966     memcpy( crv->m_cv, tmp_cv, crv->m_dim*crv->m_cv_stride*sizeof(tmp_cv[0]) );
00967     onfree(tmp_cv);
00968   }
00969   if ( crv->m_knot != srf.m_knot[dir] )
00970     memcpy( crv->m_knot, srf.m_knot[dir], crv->KnotCount()*sizeof(crv->m_knot[0]) );
00971   return crv;
00972 }
00973 
00974 // Converts the curve created in ToCurve back into a surface.
00975 // The "srf" parameter must be the surface passed to ToCurve().
00976 static ON_BOOL32 FromCurve( ON_NurbsCurve& crv, 
00977                                    ON_NurbsSurface& srf, 
00978                                    int dir )
00979 {
00980   srf.DestroySurfaceTree();
00981   crv.DestroyCurveTree();
00982   if ( dir < 0 || dir > 1 )
00983     return false;
00984   if ( !crv.m_cv )
00985     return false;
00986   if ( crv.m_is_rat )
00987     return false;
00988   int srf_cv_size = srf.CVSize();
00989   if ( srf.m_cv_count[1-dir]*srf_cv_size != crv.m_dim )
00990     return false;
00991   if ( srf.m_cv_capacity > 0 && srf.m_cv && srf.m_cv != crv.m_cv )
00992   {
00993     onfree( srf.m_cv );
00994   }
00995   srf.m_cv_capacity = crv.m_cv_capacity;
00996   srf.m_cv = crv.m_cv;
00997   crv.m_cv_capacity = 0;
00998   crv.m_cv = 0;
00999   if ( srf.m_knot_capacity[dir] > 0 && srf.m_knot[dir] && srf.m_knot[dir] != crv.m_knot )
01000   {
01001     onfree(srf.m_knot[dir]);
01002   }
01003   srf.m_order[dir] = crv.m_order;
01004   srf.m_cv_count[dir] = crv.m_cv_count;
01005   srf.m_knot_capacity[dir] = crv.m_knot_capacity;
01006   srf.m_knot[dir] = crv.m_knot;
01007   crv.m_knot_capacity = 0;
01008   crv.m_knot = 0;
01009   srf.m_cv_stride[dir] = crv.m_cv_stride;
01010   srf.m_cv_stride[1-dir] = srf_cv_size;
01011   return true;
01012 }
01013 
01014 ON_BOOL32 ON_NurbsSurface::Trim(
01015        int dir,
01016        const ON_Interval& domain
01017        )
01018 {
01019   ON_BOOL32 rc = false;
01020   if ( dir < 0 || dir > 1 )
01021     return false;
01022   ON_Interval current_domain = Domain(dir);
01023   if ( current_domain[0] == ON_UNSET_VALUE && current_domain[1] == ON_UNSET_VALUE )
01024     current_domain = domain;
01025   ON_Interval trim_domain;
01026   trim_domain.Intersection(domain, Domain(dir) );
01027   if ( !trim_domain.IsIncreasing() )
01028     return false;
01029   if (    trim_domain[0] == current_domain[0] 
01030        && trim_domain[1] == current_domain[1] )
01031     return true;
01032 
01033   DestroySurfaceTree();
01034 
01035   ON_NurbsCurve crv;
01036   if ( ToCurve(*this,dir,&crv) )
01037   {
01038     rc = crv.Trim( trim_domain );
01039     if ( rc )
01040       rc = FromCurve( crv, *this, dir );
01041   }
01042 
01043   return true;
01044 }
01045 
01046 bool ON_NurbsSurface::Extend(
01047       int dir,
01048       const ON_Interval& domain
01049       )
01050 {
01051 
01052   bool rc = false;
01053   if ( dir < 0 || dir > 1 )
01054     return false;
01055   if (IsClosed(dir)) return false;
01056 
01057   ON_NurbsCurve crv;
01058   if ( ToCurve(*this,dir,&crv) )
01059   {
01060     rc = crv.Extend( domain );
01061     FromCurve( crv, *this, dir );
01062   }
01063 
01064   if (rc){
01065     DestroySurfaceTree();
01066   }
01067   return rc;
01068 
01069 }
01070 
01071 ON_BOOL32 ON_NurbsSurface::Split(
01072        int dir,
01073        double c,
01074        ON_Surface*& west_or_south_side,
01075        ON_Surface*& east_or_north_side
01076        ) const
01077 {
01078   if ( dir < 0 || dir > 1 )
01079     return false;
01080   if ( !Domain(dir).Includes( c, true ) )
01081     return false;
01082   ON_NurbsSurface* left_srf = 0;
01083   ON_NurbsSurface* right_srf = 0;
01084 
01085   if ( west_or_south_side )
01086   {
01087     left_srf = ON_NurbsSurface::Cast( west_or_south_side );
01088     if ( !left_srf )
01089       return false;
01090     left_srf->DestroySurfaceTree();
01091   }
01092 
01093   if ( east_or_north_side )
01094   {
01095     right_srf = ON_NurbsSurface::Cast( east_or_north_side );
01096     if ( !right_srf )
01097       return false;
01098     right_srf->DestroySurfaceTree();
01099   }
01100 
01101   ON_NurbsCurve crv, left_crv, right_crv;
01102   if ( !ToCurve( *this, dir, &crv ) )
01103     return false;
01104   ON_Curve *left_side, *right_side;
01105   left_side = &left_crv;
01106   right_side = &right_crv;
01107   if ( !crv.Split( c, left_side, right_side ) )
01108     return false;
01109   
01110   if ( !left_srf )
01111     left_srf = new ON_NurbsSurface();
01112 
01113   if ( left_srf != this )
01114   {
01115     left_srf->m_dim = m_dim;
01116     left_srf->m_is_rat = m_is_rat;
01117     left_srf->m_order[1-dir] = m_order[1-dir];
01118     left_srf->m_cv_count[1-dir] = m_cv_count[1-dir];
01119     left_srf->ReserveKnotCapacity(1-dir,KnotCount(1-dir));
01120     memcpy( left_srf->m_knot[1-dir], m_knot[1-dir], KnotCount(1-dir)*sizeof(m_knot[1-dir][0] ) );
01121   }
01122 
01123   if ( !FromCurve( left_crv, *left_srf, dir ) )
01124   {
01125     if ( left_srf != this && left_srf !=  west_or_south_side )
01126       delete left_srf;
01127     else
01128       left_srf->Destroy();
01129 
01130     return false;
01131   }
01132 
01133   if ( !right_srf )
01134     right_srf = new ON_NurbsSurface();
01135 
01136   if ( right_srf != this )
01137   {
01138     right_srf->m_dim = m_dim;
01139     right_srf->m_is_rat = m_is_rat;
01140     right_srf->m_order[1-dir] = m_order[1-dir];
01141     right_srf->m_cv_count[1-dir] = m_cv_count[1-dir];
01142     right_srf->ReserveKnotCapacity(1-dir,KnotCount(1-dir));
01143     memcpy( right_srf->m_knot[1-dir], m_knot[1-dir], KnotCount(1-dir)*sizeof(m_knot[1-dir][0] ) );
01144   }
01145 
01146   if ( !FromCurve( right_crv, *right_srf, dir ) )
01147   {
01148     if ( left_srf != this && left_srf !=  west_or_south_side )
01149       delete left_srf;
01150     else
01151       left_srf->Destroy();
01152 
01153     if ( right_srf != this && right_srf !=  east_or_north_side )
01154       delete right_srf;
01155     else
01156       right_srf->Destroy();
01157 
01158     return false;
01159   }
01160 
01161   if ( !west_or_south_side)
01162     west_or_south_side = left_srf;
01163 
01164   if ( !east_or_north_side)
01165     east_or_north_side = right_srf;
01166 
01167   return true;  
01168 }
01169 
01170 
01171 int 
01172 ON_NurbsSurface::GetNurbForm( // returns 0: unable to create NURBS representation
01173                  //            with desired accuracy.
01174                  //         1: success - returned NURBS parameterization
01175                  //            matches the surface's to wthe desired accuracy
01176                  //         2: success - returned NURBS point locus matches
01177                  //            the surfaces's to the desired accuracy but, on
01178                  //            the interior of the surface's domain, the 
01179                  //            surface's parameterization and the NURBS
01180                  //            parameterization may not match to the 
01181                  //            desired accuracy.
01182       ON_NurbsSurface& srf,
01183       double // tolerance
01184       ) const
01185 {
01186   // 4 May 2007 Dale Lear
01187   //   I'm replacing the call to operator= with a call to
01188   //   ON_NurbsSurfaceCopyHelper().  The operator= call
01189   //   was copying userdata and that does not happen for
01190   //   any other GetNurbForm overrides.  Copying userdata
01191   //   in GetNurbForm is causing trouble in Make2D and 
01192   //   other places that are creating NURBS copies in
01193   //   worker memory pools.
01194 
01195   //srf = *this; // copied user data
01196   ON_NurbsSurfaceCopyHelper(*this,srf); // does not copy user data
01197   return 1;
01198 }
01199 
01200 ON_Surface* ON_NurbsSurface::Offset(
01201       double offset_distance, 
01202       double tolerance, 
01203       double* max_deviation
01204       ) const
01205 {
01206   // 3rd party developers who want to enhance openNURBS
01207   // may provide a working offset here.
01208   return NULL;
01209 }
01210 
01211 
01212 ON_BOOL32 ON_NurbsSurface::IsPlanar(
01213       ON_Plane* plane,
01214       double tolerance
01215       ) const
01216 {
01217   ON_Plane pln;
01218   double d;
01219   ON_3dPoint center, cv;
01220   ON_3dVector normal, du, dv;
01221   ON_Interval udom = Domain(0);
01222   ON_Interval vdom = Domain(1);
01223   ON_BOOL32 rc = EvNormal( udom.ParameterAt(0.5), vdom.ParameterAt(0.5), center, du, dv, normal );
01224   if ( rc && normal.Length() < 0.9 )
01225     rc = false;
01226   else
01227   {
01228     pln.origin = center;
01229     pln.zaxis = normal;
01230     if ( du.Unitize() )
01231     {
01232       pln.xaxis = du;
01233       pln.yaxis = ON_CrossProduct( pln.zaxis, pln.xaxis );
01234       pln.yaxis.Unitize();
01235       pln.UpdateEquation();
01236     }
01237     else if ( dv.Unitize() )
01238     {
01239       pln.yaxis = dv;
01240       pln.xaxis = ON_CrossProduct( pln.yaxis, pln.zaxis );
01241       pln.xaxis.Unitize();
01242       pln.UpdateEquation();
01243     }
01244     else
01245     {
01246       pln.CreateFromNormal( center, normal );
01247     }
01248 
01249     // 7 July 2006 Dale Lear
01250     //    Add a slight bias for coordinate axes planes.
01251     //    This appears to do more good than harm.  The
01252     //    issue is keeping customers from getting alarmed
01253     //    when a coordinate they know is "zero" turns out to
01254     //    be 1e-23.
01255     if (    fabs(pln.zaxis.x) <= ON_ZERO_TOLERANCE 
01256          && fabs(pln.zaxis.y) <= ON_ZERO_TOLERANCE
01257          && fabs(fabs(pln.zaxis.z)-1.0) <= ON_SQRT_EPSILON
01258        )
01259     {
01260       pln.xaxis.z = 0.0;
01261       pln.yaxis.z = 0.0;
01262       pln.zaxis.x = 0.0;
01263       pln.zaxis.y = 0.0;
01264       pln.zaxis.z = (pln.zaxis.z<0.0) ? -1.0 : 1.0;
01265       pln.UpdateEquation();
01266     }
01267     else if (    fabs(pln.zaxis.y) <= ON_ZERO_TOLERANCE 
01268               && fabs(pln.zaxis.z) <= ON_ZERO_TOLERANCE
01269               && fabs(fabs(pln.zaxis.x)-1.0) <= ON_SQRT_EPSILON
01270             )
01271     {
01272       pln.xaxis.x = 0.0;
01273       pln.yaxis.x = 0.0;
01274       pln.zaxis.y = 0.0;
01275       pln.zaxis.z = 0.0;
01276       pln.zaxis.x = (pln.zaxis.x<0.0) ? -1.0 : 1.0;
01277       pln.UpdateEquation();
01278     }
01279     else if (    fabs(pln.zaxis.z) <= ON_ZERO_TOLERANCE 
01280               && fabs(pln.zaxis.x) <= ON_ZERO_TOLERANCE
01281               && fabs(fabs(pln.zaxis.y)-1.0) <= ON_SQRT_EPSILON
01282             )
01283     {
01284       pln.xaxis.y = 0.0;
01285       pln.yaxis.y = 0.0;
01286       pln.zaxis.z = 0.0;
01287       pln.zaxis.x = 0.0;
01288       pln.zaxis.y = (pln.zaxis.y<0.0) ? -1.0 : 1.0;
01289       pln.UpdateEquation();
01290     }
01291 
01292     int i, j;
01293     for ( i = 0; i < m_cv_count[0] && rc; i++ )
01294     {
01295       for ( j = 0; j < m_cv_count[1] && rc; j++ )
01296       {
01297         GetCV( i, j, cv );
01298         d = pln.DistanceTo(cv);
01299         if ( fabs(d) > tolerance )
01300           rc = false;
01301       }
01302     }
01303 
01304     if ( rc && plane )
01305       *plane = pln;
01306   }
01307 
01308   return rc;
01309 }
01310 
01311 ON_BOOL32 
01312 ON_NurbsSurface::IsClosed( int dir ) const
01313 {
01314   bool bIsClosed = false;
01315   if ( dir >= 0 && dir <= 1 && m_dim > 0 )
01316   {
01317     if ( ON_IsKnotVectorClamped( m_order[dir], m_cv_count[dir], m_knot[dir] ) )
01318     {
01319       const double* corners[4];
01320       corners[0] = CV(0,0);
01321       corners[(0==dir)?1:2] = CV(m_cv_count[0]-1,0);
01322       corners[(0==dir)?2:1] = CV(0,m_cv_count[1]-1);
01323       corners[3] = CV(m_cv_count[0]-1,m_cv_count[1]-1);
01324       if (    ON_PointsAreCoincident(m_dim,m_is_rat,corners[0],corners[1])
01325            && ON_PointsAreCoincident(m_dim,m_is_rat,corners[2],corners[3])
01326            && ON_IsPointGridClosed( m_dim, m_is_rat, m_cv_count[0], m_cv_count[1], m_cv_stride[0], m_cv_stride[1], m_cv, dir ) 
01327          )
01328       {
01329         bIsClosed = true;
01330       }
01331     }
01332     else if ( IsPeriodic(dir) )
01333     {
01334       bIsClosed = true;
01335     }
01336   }
01337   return bIsClosed;
01338 }
01339 
01340 
01341 ON_BOOL32 
01342 ON_NurbsSurface::ChangeSurfaceSeam( 
01343                                                 int dir,
01344             double t 
01345             )
01346 {
01347         bool rc = true;
01348 
01349   if ( dir < 0 || dir > 1 )
01350     return false;
01351 
01352   ON_Interval current_domain = Domain(dir);
01353         if( !current_domain.Includes( t) )
01354                 rc = false;
01355         
01356         if(rc && IsClosed(dir) ){
01357                 DestroySurfaceTree();
01358                 ON_NurbsCurve crv;
01359                 rc = ToCurve(*this, dir, &crv)!=NULL;
01360                 if(rc)
01361                         rc = crv.ChangeClosedCurveSeam(t)!=0;
01362                 rc = FromCurve(crv,*this, dir) && rc;
01363         }
01364 
01365         return rc;
01366 }
01367 
01368 ON_BOOL32 
01369 ON_NurbsSurface::IsPeriodic( int dir ) const
01370 {
01371   bool bIsPeriodic = false;
01372   if ( dir >= 0 && dir <= 1 )
01373   {
01374     int k;
01375     bIsPeriodic = ON_IsKnotVectorPeriodic( m_order[dir], m_cv_count[dir], m_knot[dir] );
01376     if ( bIsPeriodic ) 
01377     {
01378       const double *cv0, *cv1;
01379       int i0 = m_order[dir]-2;
01380       int i1 = m_cv_count[dir]-1;
01381       for ( k = 0; k < m_cv_count[1-dir]; k++ )
01382       {
01383         cv0 = (dir)?CV(k,i0):CV(i0,k);
01384         cv1 = (dir)?CV(k,i1):CV(i1,k);
01385         for ( /*empty*/; i0 >= 0; i0--, i1-- ) 
01386         {
01387           if ( false == ON_PointsAreCoincident( m_dim, m_is_rat, cv0, cv1 ) )
01388             return false;
01389           cv0 -= m_cv_stride[dir];
01390           cv1 -= m_cv_stride[dir];      
01391         }
01392       }
01393     }
01394   }
01395   return bIsPeriodic;
01396 }
01397 
01398 bool ON_NurbsSurface::GetNextDiscontinuity( 
01399                   int dir,
01400                   ON::continuity c,
01401                   double t0,
01402                   double t1,
01403                   double* t,
01404                   int* hint,
01405                   int* dtype,
01406                   double cos_angle_tolerance,
01407                   double curvature_tolerance
01408                   ) const
01409 {
01410   int tmp_hint[2];
01411   int tmp_dtype=0;
01412 
01413   double d, tmp_t;
01414 
01415   ON_2dVector st;
01416   ON_Interval span_domain;
01417   ON_3dVector Vm[6], Vp[6];
01418   ON_3dVector Tm, Tp, Km, Kp;
01419   ON_3dVector& D1m = Vm[1+dir];
01420   ON_3dVector& D2m = Vm[3+2*dir];
01421   ON_3dVector& D1p = Vp[1+dir];
01422   ON_3dVector& D2p = Vp[3+2*dir];
01423 
01424   int ki;
01425   if ( !hint )
01426   {
01427     tmp_hint[0] = 0;
01428     tmp_hint[1] = 0;
01429     hint = &tmp_hint[0];
01430   }
01431   if ( !dtype )
01432     dtype = &tmp_dtype;
01433   if ( !t )
01434     t = &tmp_t;
01435   
01436   if ( c == ON::C0_continuous )
01437     return false;
01438 
01439   if ( c == ON::C0_locus_continuous )
01440   {
01441     return ON_Surface::GetNextDiscontinuity( 
01442       dir, c, t0, t1, t, hint, dtype, 
01443       cos_angle_tolerance, curvature_tolerance );
01444   }
01445   if ( t0 == t1 )
01446     return false;
01447 
01448   // First test for parametric discontinuities.  If none are found
01449   // then we will look for locus discontinuities at ends
01450   if ( m_order[dir] <= 2 )
01451     c = ON::PolylineContinuity(c);  // no need to look a zero 2nd derivatives
01452   const ON::continuity input_c = c; // saved so we can tell if "locus" needs to be dealt with
01453   c = ON::ParametricContinuity(c);  // strips "locus" from c
01454 
01455   bool bEv2ndDer    = ( c == ON::C2_continuous || c == ON::G2_continuous || c == ON::Gsmooth_continuous );
01456   bool bTestKappa   = ( bEv2ndDer && c != ON::C2_continuous );
01457   bool bTestTangent = ( bTestKappa || c == ON::G1_continuous );
01458 
01459   int delta_ki = 1;
01460   int delta = ((bEv2ndDer) ? 3 : 2) - m_order[dir];
01461   if ( ON::Cinfinity_continuous == c )
01462     delta = 0;
01463 
01464   ki = ON_NurbsSpanIndex(m_order[dir],m_cv_count[dir],m_knot[dir],t0,1,*hint);
01465   double segtol = (fabs(m_knot[dir][ki]) + fabs(m_knot[dir][ki+1]) + fabs(m_knot[dir][ki+1]-m_knot[dir][ki]))*ON_SQRT_EPSILON;
01466 
01467   if ( t0 < t1 )
01468   {
01469     int ii = ki+m_order[dir]-2;
01470     if ( t0 < m_knot[dir][ii+1] && t1 > m_knot[dir][ii+1] && (m_knot[dir][ii+1]-t0) <= segtol && ii+2 < m_cv_count[dir] )
01471     {
01472       t0 = m_knot[dir][ii+1];
01473       ki = ON_NurbsSpanIndex(m_order[dir],m_cv_count[dir],m_knot[dir],t0,1,*hint);
01474     }
01475     *hint = ki;
01476     ki += m_order[dir]-2;
01477     while (ki < m_cv_count[dir]-1 && m_knot[dir][ki] <= t0) 
01478       ki += delta_ki;
01479     if (ki >= m_cv_count[dir]-1) 
01480     {
01481       if ( input_c != c && t0 < m_knot[dir][m_cv_count[dir]-1] && t1 >= m_knot[dir][m_cv_count[dir]-1] )
01482       {
01483         // have to do locus end test
01484         return ON_Surface::GetNextDiscontinuity( dir, input_c, t0, t1, t, hint, dtype, 
01485                                     cos_angle_tolerance, curvature_tolerance );
01486       }
01487       return false;
01488     }
01489   }
01490   else
01491   {
01492     // (t0 > t1) work backwards
01493     int ii = ki+m_order[dir]-2;
01494     if ( t0 > m_knot[dir][ii] && t1 < m_knot[dir][ii] && (t0-m_knot[dir][ii]) <= segtol && ii > m_order[dir]-2 )
01495     {
01496       t0 = m_knot[dir][ii];
01497       ki = ON_NurbsSpanIndex(m_order[dir],m_cv_count[dir],m_knot[dir],t0,1,*hint);
01498     }
01499 
01500     *hint = ki;
01501     ki += m_order[dir]-2;
01502     while (ki < m_order[dir]-2 && m_knot[dir][ki] >= t0) 
01503       ki--;
01504     if (ki <= m_order[dir]-2) 
01505     {
01506       if ( input_c != c && t0 > m_knot[dir][m_order[dir]-2] && t1 < m_knot[dir][m_order[dir]-2] )
01507       {
01508         // have to do locus end test
01509         return ON_Surface::GetNextDiscontinuity( dir,input_c, t0, t1, t, hint, dtype, 
01510                                     cos_angle_tolerance, curvature_tolerance );
01511       }
01512       return false;
01513     }
01514     delta_ki = -1;
01515     delta = -delta;
01516   }
01517   
01518   while (m_knot[dir][ki] < t1) 
01519   {
01520     if ( delta_ki > 0 )
01521     {
01522       // t0 < t1 case
01523       while (ki < m_cv_count[dir]-1 && m_knot[dir][ki] == m_knot[dir][ki+1])
01524         ki++;
01525       if (ki >= m_cv_count[dir]-1) 
01526         break;    
01527     }
01528     else
01529     {
01530       // t0 > t1 case
01531       // 20 March 2003 Dale Lear:
01532       //     Added to make t0 > t1 case work
01533       while (ki > m_order[dir]-2 && m_knot[dir][ki] == m_knot[dir][ki-1])
01534         ki--;
01535       if (ki <= m_order[dir]-2) 
01536         break;    
01537     }
01538 
01539     if (m_knot[dir][ki] == m_knot[dir][ki+delta]) 
01540     {  
01541       if ( ON::Cinfinity_continuous == c )
01542       {
01543         // Cinfinity_continuous is treated as asking for the next knot
01544         *dtype = 3;
01545         *t = m_knot[dir][ki];
01546         return true;
01547       }
01548       
01549       st[dir] = m_knot[dir][ki];
01550 
01551       int j, j0=0, otherki;
01552       for ( otherki = m_order[1-dir]-2; otherki < m_cv_count[1-dir]-1; otherki++ )
01553       {
01554         span_domain.Set(m_knot[1-dir][otherki],m_knot[1-dir][otherki+1]);
01555         for ( j = j0; j <= 2; j++ )
01556         {
01557           st[1-dir] = span_domain.ParameterAt(0.5*j);
01558 
01559           Evaluate( st.x, st.y, bEv2ndDer?2:1, 3, &Vm[0].x, 3, hint);
01560           Evaluate( st.x, st.y, bEv2ndDer?2:1, 3, &Vp[0].x, 1, hint);
01561 
01562           if ( bTestTangent )
01563           {
01564            if ( bTestKappa )
01565             {
01566               ON_EvCurvature( D1m, D2m, Tm, Km );
01567               ON_EvCurvature( D1p, D2p, Tp, Kp );
01568             }
01569             else 
01570             {
01571               Tm = D1m;
01572               Tp = D1p;
01573               Tm.Unitize();
01574               Tp.Unitize();
01575             }
01576             d = Tm*Tp;
01577             if ( d < cos_angle_tolerance )
01578             {
01579               *dtype = 1;
01580               *t = m_knot[dir][ki];
01581               return true;
01582             }
01583             else if ( bTestKappa )
01584             {
01585               bool bIsCurvatureContinuous = ( ON::Gsmooth_continuous == c)
01586                 ? ON_IsGsmoothCurvatureContinuous(Km,Kp,cos_angle_tolerance,curvature_tolerance)
01587                 : ON_IsG2CurvatureContinuous(Km,Kp,cos_angle_tolerance,curvature_tolerance);
01588               if ( !bIsCurvatureContinuous )
01589               {
01590                 *dtype = 2;
01591                 *t = m_knot[dir][ki];
01592                 return true;
01593               }
01594             }
01595           }
01596           else
01597           {
01598             if ( !(D1m-D1p).IsTiny(D1m.MaximumCoordinate()*ON_SQRT_EPSILON) )
01599             {
01600               *dtype = 1;
01601               *t = m_knot[dir][ki];
01602               return true;
01603             }
01604             else if ( bEv2ndDer )
01605             {
01606               if ( !(D2m-D2p).IsTiny(D2m.MaximumCoordinate()*ON_SQRT_EPSILON) )
01607               {
01608                 *dtype = 2;
01609                 *t = m_knot[dir][ki];
01610                 return true;
01611               }         
01612             }
01613           }
01614 
01615         }
01616         j0 = 1;
01617       }
01618     }
01619     ki += delta_ki;
01620   }
01621 
01622   // 20 March 2003 Dale Lear:
01623   //   If we get here, there are not discontinuities strictly between
01624   //   t0 and t1.
01625   bool rc = false;
01626 
01627   if ( input_c != c )
01628   {
01629     // use base class for consistent start/end locus testing 
01630     rc = ON_Surface::GetNextDiscontinuity( dir, input_c, t0, t1, t, hint, dtype, 
01631                                     cos_angle_tolerance, curvature_tolerance );
01632   }
01633 
01634   return rc;
01635 }
01636 
01637 
01638 ON_BOOL32
01639 ON_NurbsSurface::IsSingular( // true if surface side is collapsed to a point
01640       int side   // side of parameter space to test
01641                  // 0 = south, 1 = east, 2 = north, 3 = west
01642       ) const
01643 {
01644   bool rc = false;
01645   const double* points = 0;
01646   int point_count = 0;
01647   int point_stride = 0;
01648 
01649   switch ( side ) 
01650   {
01651   case 0: // south
01652     rc = IsClamped(1,0)?true:false;
01653     if ( rc )
01654     {
01655       points = CV(0,0);
01656       point_count = m_cv_count[0];
01657       point_stride = m_cv_stride[0];
01658     }
01659     break;
01660 
01661   case 1: // east
01662     rc = IsClamped(0,1)?true:false;
01663     if (rc)
01664     {
01665       points = CV(m_cv_count[0]-1,0);
01666       point_count = m_cv_count[1];
01667       point_stride = m_cv_stride[1];
01668     }
01669     break;
01670 
01671   case 2: // north
01672     rc  = IsClamped(1,1)?true:false;
01673     if (rc)
01674     {
01675       points = CV(0,m_cv_count[1]-1);
01676       point_count = m_cv_count[0];
01677       point_stride = m_cv_stride[0];
01678     }
01679     break;
01680 
01681   case 3: // west
01682     rc = IsClamped( 0, 0 )?true:false;
01683     if (rc) 
01684     {
01685       points = CV(0,0);
01686       point_count = m_cv_count[1];
01687       point_stride = m_cv_stride[1];
01688     }
01689     break;
01690 
01691   default:
01692     rc = false;
01693     break;
01694   }
01695 
01696   if (rc)
01697     rc = ON_PointsAreCoincident(m_dim,m_is_rat,point_count,point_stride,points);
01698 
01699   return rc;
01700 }
01701 
01702 
01703 ON_BOOL32 
01704 ON_NurbsSurface::SetWeight( int i, int j, double w )
01705 {
01706   DestroySurfaceTree();
01707 
01708   ON_BOOL32 rc = false;
01709   if ( m_is_rat ) {
01710     double* cv = CV(i,j);
01711     if (cv) {
01712       cv[m_dim] = w;
01713       rc = true;
01714     }
01715   }
01716   else if ( w == 1.0 ) {
01717     rc = true;
01718   }
01719   return rc;
01720 }
01721 
01722 ON_BOOL32 
01723 ON_NurbsSurface::SetCV( int i, int j, ON::point_style style, const double* Point )
01724 {
01725   DestroySurfaceTree();
01726 
01727   ON_BOOL32 rc = true;
01728   int k;
01729   double w;
01730 
01731   double* cv = CV(i,j);
01732   if ( !cv )
01733     return false;
01734 
01735   switch ( style ) {
01736 
01737   case ON::not_rational:  // input Point is not rational
01738     memcpy( cv, Point, m_dim*sizeof(*cv) );
01739     if ( IsRational() ) {
01740       // NURBS surface is rational - set weight to one
01741       cv[m_dim] = 1.0;
01742     }
01743     break;
01744 
01745   case ON::homogeneous_rational:  // input Point is homogeneous rational
01746     if ( IsRational() ) {
01747       // NURBS surface is rational
01748       memcpy( cv, Point, (m_dim+1)*sizeof(*cv) );
01749     }
01750     else {
01751       // NURBS surface is not rational
01752       w = (Point[m_dim] != 0.0) ? 1.0/Point[m_dim] : 1.0;
01753       for ( k = 0; k < m_dim; k++ ) {
01754         cv[k] = w*Point[k];
01755       }
01756     }
01757     break;
01758 
01759   case ON::euclidean_rational:  // input Point is euclidean rational
01760     if ( IsRational() ) {
01761       // NURBS surface is rational - convert euclean point to homogeneous form
01762       w = Point[m_dim];
01763       for ( k = 0; k < m_dim; k++ )
01764         cv[k] = w*Point[k];  // 22 April 2003 - bug fix [i] to [k]
01765       cv[m_dim] = w;
01766     }
01767     else {
01768       // NURBS surface is not rational
01769       memcpy( cv, Point, m_dim*sizeof(*cv) );
01770     }
01771     break;
01772 
01773   case ON::intrinsic_point_style:  // input Point is euclidean rational
01774     memcpy( cv, Point, CVSize()*sizeof(*cv) );
01775     break;
01776 
01777   default:
01778     rc = false;
01779     break;
01780   }
01781   return rc;
01782 }
01783 
01784 ON_BOOL32 
01785 ON_NurbsSurface::SetCV( int i, int j, const ON_3dPoint& point )
01786 {
01787   DestroySurfaceTree();
01788 
01789   ON_BOOL32 rc = false;
01790   double* cv = CV(i,j);
01791   if ( cv ) {
01792     cv[0] = point.x;
01793     if ( m_dim > 1 ) {
01794       cv[1] = point.y;
01795       if ( m_dim > 2 )
01796         cv[2] = point.z;
01797     }
01798     if ( m_is_rat ) {
01799       cv[m_dim] = 1.0;
01800     }
01801     rc = true;
01802   }
01803   return rc;
01804 }
01805 
01806 ON_BOOL32 
01807 ON_NurbsSurface::SetCV( int i, int j, const ON_4dPoint& point )
01808 {
01809   DestroySurfaceTree();
01810 
01811   ON_BOOL32 rc = false;
01812   double* cv = CV(i,j);
01813   if ( cv ) {
01814     if ( m_is_rat ) {
01815       cv[0] = point.x;
01816       if ( m_dim > 1 ) {
01817         cv[1] = point.y;
01818         if ( m_dim > 2 )
01819           cv[2] = point.z;
01820       }
01821       cv[m_dim] = point.w;
01822       rc = true;
01823     }
01824     else {
01825       double w;
01826       if ( point.w != 0.0 ) {
01827         w = 1.0/point.w;
01828         rc = true;
01829       }
01830       else {
01831         w = 1.0;
01832       }
01833       cv[0] = w*point.x;
01834       if ( m_dim > 1 ) {
01835         cv[1] = w*point.y;
01836         if ( m_dim > 2 ) {
01837           cv[2] = w*point.z;
01838         }
01839       }
01840     }
01841   }
01842   return rc;
01843 }
01844 
01845 ON_BOOL32 
01846 ON_NurbsSurface::GetCV( int i, int j, ON::point_style style, double* Point ) const
01847 {
01848   const double* cv = CV(i,j);
01849   if ( !cv )
01850     return false;
01851   int dim = Dimension();
01852   double w = ( IsRational() ) ? cv[dim] : 1.0;
01853   switch(style) {
01854   case ON::euclidean_rational:
01855     Point[dim] = w;
01856     // no break here
01857   case ON::not_rational:
01858     if ( w == 0.0 )
01859       return false;
01860     w = 1.0/w;
01861     while(dim--) *Point++ = *cv++ * w;
01862     break;
01863   case ON::homogeneous_rational:
01864     Point[dim] = w;
01865     memcpy( Point, cv, dim*sizeof(*Point) );
01866     break;
01867   default:
01868     return false;
01869   }
01870   return true;
01871 }
01872 
01873 ON_BOOL32 
01874 ON_NurbsSurface::GetCV( int i, int j, ON_3dPoint& point ) const
01875 {
01876   ON_BOOL32 rc = false;
01877   const double* cv = CV(i,j);
01878   if ( cv ) {
01879     if ( m_is_rat ) {
01880       if (cv[m_dim] != 0.0) {
01881         const double w = 1.0/cv[m_dim];
01882         point.x = cv[0]*w;
01883         point.y = (m_dim>1)? cv[1]*w : 0.0;
01884         point.z = (m_dim>2)? cv[2]*w : 0.0;
01885         rc = true;
01886       }
01887     }
01888     else {
01889       point.x = cv[0];
01890       point.y = (m_dim>1)? cv[1] : 0.0;
01891       point.z = (m_dim>2)? cv[2] : 0.0;
01892       rc = true;
01893     }
01894   }
01895   return rc;
01896 }
01897 
01898 ON_BOOL32 
01899 ON_NurbsSurface::GetCV( int i, int j, ON_4dPoint& point ) const
01900 {
01901   ON_BOOL32 rc = false;
01902   const double* cv = CV(i,j);
01903   if ( cv ) {
01904     point.x = cv[0];
01905     point.y = (m_dim>1)? cv[1] : 0.0;
01906     point.z = (m_dim>2)? cv[2] : 0.0;
01907     point.w = (m_is_rat) ? cv[m_dim] : 1.0;
01908     rc = true;
01909   }
01910   return rc;
01911 }
01912 
01913 ON_BOOL32 
01914 ON_NurbsSurface::SetKnot( int dir, int knot_index, double k )
01915 {
01916   DestroySurfaceTree();
01917   if ( dir ) dir = 1;
01918   if ( knot_index < 0 || knot_index >= KnotCount(dir) )
01919     return false;
01920   m_knot[dir][knot_index] = k;
01921   return true;
01922 }
01923 
01924 bool ON_NurbsSurface::IsContinuous(
01925     ON::continuity desired_continuity,
01926     double s, 
01927     double t, 
01928     int* hint, // default = NULL,
01929     double point_tolerance, // default=ON_ZERO_TOLERANCE
01930     double d1_tolerance, // default==ON_ZERO_TOLERANCE
01931     double d2_tolerance, // default==ON_ZERO_TOLERANCE
01932     double cos_angle_tolerance, // default==ON_DEFAULT_ANGLE_TOLERANCE_COSINE
01933     double curvature_tolerance  // default==ON_SQRT_EPSILON
01934     ) const
01935 {
01936   // TODO: speed up by avoiding evaluation at non-multi knots
01937   return ON_Surface::IsContinuous( desired_continuity, s, t, hint,
01938                                     point_tolerance, d1_tolerance, d2_tolerance,
01939                                     cos_angle_tolerance, curvature_tolerance );
01940 }
01941 
01942 ON_BOOL32
01943 ON_NurbsSurface::Reverse(int dir)
01944 {
01945   if (dir < 0 || dir > 1) return false;
01946   DestroySurfaceTree();
01947   ON_BOOL32 rc0 = ON_ReverseKnotVector( m_order[dir], m_cv_count[dir], m_knot[dir] );
01948   ON_BOOL32 rc1 = ON_ReversePointGrid( 3, m_is_rat, m_cv_count[0], m_cv_count[1], m_cv_stride[0], m_cv_stride[1], m_cv, dir );
01949   return rc0 && rc1;
01950 }
01951 
01952 ON_BOOL32
01953 ON_NurbsSurface::Transpose()
01954 {
01955   DestroySurfaceTree();
01956   int i;
01957   // transpose CV grid
01958   i = m_order[0]; m_order[0] = m_order[1]; m_order[1] = i;
01959   i = m_cv_count[0]; m_cv_count[0] = m_cv_count[1]; m_cv_count[1] = i;
01960   i = m_cv_stride[0]; m_cv_stride[0] = m_cv_stride[1]; m_cv_stride[1] = i;
01961 
01962   // swap knot vectors
01963   i = m_knot_capacity[0]; m_knot_capacity[0] = m_knot_capacity[1]; m_knot_capacity[1] = i;
01964   double* k = m_knot[0]; m_knot[0] = m_knot[1]; m_knot[1] = k;
01965   return true;
01966 }
01967 
01968 ON_BOOL32
01969 ON_NurbsSurface::SwapCoordinates( int i, int j )
01970 {
01971   DestroySurfaceTree();
01972   ON_BOOL32 rc = true;
01973   int k;
01974   if ( m_cv_count[0] <= m_cv_count[1] ) {
01975     for ( k = 0; k < m_cv_count[0]; k++ ) {
01976       if ( !ON_SwapPointListCoordinates( m_cv_count[1], m_cv_stride[1], CV(k,0), i, j ) )
01977         rc = false;
01978     }
01979   }
01980   else {
01981     for ( k = 0; k < m_cv_count[1]; k++ ) {
01982       if ( !ON_SwapPointListCoordinates( m_cv_count[0], m_cv_stride[0], CV(0,k), i, j ) )
01983         rc = false;
01984     }
01985   }
01986   return rc;
01987 }
01988 
01989 ON_BOOL32 ON_NurbsSurface::SetCVRow(
01990        int row_index,
01991        const ON_3dPoint& point
01992        )
01993 {
01994   DestroySurfaceTree();
01995   int i;
01996 
01997   if ( row_index < 0 || row_index > m_cv_count[1] )
01998     return false;
01999 
02000   for ( i = 0; i < m_cv_count[0]; i++ ) {
02001     if ( !SetCV( i, row_index, point ) )
02002       return false;
02003   }
02004 
02005   return true;
02006 }
02007 
02008 ON_BOOL32 ON_NurbsSurface::SetCVRow(
02009        int row_index,
02010        int v_stride,   // v stride
02011        const double* v // values (same dim and is_rat as surface)
02012        )
02013 {
02014   DestroySurfaceTree();
02015   int i;
02016   unsigned int s;
02017   double* cv;
02018 
02019   if ( row_index < 0 || row_index > m_cv_count[1] )
02020     return false;
02021   cv = CV(0,row_index);
02022   if ( !cv )
02023     return false;
02024   if ( v_stride < CVSize() )
02025     return false;
02026   s = CVSize()*sizeof(*cv);
02027   if ( s < m_dim*sizeof(*cv) )
02028     return false;
02029 
02030   for ( i = 0; i < m_cv_count[0]; i++ ) {
02031     memcpy( cv, v, s );
02032     cv += m_cv_stride[0];
02033     v += v_stride;
02034   }
02035 
02036   return true;
02037 }
02038 
02039 ON_BOOL32 ON_NurbsSurface::SetCVColumn(
02040        int col_index,
02041        const ON_3dPoint& point
02042        )
02043 {
02044   DestroySurfaceTree();
02045   int j;
02046 
02047   if ( col_index < 0 || col_index > m_cv_count[0] )
02048     return false;
02049 
02050   for ( j = 0; j < m_cv_count[1]; j++ ) {
02051     if ( !SetCV( col_index, j, point ) )
02052       return false;
02053   }
02054 
02055   return true;
02056 }
02057 
02058 ON_BOOL32 ON_NurbsSurface::SetCVColumn(
02059        int col_index,
02060        int v_stride,   // v stride
02061        const double* v // values (same dim and is_rat as surface)
02062        )
02063 {
02064   DestroySurfaceTree();
02065   int i;
02066   unsigned int s;
02067   double* cv;
02068 
02069   if ( col_index < 0 || col_index > m_cv_count[0] )
02070     return false;
02071   cv = CV(col_index,0);
02072   if ( !cv )
02073     return false;
02074   if ( v_stride < CVSize() )
02075     return false;
02076   s = CVSize()*sizeof(*cv);
02077   if ( s < m_dim*sizeof(*cv) )
02078     return false;
02079 
02080   for ( i = 0; i < m_cv_count[1]; i++ ) {
02081     memcpy( cv, v, s );
02082     cv += m_cv_stride[1];
02083     v += v_stride;
02084   }
02085 
02086   return true;
02087 }
02088 
02089 double ON_NurbsSurface::GrevilleAbcissa(
02090          int dir,    // dir
02091          int gindex  // index (0 <= index < CVCount(dir)
02092          ) const
02093 {
02094   if (dir) 
02095     dir = 1;
02096   return ON_GrevilleAbcissa( m_order[dir], m_knot[dir] + gindex );
02097 }
02098 
02099 bool ON_NurbsSurface::GetGrevilleAbcissae( // see ON_GetGrevilleAbcissae() for details
02100          int dir,          // dir
02101          double* g         // g[cv1-cv0]
02102          ) const
02103 {
02104   if (dir) 
02105     dir = 1;
02106   return ON_GetGrevilleAbcissae( m_order[dir], m_cv_count[dir], m_knot[dir], false, g );
02107 }
02108 
02109 bool ON_NurbsSurface::SetClampedGrevilleKnotVector(
02110          int dir,        // dir
02111          int g_stride,   // g_stride
02112          const double* g // g[], Greville abcissa
02113          )
02114 {
02115   DestroySurfaceTree();
02116   if ( !m_knot[dir] && m_order[dir] >= 2 && m_cv_count[dir] >= m_order[dir] )
02117     ReserveKnotCapacity(dir,KnotCount(dir));
02118   return ON_GetGrevilleKnotVector( g_stride, g, false, Order(dir), CVCount(dir), m_knot[dir] );
02119 }
02120 
02121 bool ON_NurbsSurface::SetPeriodicGrevilleKnotVector(
02122          int dir,        // dir
02123          int g_stride,   // g_stride
02124          const double* g // g[], Greville abcissa
02125          )
02126 {
02127   DestroySurfaceTree();
02128   if ( !m_knot[dir] && m_order[dir] >= 2 && m_cv_count[dir] >= m_order[dir] )
02129     ReserveKnotCapacity(dir,KnotCount(dir));
02130   return ON_GetGrevilleKnotVector( g_stride, g, true, Order(dir), CVCount(dir), m_knot[dir] );
02131 }
02132 
02133 
02134 bool ON_NurbsSurface::ZeroCVs()
02135 {
02136   DestroySurfaceTree();
02137   bool rc = false;
02138   int i, j;
02139   if ( m_cv ) {
02140     if ( m_cv_capacity > 0 ) {
02141       memset( m_cv, 0, m_cv_capacity*sizeof(*m_cv) );
02142       if ( m_is_rat ) {
02143         for ( i = 0; i < m_cv_count[0]; i++ ) for ( j = 0; j < m_cv_count[1]; j++ ) {
02144           SetWeight( i, j, 1.0 );
02145         }
02146       }
02147       rc = true;
02148     }
02149     else {
02150       double* cv;
02151       int s = CVSize()*sizeof(*cv);
02152       j = 0;
02153       for ( i = 0; i < m_cv_count[0]; i++ ) for ( j = 0; j < m_cv_count[1]; j++ ) {
02154         cv = CV(i,j);
02155         if ( !cv )
02156           return false;
02157         memset(cv,0,s);
02158         if ( m_is_rat )
02159           cv[m_dim] = 1.0;
02160       }
02161       rc = (i>0 && j>0) ? true : false;
02162     }
02163   }
02164   return rc;
02165 }
02166 
02167 bool ON_NurbsSurface::IsClamped( // determine if knot vector is clamped
02168       int dir, // dir 0 = "s", 1 = "t", 2 = both
02169       int end  // (default =2) end to check: 0 = start, 1 = end, 2 = start and end
02170       ) const
02171 {
02172   bool rc = false;
02173   if ( dir == 0 || dir == 1)
02174     rc = ON_IsKnotVectorClamped( m_order[dir], m_cv_count[dir], m_knot[dir], end );
02175   return rc;
02176 }
02177 
02178 static void ConvertToCurve( const ON_NurbsSurface& srf, int dir, ON_NurbsCurve& crv )
02179 {
02180   // DO NOT MAKE THIS FUNCTION PUBLIC - IT IS DELICATE AND DEDICATED TO USE IN THIS FILE
02181 
02182   crv.DestroyCurveTree();
02183   if (dir)
02184     dir = 1;
02185   const int Sdim = srf.CVSize();
02186   const int n = srf.CVCount(1-dir);
02187   const int Ndim = Sdim*n;
02188   const int knot_count = srf.KnotCount(dir);
02189   int i, j;
02190   double *Ncv;
02191   const double *Scv;
02192 
02193   crv.m_dim = Ndim;
02194   crv.m_is_rat = 0;
02195   crv.m_order = srf.Order(dir);
02196   crv.m_cv_count = srf.CVCount(dir);
02197   crv.m_cv_stride = crv.m_dim;
02198   crv.ReserveCVCapacity(srf.CVCount(dir)*Ndim);
02199   crv.ReserveKnotCapacity(srf.KnotCount(dir));
02200 
02201   if ( crv.m_knot != srf.m_knot[dir] && srf.m_knot[dir] ) 
02202   {
02203     memcpy( crv.m_knot, srf.m_knot[dir], knot_count*sizeof(crv.m_knot[0]) );
02204   }
02205 
02206   if ( crv.m_cv != srf.m_cv && srf.m_cv ) 
02207   {
02208     if (dir) {
02209       for ( i = 0; i < crv.m_cv_count; i++ ) {
02210         Ncv = crv.CV(i);
02211         for ( j = 0; j < n; j++ ) {
02212           Scv = srf.CV(j,i);
02213           memcpy( Ncv, Scv, Sdim*sizeof(*Ncv) );
02214           Ncv += Sdim;
02215         }
02216       }
02217     }
02218     else {
02219       for ( i = 0; i < crv.m_cv_count; i++ ) {
02220         Ncv = crv.CV(i);
02221         for ( j = 0; j < n; j++ ) {
02222           Scv = srf.CV(i,j);
02223           memcpy( Ncv, Scv, Sdim*sizeof(*Ncv) );
02224           Ncv += Sdim;
02225         }
02226       }
02227     }
02228   }
02229 }
02230 
02231 static void ConvertFromCurve( ON_NurbsCurve& crv, int dir, ON_NurbsSurface& srf )
02232 {
02233   // DO NOT MAKE THIS FUNCTION PUBLIC - IT IS DELICATE AND DEDICATED TO USE IN THIS FILE
02234 
02235   crv.DestroyCurveTree();
02236   srf.DestroySurfaceTree();
02237   if (dir)
02238     dir = 1;
02239   const int Sdim = srf.CVSize();
02240 
02241   srf.m_order[dir]       = crv.m_order;
02242   srf.m_cv_count[dir]    = crv.m_cv_count;
02243   srf.m_cv_stride[dir]   = crv.m_cv_stride;
02244   srf.m_cv_stride[1-dir] = Sdim;
02245 
02246   if ( crv.m_cv ) 
02247   {
02248     if (    srf.m_cv 
02249          && crv.m_cv != srf.m_cv
02250          && srf.m_cv_capacity > 0 
02251          && srf.m_cv_capacity <  crv.m_cv_stride*crv.m_cv_count ) 
02252     {
02253       // discard surface cvs because there isn't enough room
02254       onfree( srf.m_cv );
02255       srf.m_cv = 0;
02256       srf.m_cv_capacity = 0;
02257     }
02258 
02259     if ( srf.m_cv )
02260     {
02261       // use existing surface cvs
02262       memcpy( srf.m_cv, crv.m_cv, crv.m_cv_stride*crv.m_cv_count*sizeof(*srf.m_cv) );
02263     }
02264     else
02265     {
02266       // move curve cvs to surface
02267       srf.m_cv = crv.m_cv;
02268       srf.m_cv_capacity = crv.m_cv_capacity;
02269       crv.m_cv = 0;
02270       crv.m_cv_capacity  = 0;
02271     }
02272 
02273     crv.m_cv_stride  = 0;
02274   }
02275 
02276   if ( crv.m_knot && crv.m_knot != srf.m_knot[dir] ) 
02277   {
02278     if ( srf.m_knot_capacity[dir] > 0 ) 
02279     {
02280       onfree( srf.m_knot[dir] );
02281       srf.m_knot[dir] = 0;
02282       srf.m_knot_capacity[dir] = 0;
02283     }
02284     srf.m_knot[dir] = crv.m_knot;
02285     srf.m_knot_capacity[dir] = crv.m_knot_capacity;
02286     crv.m_knot = 0;
02287     crv.m_knot_capacity = 0;
02288   }
02289 }
02290 
02291 
02292 
02293 bool ON_NurbsSurface::ClampEnd(
02294           int dir,         // dir 0 = "s", 1 = "t"
02295           int end// 0 = clamp start, 1 = clamp end, 2 = clamp start and end
02296           )
02297 {
02298   DestroySurfaceTree();
02299   if (dir)
02300     dir = 1;
02301   ON_NurbsCurve crv;
02302   crv.m_knot = m_knot[dir];
02303   ConvertToCurve(*this,dir,crv);
02304   bool rc = crv.ClampEnd(end);
02305   ConvertFromCurve(crv,dir,*this);
02306   return rc;
02307 }
02308 
02309 bool ON_NurbsSurface::InsertKnot(
02310          int dir,         // dir 0 = "s", 1 = "t"
02311          double knot_value,
02312          int knot_multiplicity // default = 1
02313          )
02314 {
02315   DestroySurfaceTree();
02316   bool rc = false;
02317 
02318   if ( (dir == 0 || dir == 1) && IsValid() && knot_multiplicity > 0 && knot_multiplicity < Order(dir) ) 
02319   {
02320     ON_Interval domain = Domain( dir );
02321     if ( knot_value < domain.Min() || knot_value > domain.Max() ) 
02322     {
02323       ON_ERROR("ON_NurbsSurface::InsertKnot() knot_value not inside domain.");
02324     }
02325     else 
02326     {
02327       ON_NurbsCurve crv;
02328       crv.m_knot = m_knot[dir];
02329       crv.m_knot_capacity = m_knot_capacity[dir];
02330       m_knot[dir] = 0;
02331       m_knot_capacity[dir] = 0;
02332       crv.ReserveKnotCapacity(CVCount(dir)+knot_multiplicity);
02333       ConvertToCurve(*this,dir,crv);
02334       rc = crv.InsertKnot(knot_value,knot_multiplicity);
02335       ConvertFromCurve(crv,dir,*this);
02336     }
02337   }
02338 
02339   return rc;
02340 }
02341 
02342 bool ON_NurbsSurface::MakeRational()
02343 {
02344   if ( !IsRational() ) 
02345   {
02346     DestroySurfaceTree();
02347     ON_BezierSurface b;
02348     b.m_dim = m_dim;
02349     b.m_is_rat = m_is_rat;
02350     b.m_order[0] = m_cv_count[0];
02351     b.m_order[1] = m_cv_count[1];
02352     b.m_cv_stride[0] = m_cv_stride[0];
02353     b.m_cv_stride[1] = m_cv_stride[1];
02354     b.m_cv = m_cv;
02355                 b.m_cv_capacity = m_cv_capacity;
02356           b.MakeRational();
02357     m_is_rat = b.m_is_rat;
02358     m_cv_stride[0] = b.m_cv_stride[0];
02359     m_cv_stride[1] = b.m_cv_stride[1];
02360     m_cv = b.m_cv;
02361     b.m_cv = 0;
02362   }
02363   return IsRational();
02364 }
02365 
02366 bool ON_NurbsSurface::ChangeDimension(
02367           int desired_dimension  //  desired_dimension
02368           )
02369 {
02370   bool rc = false;
02371   int i, j, k;
02372   if ( desired_dimension < 1 )
02373     return false;
02374   if ( desired_dimension == m_dim )
02375     return true;
02376 
02377   DestroySurfaceTree();
02378 
02379   if ( desired_dimension < m_dim ) 
02380   {
02381     if ( m_is_rat ) {
02382       double* cv;
02383       for ( i = 0; i < m_cv_count[0]; i++ ) 
02384       {
02385         for ( j = 0; j < m_cv_count[1]; j++ ) 
02386         {
02387           cv = CV(i,j);
02388           cv[desired_dimension] = cv[m_dim];
02389         }
02390       }
02391     }
02392     m_dim = desired_dimension;
02393     rc = true;
02394   }
02395   else 
02396   {
02397     const double* old_cv;
02398     double* new_cv;
02399     //const int old_cv_size = m_is_rat ? (m_dim + 1) : m_dim;
02400     const int old_stride0 = m_cv_stride[0];
02401     const int old_stride1 = m_cv_stride[1];
02402     const int cv_size = m_is_rat ? (desired_dimension + 1) : desired_dimension;
02403     int new_stride0 = old_stride0;
02404     int new_stride1 = old_stride1;
02405     if ( cv_size > old_stride0 && cv_size > old_stride1 )
02406     {      
02407       new_stride0 = (old_stride0 <= old_stride1) ? cv_size : (cv_size*m_cv_count[1]);
02408       new_stride1 = (old_stride0 <= old_stride1) ? (cv_size*m_cv_count[0]) : cv_size;
02409       ReserveCVCapacity(cv_size*m_cv_count[0]*m_cv_count[1]);
02410     }
02411 
02412     if ( old_stride0 <= old_stride1 )
02413     {
02414       for ( j = m_cv_count[1]-1; j >= 0; j-- )
02415       {
02416         for ( i = m_cv_count[0]-1; i >= 0; i-- )
02417         {
02418           old_cv = m_cv + (old_stride0*i + old_stride1*j);
02419           new_cv = m_cv + (new_stride0*i + new_stride1*j);
02420           if ( m_is_rat )
02421           {
02422             new_cv[desired_dimension] = old_cv[m_dim];
02423           }
02424           for ( k = desired_dimension-1; k >= m_dim; k-- )
02425           {
02426             new_cv[k] = 0.0;
02427           }
02428           for ( k = m_dim-1; k >= 0; k-- )
02429           {
02430             new_cv[k] = old_cv[k];
02431           }
02432         }
02433       }
02434     }
02435     else
02436     {
02437       for ( i = m_cv_count[0]-1; i >= 0; i-- )
02438       {
02439         for ( j = m_cv_count[1]-1; j >= 0; j-- )
02440         {
02441           old_cv = m_cv + (old_stride0*i + old_stride1*j);
02442           new_cv = m_cv + (new_stride0*i + new_stride1*j);
02443           if ( m_is_rat )
02444           {
02445             new_cv[desired_dimension] = old_cv[m_dim];
02446           }
02447           for ( k = desired_dimension-1; k >= m_dim; k-- )
02448           {
02449             new_cv[k] = 0.0;
02450           }
02451           for ( k = m_dim-1; k >= 0; k-- )
02452           {
02453             new_cv[k] = old_cv[k];
02454           }
02455         }
02456       }
02457     }
02458     m_cv_stride[0] = new_stride0;
02459     m_cv_stride[1] = new_stride1;
02460     m_dim = desired_dimension;
02461     rc = true;
02462   }
02463   return rc;
02464 }
02465 
02466 bool ON_NurbsSurface::IncreaseDegree(
02467          int dir,  // dir 0 = "s", 1 = "t"
02468          int desired_degree  //  desired_degree
02469          )
02470 {
02471   DestroySurfaceTree();
02472   bool rc = false;
02473 
02474   if ( (dir == 0 || dir == 1) && IsValid() && desired_degree >= 1 )
02475   {
02476     if ( m_order[dir] == desired_degree+1 )
02477       rc = true;
02478     else
02479     {
02480       ON_NurbsCurve crv;
02481       crv.m_knot = m_knot[dir];
02482       crv.m_knot_capacity = m_knot_capacity[dir];
02483       m_knot[dir] = 0;
02484       m_knot_capacity[dir] = 0;
02485       ConvertToCurve(*this,dir,crv);
02486       rc = crv.IncreaseDegree(desired_degree);
02487       ConvertFromCurve(crv,dir,*this);
02488     }
02489   }
02490 
02491   return rc;
02492 }
02493 
02494 bool ON_NurbsSurface::MakeNonRational()
02495 {
02496   if ( IsRational() ) 
02497   {
02498     DestroySurfaceTree();
02499     ON_BezierSurface b;
02500     b.m_dim = m_dim;
02501     b.m_is_rat = m_is_rat;
02502     b.m_order[0] = m_cv_count[0];
02503     b.m_order[1] = m_cv_count[1];
02504     b.m_cv_stride[0] = m_cv_stride[0];
02505     b.m_cv_stride[1] = m_cv_stride[1];
02506     b.m_cv = m_cv;
02507     b.MakeNonRational();
02508     m_is_rat = b.m_is_rat;
02509     m_cv_stride[0] = b.m_cv_stride[0];
02510     m_cv_stride[1] = b.m_cv_stride[1];
02511     m_cv = b.m_cv;
02512     b.m_cv = 0;
02513   }
02514   return IsRational() ? false : true;
02515 }
02516 
02517 ON_TensorProduct::ON_TensorProduct()
02518 {}
02519 
02520 ON_TensorProduct::~ON_TensorProduct()
02521 {}
02522 
02523 ON_BOOL32 ON_NurbsSurface::TensorProduct(
02524       const ON_NurbsCurve& nurbscurveA,
02525       const ON_NurbsCurve& nurbscurveB,
02526       ON_TensorProduct& tensor
02527       )
02528 {
02529   DestroySurfaceTree();
02530   //   The resulting surface will satisfy
02531   //     NurbSrf(s,t) = T( NurbA(s), NurbB(t) )
02532   // 
02533   //   If you want to understand the relationship between multilinear maps
02534   //   and tensor products, read chapter 16 of Serge Lang's Algebra book.
02535   //   The connection between Lang and tensor product nurb surfaces being
02536   //   that NurbA and NurbB are elements of the module of piecewise polynomial
02537   //   functions that satisfy certain degree and continuity constraints.
02538 
02539   ON_BOOL32 rc;
02540         double wA, wB, wC;
02541         const double *cvA, *cvB;
02542         double *cvC;
02543         int i, j, k,  cv_countA, cv_countB, dimA, dimB, dimC, is_ratA, is_ratB, is_ratC;
02544 
02545         dimA = nurbscurveA.Dimension();
02546         dimB = nurbscurveB.Dimension();
02547         dimC = tensor.DimensionC();
02548 
02549   if ( tensor.DimensionA() > dimA ) {
02550     ON_ERROR("ON_NurbsSurface::TensorProduct() - tensor.DimensionA() > dimA");
02551     return false;
02552   }
02553   if ( tensor.DimensionB() > dimB ) {
02554     ON_ERROR("ON_NurbsSurface::TensorProduct() - tensor.DimensionB() > dimB");
02555     return false;
02556   }
02557 
02558         is_ratA = nurbscurveA.IsRational();
02559         is_ratB = nurbscurveB.IsRational();
02560         is_ratC = (is_ratA || is_ratB);
02561   cv_countA = nurbscurveA.CVCount();
02562   cv_countB = nurbscurveB.CVCount();
02563 
02564   Create( dimC, is_ratC, nurbscurveA.Order(), nurbscurveB.Order(), cv_countA, cv_countB );
02565 
02566   if ( m_knot[0] != nurbscurveA.m_knot )
02567     memcpy( m_knot[0], nurbscurveA.m_knot, KnotCount(0)*sizeof(*m_knot[0]) );
02568   if ( m_knot[1] != nurbscurveB.m_knot )
02569     memcpy( m_knot[1], nurbscurveB.m_knot, KnotCount(1)*sizeof(*m_knot[1]) );
02570 
02571         for (i = 0; i < cv_countA; i++) {
02572     cvA = nurbscurveA.CV(i);
02573                 for (j = 0; j < cv_countB; j++) {
02574                 cvB = nurbscurveB.CV(j);
02575       cvC = CV(i,j);
02576                         wA = (is_ratA) ? cvA[dimA] : 1.0;
02577                         wB = (is_ratB) ? cvB[dimB] : 1.0;
02578                         rc = tensor.Evaluate( (wA == 0.0) ? 0.0 : 1.0/wA, cvA, 
02579                                                                                   (wB == 0.0) ? 0.0 : 1.0/wB, cvB, 
02580                                                                                   cvC );
02581       if ( !rc )
02582         return false;
02583                         if (is_ratC) {
02584                         wC = wA*wB;
02585         for ( k = 0; k < dimC; k++ )
02586           *cvC++ *= wC;
02587         *cvC = wC;
02588                         }
02589                 }
02590         }
02591         return true;
02592 }
02593 
02594 static
02595 bool ON_MakeDegreesCompatible(
02596        ON_NurbsCurve& nurbs_curveA,
02597        ON_NurbsCurve& nurbs_curveB
02598        )
02599 {
02600   bool rc = false;
02601   if ( nurbs_curveA.m_order > nurbs_curveB.m_order )
02602     rc = nurbs_curveB.IncreaseDegree( nurbs_curveA.Degree() )?true:false;
02603   else
02604     rc = nurbs_curveA.IncreaseDegree( nurbs_curveB.Degree() )?true:false;
02605   return (nurbs_curveA.m_order == nurbs_curveA.m_order);
02606 }
02607 
02608 static
02609 bool ON_MakeDomainsCompatible(
02610        ON_NurbsCurve& nurbs_curveA,
02611        ON_NurbsCurve& nurbs_curveB
02612        )
02613 {
02614   ON_Interval dA = nurbs_curveA.Domain();
02615   ON_Interval dB = nurbs_curveB.Domain();
02616   bool rc = false;
02617   if ( dA.Length() >= dB.Length() )
02618     rc = (nurbs_curveB.SetDomain(dA[0],dA[1])?true:false);
02619   else
02620     rc = (nurbs_curveA.SetDomain(dB[0],dB[1])?true:false);
02621   return rc;
02622 }
02623 
02624 static
02625 bool ON_MakeKnotVectorsCompatible(
02626        ON_NurbsCurve& nurbs_curveA,
02627        ON_NurbsCurve& nurbs_curveB
02628        )
02629 {
02630   if ( !ON_MakeDegreesCompatible( nurbs_curveA, nurbs_curveB ) )
02631     return false;
02632   if ( !ON_MakeDomainsCompatible( nurbs_curveA, nurbs_curveB ) )
02633     return false;
02634 
02635   const int order = nurbs_curveA.m_order;
02636   ON_Interval span;
02637   double ktol, a, b;
02638   int i, ki, multA, multB;
02639   int knot_countA = nurbs_curveA.KnotCount();
02640   int knot_countB = nurbs_curveB.KnotCount();
02641   int max_knot_capacity = knot_countA + knot_countB - 2*(order-1);
02642 
02643   bool bPeriodic = false;
02644   if ( nurbs_curveA.IsPeriodic() || nurbs_curveB.IsPeriodic() )
02645   {
02646     bPeriodic = true;
02647     for ( ki = 0; ki < order-2 && bPeriodic; ki++ )
02648     {
02649       if ( nurbs_curveA.m_knot[ki] != nurbs_curveB.m_knot[ki] )
02650         bPeriodic = false;
02651     }
02652     int kiA, kiB;
02653     for (
02654       kiA = nurbs_curveA.m_cv_count,
02655       kiB = nurbs_curveB.m_cv_count;
02656       kiA < knot_countA && kiB < knot_countB && bPeriodic;
02657       kiA++, kiB++ )
02658     {
02659       if ( nurbs_curveA.m_knot[kiA] != nurbs_curveB.m_knot[kiA] )
02660         bPeriodic = false;
02661     }
02662   }
02663   if ( !bPeriodic )
02664   {
02665     if ( !nurbs_curveA.ClampEnd(2) )
02666       return false;
02667     if ( !nurbs_curveB.ClampEnd(2) )
02668       return false;
02669   }
02670 
02671   ki = order-1; 
02672   while ( (ki < nurbs_curveA.m_cv_count-1 || ki < nurbs_curveB.m_cv_count-1)
02673           && nurbs_curveA.m_knot[ki-1] == nurbs_curveB.m_knot[ki-1]
02674           && ki <= nurbs_curveA.m_cv_count-1
02675           && ki <= nurbs_curveB.m_cv_count-1
02676           )
02677   {
02678     a = nurbs_curveA.m_knot[ki];
02679     if ( a == nurbs_curveA.m_knot[ki-1] )
02680       return false;
02681     b = nurbs_curveB.m_knot[ki];
02682     if ( b == nurbs_curveB.m_knot[ki-1] )
02683       return false;
02684     multA = ON_KnotMultiplicity( order, nurbs_curveA.m_cv_count, nurbs_curveA.m_knot, ki );
02685     multB = ON_KnotMultiplicity( order, nurbs_curveB.m_cv_count, nurbs_curveB.m_knot, ki );
02686 
02687     if ( a < b )
02688     {
02689       // insert a in nurbs_curveB
02690       span.Set(nurbs_curveB.m_knot[ki-1], nurbs_curveB.m_knot[ki] );
02691       ktol = ON_SQRT_EPSILON*(span.Length() + fabs(nurbs_curveB.m_knot[ki-1]) + fabs(nurbs_curveB.m_knot[ki]) );
02692       if ( a >= span[1] - ktol )
02693       {
02694         for ( i = ki; i < ki+multB; i++ )
02695           nurbs_curveB.m_knot[i] = a;          
02696       }
02697       else
02698       {
02699         nurbs_curveB.ReserveKnotCapacity( max_knot_capacity );
02700         nurbs_curveB.InsertKnot( a, multA );
02701       }
02702       b = nurbs_curveB.m_knot[ki];
02703       multB = ON_KnotMultiplicity( order, nurbs_curveB.m_cv_count, nurbs_curveB.m_knot, ki );
02704     }
02705     else if ( b < a )
02706     {
02707       // insert b in nurbs_curveA
02708       span.Set(nurbs_curveA.m_knot[ki-1], nurbs_curveA.m_knot[ki] );
02709       ktol = ON_SQRT_EPSILON*(span.Length() + fabs(nurbs_curveA.m_knot[ki-1]) + fabs(nurbs_curveA.m_knot[ki]) );
02710       if ( b >= span[1] - ktol )
02711       {
02712         for ( i = ki; i < ki+multA; i++ )
02713           nurbs_curveA.m_knot[i] = b;
02714       }
02715       else
02716       {
02717         nurbs_curveA.ReserveKnotCapacity( max_knot_capacity );
02718         nurbs_curveA.InsertKnot( b, multB );
02719       }
02720       a = nurbs_curveA.m_knot[ki];
02721       multA = ON_KnotMultiplicity( order, nurbs_curveA.m_cv_count, nurbs_curveA.m_knot, ki );
02722     }
02723 
02724     if ( a != b )
02725       return false;
02726 
02727     if ( a == b )
02728     {
02729       if ( multA < multB )
02730       {
02731         nurbs_curveA.ReserveKnotCapacity( max_knot_capacity );
02732         if ( !nurbs_curveA.InsertKnot( a, multB ) )
02733           return false;
02734         multA = multB;
02735       }
02736       else if ( multB < multA )
02737       {
02738         nurbs_curveB.ReserveKnotCapacity( max_knot_capacity );
02739         if ( !nurbs_curveB.InsertKnot( a, multA ) )
02740           return false;
02741         multB = multA;
02742       }
02743       ki += multA;
02744     }
02745   }
02746 
02747   if ( nurbs_curveA.m_cv_count != nurbs_curveB.m_cv_count )
02748     return false;
02749   knot_countA = nurbs_curveA.KnotCount();
02750   for ( ki = 0; ki < knot_countA; ki++ )
02751   {
02752     if ( nurbs_curveA.m_knot[ki] != nurbs_curveB.m_knot[ki] )
02753       return false;
02754   }
02755 
02756   return true;
02757 }
02758 
02759 int ON_NurbsSurface::CreateRuledSurface(
02760        const ON_Curve& curveA,
02761        const ON_Curve& curveB,
02762        const ON_Interval* curveA_domain,
02763        const ON_Interval* curveB_domain
02764        )
02765 {
02766   DestroySurfaceTree();
02767   int rcA=1, rcB=1;
02768   ON_NurbsCurve nurbs_curveA, nurbs_curveB;
02769   if ( m_cv && m_cv_capacity == 0 )
02770     nurbs_curveA.m_cv = m_cv;
02771   if ( m_knot[0] && m_knot_capacity[0] == 0 )
02772     nurbs_curveA.m_knot = m_knot[0];
02773   rcA = curveA.GetNurbForm( nurbs_curveA, 0.0, curveA_domain );
02774   if ( rcA<=0 )
02775     return 0;
02776   rcB = curveB.GetNurbForm( nurbs_curveB, 0.0, curveB_domain );
02777   if ( rcB<=0 )
02778     return 0;
02779 
02780   if ( !ON_MakeKnotVectorsCompatible( nurbs_curveA, nurbs_curveB ) )
02781     return false;
02782 
02783   if ( nurbs_curveA.m_cv_count != nurbs_curveB.m_cv_count )
02784     return 0;
02785   if ( nurbs_curveA.m_order != nurbs_curveB.m_order )
02786     return 0;
02787 
02788   int srf_dim = 3;
02789   if ( nurbs_curveA.Dimension() > srf_dim )
02790     srf_dim = nurbs_curveA.Dimension();
02791   if ( nurbs_curveB.Dimension() > srf_dim )
02792     srf_dim = nurbs_curveB.Dimension();
02793 
02794   if (nurbs_curveA.Dimension() < srf_dim )
02795     nurbs_curveA.ChangeDimension(srf_dim);
02796   else if (nurbs_curveB.Dimension() < srf_dim )
02797     nurbs_curveB.ChangeDimension(srf_dim);
02798 
02799   if ( nurbs_curveA.IsRational() )
02800     nurbs_curveB.MakeRational();
02801   else if ( nurbs_curveB.IsRational() )
02802     nurbs_curveA.MakeRational();
02803 
02804   // reserve enough room in nurbs_curveA.m_cv 
02805   // for two rows of surface cvs.
02806   const int is_rat = nurbs_curveA.m_is_rat ? 1 : 0;
02807   if ( is_rat )
02808   {
02809     nurbs_curveA.m_is_rat = 0;
02810     nurbs_curveA.m_dim++;
02811   }
02812   nurbs_curveA.ChangeDimension( 2*nurbs_curveA.m_dim );
02813   nurbs_curveA.m_dim = srf_dim;
02814   nurbs_curveA.m_is_rat = is_rat;
02815 
02816   // transfer m_cv and m_knot[0] memory from nurbs_curveA to
02817   // this nurbs surface.
02818   if ( m_cv && m_cv_capacity > 0 )
02819     onfree(m_cv);
02820   m_cv = nurbs_curveA.m_cv;
02821   m_cv_capacity = nurbs_curveA.m_cv_capacity;
02822   nurbs_curveA.m_cv_capacity = 0;
02823 
02824   if ( m_knot[0] && m_knot_capacity[0] > 0 )
02825     onfree(m_knot[0]);
02826   m_knot[0] = nurbs_curveA.m_knot;
02827   m_knot_capacity[0] = nurbs_curveA.m_knot_capacity;
02828   nurbs_curveA.m_knot_capacity = 0;
02829 
02830   // Fill in linear knots
02831   ReserveKnotCapacity( 1, 2 );
02832   m_knot[1][0] = 0.0;
02833   m_knot[1][1] = 1.0;
02834 
02835   m_dim = srf_dim;
02836   m_is_rat = nurbs_curveA.m_is_rat;
02837   m_order[0] = nurbs_curveA.m_order;
02838   m_order[1] = 2;
02839   m_cv_count[0] = nurbs_curveA.m_cv_count;
02840   m_cv_count[1] = 2;
02841   m_cv_stride[0] = nurbs_curveA.m_cv_stride;
02842   m_cv_stride[1] = m_cv_stride[0]/2;
02843 
02844   // fill in "B" row of cvs
02845   for ( int i = 0; i < m_cv_count[0]; i++ )
02846   {
02847     SetCV(i,1,ON::intrinsic_point_style, nurbs_curveB.CV(i));
02848   }
02849 
02850   return ((rcA<=rcB) ? rcB : rcA);
02851 }
02852 
02853 static
02854 ON_3dPoint CornerAt( const ON_Surface& srf, int corner )
02855 {
02856   double s, t;
02857   switch (corner)
02858   {
02859   case 0: // sw
02860     s = srf.Domain(0)[0];
02861     t = srf.Domain(1)[0];
02862     break;
02863   case 1: // se
02864     s = srf.Domain(0)[1];
02865     t = srf.Domain(1)[0];
02866     break;
02867   case 2: // ne
02868     s = srf.Domain(0)[1];
02869     t = srf.Domain(1)[1];
02870     break;
02871   case 3: // nw
02872     s = srf.Domain(0)[0];
02873     t = srf.Domain(1)[1];
02874     break;
02875   default:
02876     return ON_UNSET_POINT;
02877     break;
02878   }
02879   return srf.PointAt(s,t);
02880 }
02881 
02882 bool ON_NurbsSurface::CollapseSide(
02883        int side,
02884        ON_3dPoint point
02885        )
02886 {
02887   if ( point == ON_UNSET_POINT )
02888   {
02889     point = CornerAt(*this,side);
02890     if ( point == ON_UNSET_POINT )
02891       return false;
02892   }
02893 
02894   if ( !m_cv )
02895     return false;
02896 
02897   int i0 = 0;
02898   int i1 = m_cv_count[0];
02899   int j0 = 0;
02900   int j1 = m_cv_count[1];
02901 
02902   switch (side)
02903   {
02904   case 0: // south
02905     j1 = j0+1;
02906     break;
02907   case 1: // east
02908     i0 = i1-1;
02909     break;
02910   case 2: // north
02911     j0 = j1-1;
02912     break;
02913   case 3: // west
02914     i1 = i0+1;
02915     break;
02916   default:
02917     return false;
02918     break;
02919   }
02920 
02921   if ( i0 >= i1 || j0 >= j1 )
02922     return false;
02923 
02924   int i, j;
02925   ON_4dPoint cv;
02926   for ( i = i0; i < i1; i++ ) for ( j = j0; j < j1; j++ )
02927   {
02928     if ( !GetCV(i,j,cv) )
02929       return false;
02930     cv.x = point.x*cv.w;
02931     cv.y = point.y*cv.w;
02932     cv.z = point.z*cv.w;
02933     if ( !SetCV(i,j,cv) )
02934       return false;
02935   }
02936   return true;
02937 }
02938 
02939 int ON_NurbsSurface::CreateConeSurface(
02940        ON_3dPoint apex_point,
02941        const ON_Curve& curve,
02942        const ON_Interval* curve_domain
02943        )
02944 {
02945   DestroySurfaceTree();
02946   ON_NurbsCurve nurbs_curve;
02947   if ( m_cv && m_cv_capacity == 0 )
02948     nurbs_curve.m_cv = m_cv;
02949   if ( m_knot[0] && m_knot_capacity[0] == 0 )
02950     nurbs_curve.m_knot = m_knot[0];
02951   int rc = curve.GetNurbForm( nurbs_curve, 0.0, curve_domain );
02952   if (rc>0)
02953   {
02954     // reserve enough room in nurbs_curve.m_cv 
02955     // for two rows of surface cvs.
02956     nurbs_curve.ChangeDimension(3);
02957     const int is_rat = nurbs_curve.m_is_rat?1:0;
02958     if ( is_rat )
02959     {
02960       nurbs_curve.m_is_rat = 0;
02961       nurbs_curve.m_dim++;
02962     }
02963     nurbs_curve.ChangeDimension( 2*nurbs_curve.m_dim );
02964     nurbs_curve.m_is_rat = is_rat;
02965     nurbs_curve.m_dim = 3;
02966 
02967     // transfer m_cv and m_knot[0] memory from nurbs_curve to
02968     // this nurbs surface.
02969     if ( m_cv && m_cv_capacity > 0 )
02970       onfree(m_cv);
02971     m_cv = nurbs_curve.m_cv;
02972     m_cv_capacity = nurbs_curve.m_cv_capacity;
02973     nurbs_curve.m_cv_capacity = 0;
02974 
02975     if ( m_knot[0] && m_knot_capacity[0] > 0 )
02976       onfree(m_knot[0]);
02977     m_knot[0] = nurbs_curve.m_knot;
02978     m_knot_capacity[0] = nurbs_curve.m_knot_capacity;
02979     nurbs_curve.m_knot_capacity = 0;
02980 
02981     // Fill in linear knots
02982     ReserveKnotCapacity( 1, 2 );
02983     m_knot[1][0] = 0.0;
02984     m_knot[1][1] = 1.0;
02985 
02986     m_dim = 3;
02987     m_is_rat = is_rat;
02988     m_order[0] = nurbs_curve.m_order;
02989     m_order[1] = 2;
02990     m_cv_count[0] = nurbs_curve.m_cv_count;
02991     m_cv_count[1] = 2;
02992     m_cv_stride[0] = nurbs_curve.m_cv_stride;
02993     m_cv_stride[1] = nurbs_curve.m_cv_stride/2;
02994 
02995     for ( int i = 0; i < m_cv_count[0]; i++ )
02996     {
02997       SetCV(i,1,apex_point);
02998       if ( is_rat )
02999       {
03000         double* cv = CV(i,1);
03001         double w = Weight(i,0);
03002         cv[0] *= w;
03003         cv[1] *= w;
03004         cv[2] *= w;
03005         cv[3] = w;
03006       }
03007     }
03008   }
03009   else
03010     Destroy();
03011   return rc;
03012 }
03013 
03014 
03015 
03016 ON_NurbsSurface* ON_NurbsSurfaceQuadrilateral( 
03017              const ON_3dPoint& P, 
03018              const ON_3dPoint& Q, 
03019              const ON_3dPoint& R, 
03020              const ON_3dPoint& S,
03021              ON_NurbsSurface* nurbs_surface
03022              )
03023 {
03024   if ( !nurbs_surface )
03025     nurbs_surface = new ON_NurbsSurface( 3, false, 2, 2, 2, 2 );
03026   else
03027     nurbs_surface->Create( 3, false, 2, 2, 2, 2 );
03028   nurbs_surface->SetCV(0,0,P);
03029   nurbs_surface->SetCV(1,0,Q);
03030   nurbs_surface->SetCV(1,1,R);
03031   nurbs_surface->SetCV(0,1,S);
03032   double d1 = P.DistanceTo(Q);
03033   double d2 = R.DistanceTo(S);
03034   double d = (d1 >= d2) ? d1 : d2;
03035   if (d <= ON_ZERO_TOLERANCE )
03036     d = 1.0;
03037   nurbs_surface->m_knot[0][0] = 0.0;
03038   nurbs_surface->m_knot[0][1] = d;
03039   d1 = P.DistanceTo(S);
03040   d2 = Q.DistanceTo(R);
03041   d = (d1 >= d2) ? d1 : d2;
03042   if (d <= ON_ZERO_TOLERANCE )
03043     d = 1.0;
03044   nurbs_surface->m_knot[1][0] = 0.0;
03045   nurbs_surface->m_knot[1][1] = d;
03046   return nurbs_surface;
03047 }
03048 
03049 ON_BOOL32 ON_NurbsSurface::ConvertSpanToBezier(
03050     int span_index0,
03051     int span_index1, 
03052     ON_BezierSurface& bezier_surface
03053     ) const
03054 {
03055   int i, j;
03056   if ( !m_cv || !m_knot[0] || !m_knot[1] )
03057     return false;
03058   if ( span_index0 < 0 ||  span_index0 > m_cv_count[0]-m_order[0] )
03059     return false;
03060   if ( span_index1 < 0 ||  span_index1 > m_cv_count[1]-m_order[1] )
03061     return false;
03062   i = span_index0+m_order[0]-2;
03063   if ( m_knot[0][i] >= m_knot[0][i+1] )
03064     return false;
03065   j = span_index1+m_order[1]-2;
03066   if ( m_knot[1][j] >= m_knot[1][j+1] )
03067     return false;
03068   {
03069     ON_NurbsSurface bispan;
03070     bispan.m_cv = bezier_surface.m_cv;
03071     bispan.m_cv_capacity = bezier_surface.m_cv_capacity;
03072     bispan.Create( m_dim, m_is_rat, m_order[0], m_order[1], m_order[0], m_order[1] );
03073     const int sizeof_cv = CVSize()*sizeof(*bispan.m_cv);
03074     for ( i = 0; i < m_order[0]; i++ ) for ( j = 0; j < m_order[1]; j++ )
03075     {
03076       memcpy( bispan.CV(i,j), CV(span_index0+i,span_index1+j), sizeof_cv ); 
03077     }
03078     i = span_index0+m_order[0]-2;
03079     j = span_index1+m_order[1]-2;
03080     ON_BOOL32 bClamp = false;
03081     if ( m_knot[0][span_index0] != m_knot[0][span_index0+m_order[0]-2] )
03082       bClamp = true;
03083     if ( m_knot[0][span_index0+m_order[0]-1] != m_knot[0][span_index0+2*m_order[0]-3] )
03084       bClamp = true;
03085     if ( m_knot[1][span_index1] != m_knot[1][span_index1+m_order[1]-2] )
03086       bClamp = true;
03087     if ( m_knot[1][span_index1+m_order[1]-1] != m_knot[1][span_index1+2*m_order[1]-3] )
03088       bClamp = true;
03089     if ( bClamp )
03090     {
03091       memcpy( bispan.m_knot[0], m_knot[0]+span_index0, bispan.KnotCount(0)*sizeof(bispan.m_knot[0][0]) );
03092       memcpy( bispan.m_knot[1], m_knot[1]+span_index1, bispan.KnotCount(1)*sizeof(bispan.m_knot[1][0]) );
03093       bispan.ClampEnd(1,2);
03094       bispan.ClampEnd(0,2);
03095     }
03096     bezier_surface.m_dim = bispan.m_dim;
03097     bezier_surface.m_is_rat = bispan.m_is_rat;
03098     bezier_surface.m_order[0] = bispan.m_order[0];
03099     bezier_surface.m_order[1] = bispan.m_order[1];
03100     bezier_surface.m_cv_stride[0] = bispan.m_cv_stride[0];
03101     bezier_surface.m_cv_stride[1] = bispan.m_cv_stride[1];
03102     bezier_surface.m_cv = bispan.m_cv;
03103     bezier_surface.m_cv_capacity = bispan.m_cv_capacity;
03104     bispan.m_cv = 0;
03105     bispan.m_cv_capacity = 0;
03106   }
03107   return true;
03108 }


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