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 #if !defined(OPENNURBS_BEZIER_INC_) 00018 #define OPENNURBS_BEZIER_INC_ 00019 00020 class ON_PolynomialCurve; 00021 class ON_PolynomialSurface; 00022 class ON_BezierCurve; 00023 class ON_BezierSurface; 00024 class ON_TextLog; 00025 class ON_NurbsCurve; 00026 class ON_NurbsSurface; 00027 class ON_X_EVENT; 00028 00029 class ON_CLASS ON_PolynomialCurve 00030 { 00031 public: 00032 ON_PolynomialCurve(); 00033 00034 // Description: 00035 // See ON_PolynomialCurve::Create. 00036 // Parameters: 00037 // dim - [in] dimension of the curve 00038 // bIsRational - [in] true if rational 00039 // order - [in] (>=2) order = degree+1 00040 ON_PolynomialCurve( 00041 int dim, 00042 ON_BOOL32 bIsRational, 00043 int order 00044 ); 00045 00046 ~ON_PolynomialCurve(); 00047 00048 ON_PolynomialCurve(const ON_PolynomialCurve&); 00049 00050 ON_PolynomialCurve(const ON_BezierCurve&); 00051 00052 ON_PolynomialCurve& operator=(const ON_PolynomialCurve&); 00053 00054 ON_PolynomialCurve& operator=(const ON_BezierCurve&); 00055 00056 // Description: 00057 // Initializes fields and allocates the m_cv array. 00058 // Parameters: 00059 // dim - [in] dimension of the curve 00060 // bIsRational - [in] true if rational 00061 // order - [in] (>=2) order = degree+1 00062 ON_BOOL32 Create( 00063 int dim, 00064 ON_BOOL32 bIsRational, 00065 int order 00066 ); 00067 00068 // Description: 00069 // Deallocates the m_cv array and sets fields to zero. 00070 void Destroy(); 00071 00072 // Description: 00073 // Evaluate a polynomial curve. 00074 // Parameters: 00075 // t - [in] evaluation parameter ( usually in Domain() ). 00076 // der_count - [in] (>=0) number of derivatives to evaluate 00077 // v_stride - [in] (>=Dimension()) stride to use for the v[] array 00078 // v - [out] array of length (der_count+1)*v_stride 00079 // curve(t) is returned in (v[0],...,v[m_dim-1]), 00080 // curve'(t) is retuned in (v[v_stride],...,v[v_stride+m_dim-1]), 00081 // curve"(t) is retuned in (v[2*v_stride],...,v[2*v_stride+m_dim-1]), 00082 // etc. 00083 // Returns: 00084 // false if unable to evaluate. 00085 ON_BOOL32 Evaluate( 00086 double t, 00087 int der_count, 00088 int v_stride, 00089 double* v 00090 ) const; 00091 00092 // dimension of polynomial curve (1,2, or 3) 00093 int m_dim; 00094 00095 // 1 if polynomial curve is rational, 0 if polynomial curve is not rational 00096 int m_is_rat; 00097 00098 // order (=degree+1) of polynomial 00099 int m_order; 00100 00101 // coefficients ( m_cv.Count() = order of monomial ) 00102 ON_4dPointArray m_cv; 00103 00104 // domain of polynomial 00105 ON_Interval m_domain; 00106 }; 00107 00108 class ON_CLASS ON_PolynomialSurface 00109 { 00110 public: 00111 ON_PolynomialSurface(); 00112 ON_PolynomialSurface( 00113 int, // dim, 00114 ON_BOOL32, // true if rational 00115 int, // "u" order 00116 int // "v" order 00117 ); 00118 ~ON_PolynomialSurface(); 00119 ON_PolynomialSurface(const ON_PolynomialSurface&); 00120 ON_PolynomialSurface(const ON_BezierSurface&); 00121 ON_PolynomialSurface& operator=(const ON_PolynomialSurface&); 00122 ON_PolynomialSurface& operator=(const ON_BezierSurface&); 00123 00124 ON_BOOL32 Create( 00125 int, // dim, 00126 ON_BOOL32, // true if rational 00127 int, // "u" order 00128 int // "v" order 00129 ); 00130 void Destroy(); 00131 00132 ON_BOOL32 Evaluate( // returns false if unable to evaluate 00133 double s, 00134 double t, // evaluation parameter 00135 int der_count, // number of derivatives (>=0) 00136 int v_stride, // array stride (>=Dimension()) 00137 double* v // array of length stride*(ndir+1)*(ndir+2)/2 00138 ) const; 00139 00140 int m_dim; // 1,2, or 3 00141 int m_is_rat; // 1 if rational, 0 if not rational 00142 int m_order[2]; 00143 ON_4dPointArray m_cv; // coefficients ( m_C.Length() = m_order[0]*m_order[1] 00144 // coefficient of s^m*t^n = m_cv[m_order[1]*m+n] 00145 ON_Interval m_domain[2]; 00146 }; 00147 00148 class ON_CLASS ON_BezierCurve 00149 { 00150 public: 00151 00152 ON_BezierCurve(); 00153 00154 // Description: 00155 // Creates a bezier with cv memory allocated. 00156 // Parameters: 00157 // dim - [in] (>0) dimension of bezier curve 00158 // bIsRational - [in] true for a rational bezier 00159 // order - [in] (>=2) order (=degree+1) of bezier curve 00160 ON_BezierCurve( 00161 int dim, 00162 ON_BOOL32 bIsRational, 00163 int order 00164 ); 00165 00166 ~ON_BezierCurve(); 00167 ON_BezierCurve(const ON_BezierCurve&); 00168 ON_BezierCurve(const ON_PolynomialCurve&); 00169 ON_BezierCurve(const ON_2dPointArray&); // sets control points 00170 ON_BezierCurve(const ON_3dPointArray&); // sets control points 00171 ON_BezierCurve(const ON_4dPointArray&); // sets control points 00172 ON_BezierCurve& operator=(const ON_BezierCurve&); 00173 ON_BezierCurve& operator=(const ON_PolynomialCurve&); 00174 00175 00176 ON_BezierCurve& operator=(const ON_2dPointArray&); // sets control points 00177 ON_BezierCurve& operator=(const ON_3dPointArray&); // sets control points 00178 ON_BezierCurve& operator=(const ON_4dPointArray&); // sets control points 00179 00180 bool IsValid() const; 00181 00182 void Dump( ON_TextLog& ) const; // for debugging 00183 00184 // Returns: 00185 // Dimension of bezier. 00186 int Dimension() const; 00187 00188 // Description: 00189 // Creates a bezier with cv memory allocated. 00190 // Parameters: 00191 // dim - [in] (>0) dimension of bezier curve 00192 // bIsRational - [in] true for a rational bezier 00193 // order - [in] (>=2) order (=degree+1) of bezier curve 00194 // Returns: 00195 // true if successful. 00196 bool Create( 00197 int dim, 00198 ON_BOOL32 bIsRational, 00199 int order 00200 ); 00201 00202 // Description: 00203 // Deallocates m_cv memory. 00204 void Destroy(); 00205 00206 void EmergencyDestroy(); // call if memory used by ON_NurbsCurve becomes invalid 00207 00208 // Description: 00209 // Loft a bezier curve through a list of points. 00210 // Parameters: 00211 // points - [in] an array of 2 or more points to interpolate 00212 // Returns: 00213 // true if successful 00214 // Remarks: 00215 // The result has order = points.Count() and the loft uses the 00216 // uniform parameterizaton curve( i/(points.Count()-1) ) = points[i]. 00217 bool Loft( 00218 const ON_3dPointArray& points 00219 ); 00220 00221 // Description: 00222 // Loft a bezier curve through a list of points. 00223 // Parameters: 00224 // pt_dim - [in] dimension of points to interpolate 00225 // pt_count - [in] number of points (>=2) 00226 // pt_stride - [in] (>=pt_dim) pt[] array stride 00227 // pt - [in] array of points 00228 // t_stride - [in] (>=1) t[] array stride 00229 // t - [in] strictly increasing array of interpolation parameters 00230 // Returns: 00231 // true if successful 00232 // Remarks: 00233 // The result has order = points.Count() and the loft uses the 00234 // parameterizaton curve( t[i] ) = points[i]. 00235 bool Loft( 00236 int pt_dim, 00237 int pt_count, 00238 int pt_stride, 00239 const double* pt, 00240 int t_stride, 00241 const double* t 00242 ); 00243 00244 // Description: 00245 // Gets bounding box. 00246 // Parameters: 00247 // box_min - [out] minimum corner of axis aligned bounding box 00248 // The box_min[] array must have size m_dim. 00249 // box_max - [out] maximum corner of axis aligned bounding box 00250 // The box_max[] array must have size m_dim. 00251 // bGrowBox - [in] if true, input box_min/box_max must be set 00252 // to valid bounding box corners and this box is enlarged to 00253 // be the union of the input box and the bezier's bounding 00254 // box. 00255 // Returns: 00256 // true if successful. 00257 bool GetBBox( // returns true if successful 00258 double* box_min, 00259 double* box_max, 00260 int bGrowBox = false 00261 ) const; 00262 00263 // Description: 00264 // Gets bounding box. 00265 // Parameters: 00266 // bbox - [out] axis aligned bounding box returned here. 00267 // bGrowBox - [in] if true, input bbox must be a valid 00268 // bounding box and this box is enlarged to 00269 // be the union of the input box and the 00270 // bezier's bounding box. 00271 // Returns: 00272 // true if successful. 00273 bool GetBoundingBox( 00274 ON_BoundingBox& bbox, 00275 int bGrowBox = false 00276 ) const; 00277 00278 // Description: 00279 // Gets bounding box. 00280 // Returns: 00281 // Axis aligned bounding box. 00282 ON_BoundingBox BoundingBox() const; 00283 00284 /* 00285 Description: 00286 Get tight bounding box of the bezier. 00287 Parameters: 00288 tight_bbox - [in/out] tight bounding box 00289 bGrowBox -[in] (default=false) 00290 If true and the input tight_bbox is valid, then returned 00291 tight_bbox is the union of the input tight_bbox and the 00292 tight bounding box of the bezier curve. 00293 xform -[in] (default=NULL) 00294 If not NULL, the tight bounding box of the transformed 00295 bezier is calculated. The bezier curve is not modified. 00296 Returns: 00297 True if the returned tight_bbox is set to a valid 00298 bounding box. 00299 */ 00300 bool GetTightBoundingBox( 00301 ON_BoundingBox& tight_bbox, 00302 int bGrowBox = false, 00303 const ON_Xform* xform = 0 00304 ) const; 00305 00306 // Description: 00307 // Transform the bezier. 00308 // Parameters: 00309 // xform - [in] transformation to apply to bezier 00310 // Returns: 00311 // true if successful. false if bezier is invalid 00312 // and cannot be transformed. 00313 bool Transform( 00314 const ON_Xform& xform 00315 ); 00316 00317 // Description: 00318 // Rotates the bezier curve about the specified axis. A positive 00319 // rotation angle results in a counter-clockwise rotation 00320 // about the axis (right hand rule). 00321 // Parameters: 00322 // sin_angle - [in] sine of rotation angle 00323 // cos_angle - [in] sine of rotation angle 00324 // rotation_axis - [in] direction of the axis of rotation 00325 // rotation_center - [in] point on the axis of rotation 00326 // Returns: 00327 // true if bezier curve successfully rotated 00328 // Remarks: 00329 // Uses ON_BezierCurve::Transform() function to calculate the result. 00330 bool Rotate( 00331 double sin_angle, 00332 double cos_angle, 00333 const ON_3dVector& rotation_axis, 00334 const ON_3dPoint& rotation_center 00335 ); 00336 00337 // Description: 00338 // Rotates the bezier curve about the specified axis. A positive 00339 // rotation angle results in a counter-clockwise rotation 00340 // about the axis (right hand rule). 00341 // Parameters: 00342 // rotation_angle - [in] angle of rotation in radians 00343 // rotation_axis - [in] direction of the axis of rotation 00344 // rotation_center - [in] point on the axis of rotation 00345 // Returns: 00346 // true if bezier curve successfully rotated 00347 // Remarks: 00348 // Uses ON_BezierCurve::Transform() function to calculate the result. 00349 bool Rotate( 00350 double rotation_angle, 00351 const ON_3dVector& rotation_axis, 00352 const ON_3dPoint& rotation_center 00353 ); 00354 00355 // Description: 00356 // Translates the bezier curve along the specified vector. 00357 // Parameters: 00358 // translation_vector - [in] translation vector 00359 // Returns: 00360 // true if bezier curve successfully translated 00361 // Remarks: 00362 // Uses ON_BezierCurve::Transform() function to calculate the result. 00363 bool Translate( 00364 const ON_3dVector& translation_vector 00365 ); 00366 00367 // Description: 00368 // Scales the bezier curve by the specified facotor. The scale is 00369 // centered at the origin. 00370 // Parameters: 00371 // scale_factor - [in] scale factor 00372 // Returns: 00373 // true if bezier curve successfully scaled 00374 // Remarks: 00375 // Uses ON_BezierCurve::Transform() function to calculate the result. 00376 bool Scale( 00377 double scale_factor 00378 ); 00379 00380 // Returns: 00381 // Domain of bezier (always [0,1]). 00382 ON_Interval Domain() const; 00383 00384 // Description: 00385 // Reverses bezier by reversing the order 00386 // of the control points. 00387 bool Reverse(); 00388 00389 // Description: 00390 // Evaluate point at a parameter. 00391 // Parameters: 00392 // t - [in] evaluation parameter 00393 // Returns: 00394 // Point (location of curve at the parameter t). 00395 ON_3dPoint PointAt( 00396 double t 00397 ) const; 00398 00399 // Description: 00400 // Evaluate first derivative at a parameter. 00401 // Parameters: 00402 // t - [in] evaluation parameter 00403 // Returns: 00404 // First derivative of the curve at the parameter t. 00405 // Remarks: 00406 // No error handling. 00407 // See Also: 00408 // ON_Curve::Ev1Der 00409 ON_3dVector DerivativeAt( 00410 double t 00411 ) const; 00412 00413 // Description: 00414 // Evaluate unit tangent vector at a parameter. 00415 // Parameters: 00416 // t - [in] evaluation parameter 00417 // Returns: 00418 // Unit tangent vector of the curve at the parameter t. 00419 // Remarks: 00420 // No error handling. 00421 // See Also: 00422 // ON_Curve::EvTangent 00423 ON_3dVector TangentAt( 00424 double t 00425 ) const; 00426 00427 // Description: 00428 // Evaluate the curvature vector at a parameter. 00429 // Parameters: 00430 // t - [in] evaluation parameter 00431 // Returns: 00432 // curvature vector of the curve at the parameter t. 00433 // Remarks: 00434 // No error handling. 00435 // See Also: 00436 // ON_Curve::EvCurvature 00437 ON_3dVector CurvatureAt( 00438 double t 00439 ) const; 00440 00441 // Description: 00442 // Evaluate point at a parameter with error checking. 00443 // Parameters: 00444 // t - [in] evaluation parameter 00445 // point - [out] value of curve at t 00446 // Returns: 00447 // false if unable to evaluate. 00448 bool EvPoint( 00449 double t, 00450 ON_3dPoint& point 00451 ) const; 00452 00453 // Description: 00454 // Evaluate first derivative at a parameter with error checking. 00455 // Parameters: 00456 // t - [in] evaluation parameter 00457 // point - [out] value of curve at t 00458 // first_derivative - [out] value of first derivative at t 00459 // Returns: 00460 // false if unable to evaluate. 00461 bool Ev1Der( 00462 double t, 00463 ON_3dPoint& point, 00464 ON_3dVector& first_derivative 00465 ) const; 00466 00467 // Description: 00468 // Evaluate second derivative at a parameter with error checking. 00469 // Parameters: 00470 // t - [in] evaluation parameter 00471 // point - [out] value of curve at t 00472 // first_derivative - [out] value of first derivative at t 00473 // second_derivative - [out] value of second derivative at t 00474 // Returns: 00475 // false if unable to evaluate. 00476 bool Ev2Der( 00477 double t, 00478 ON_3dPoint& point, 00479 ON_3dVector& first_derivative, 00480 ON_3dVector& second_derivative 00481 ) const; 00482 00483 /* 00484 Description: 00485 Evaluate unit tangent at a parameter with error checking. 00486 Parameters: 00487 t - [in] evaluation parameter 00488 point - [out] value of curve at t 00489 tangent - [out] value of unit tangent 00490 Returns: 00491 false if unable to evaluate. 00492 See Also: 00493 ON_Curve::TangentAt 00494 ON_Curve::Ev1Der 00495 */ 00496 bool EvTangent( 00497 double t, 00498 ON_3dPoint& point, 00499 ON_3dVector& tangent 00500 ) const; 00501 00502 /* 00503 Description: 00504 Evaluate unit tangent and curvature at a parameter with error checking. 00505 Parameters: 00506 t - [in] evaluation parameter 00507 point - [out] value of curve at t 00508 tangent - [out] value of unit tangent 00509 kappa - [out] value of curvature vector 00510 Returns: 00511 false if unable to evaluate. 00512 */ 00513 bool EvCurvature( 00514 double t, 00515 ON_3dPoint& point, 00516 ON_3dVector& tangent, 00517 ON_3dVector& kappa 00518 ) const; 00519 00520 // Description: 00521 // Evaluate a bezier. 00522 // Parameters: 00523 // t - [in] evaluation parameter (usually 0 <= t <= 1) 00524 // der_count - [in] (>=0) number of derivatives to evaluate 00525 // v_stride - [in] (>=m_dim) stride to use for the v[] array 00526 // v - [out] array of length (der_count+1)*v_stride 00527 // bez(t) is returned in (v[0],...,v[m_dim-1]), 00528 // bez'(t) is retuned in (v[v_stride],...,v[v_stride+m_dim-1]), 00529 // bez"(t) is retuned in (v[2*v_stride],...,v[2*v_stride+m_dim-1]), 00530 // etc. 00531 // Returns: 00532 // true if successful 00533 bool Evaluate( 00534 double t, 00535 int der_count, 00536 int v_stride, 00537 double* v 00538 ) const; 00539 00540 // Description: 00541 // Get ON_NurbsCurve form of a bezier. 00542 // Parameters: 00543 // nurbs_curve - [out] NURBS curve form of a bezier. 00544 // The domain is [0,1]. 00545 // Returns: 00546 // true if successful 00547 bool GetNurbForm( 00548 ON_NurbsCurve& nurbs_curve 00549 ) const; 00550 00551 // Returns: 00552 // true if bezier is rational. 00553 bool IsRational() const; 00554 00555 // Returns: 00556 // Number of doubles per control vertex. 00557 // (= IsRational() ? Dim()+1 : Dim()) 00558 int CVSize() const; 00559 00560 // Returns: 00561 // Number of control vertices in the bezier. 00562 // This is always the same as the order of the bezier. 00563 int CVCount() const; 00564 00565 // Returns: 00566 // Order of the bezier. (order=degree+1) 00567 int Order() const; // order = degree + 1 00568 00569 // Returns: 00570 // Degree of the bezier. (degree=order-1) 00571 int Degree() const; 00572 00573 /* 00574 Description: 00575 Expert user function to get a pointer to control vertex 00576 memory. If you are not an expert user, please use 00577 ON_BezierCurve::GetCV( ON_3dPoint& ) or 00578 ON_BezierCurve::GetCV( ON_4dPoint& ). 00579 Parameters: 00580 cv_index - [in] (0 <= cv_index < m_order) 00581 Returns: 00582 Pointer to control vertex. 00583 Remarks: 00584 If the Bezier curve is rational, the format of the 00585 returned array is a homogeneos rational point with 00586 length m_dim+1. If the Bezier curve is not rational, 00587 the format of the returned array is a nonrational 00588 euclidean point with length m_dim. 00589 See Also 00590 ON_BezierCurve::CVStyle 00591 ON_BezierCurve::GetCV 00592 ON_BezierCurve::Weight 00593 */ 00594 double* CV( 00595 int cv_index 00596 ) const; 00597 00598 /* 00599 Description: 00600 Returns the style of control vertices in the m_cv array. 00601 Returns: 00602 @untitled table 00603 ON::not_rational m_is_rat is false 00604 ON::homogeneous_rational m_is_rat is true 00605 */ 00606 ON::point_style CVStyle() const; 00607 00608 // Parameters: 00609 // cv_index - [in] control vertex index (0<=i<m_order) 00610 // Returns: 00611 // Weight of the i-th control vertex. 00612 double Weight( 00613 int cv_index 00614 ) const; 00615 00616 // Description: 00617 // Set weight of a control vertex. 00618 // Parameters: 00619 // cv_index - [in] control vertex index (0 <= cv_index < m_order) 00620 // weight - [in] weight 00621 // Returns: 00622 // true if the weight can be set. If weight is not 1 and 00623 // the bezier is not rational, then false is returned. 00624 // Use ON_BezierCurve::MakeRational to make a bezier curve 00625 // rational. 00626 // See Also: 00627 // ON_BezierCurve::SetCV, ON_BezierCurve::MakeRational, 00628 // ON_BezierCurve::IsRational, ON_BezierCurve::Weight 00629 bool SetWeight( 00630 int cv_index, 00631 double weight 00632 ); 00633 00634 // Description: 00635 // Set control vertex 00636 // Parameters: 00637 // cv_index - [in] control vertex index (0 <= cv_index < m_order) 00638 // pointstyle - [in] specifes what kind of values are passed 00639 // in the cv array. 00640 // ON::not_rational 00641 // cv[] is an array of length m_dim that defines 00642 // a euclidean (world coordinate) point 00643 // ON::homogeneous_rational 00644 // cv[] is an array of length (m_dim+1) that defines 00645 // a rational homogeneous point. 00646 // ON::euclidean_rational 00647 // cv[] is an array of length (m_dim+1). The first 00648 // m_dim values define the euclidean (world coordinate) 00649 // location of the point. cv[m_dim] is the weight 00650 // ON::intrinsic_point_style 00651 // If m_is_rat is true, cv[] has ON::homogeneous_rational 00652 // point style. If m_is_rat is false, cv[] has 00653 // ON::not_rational point style. 00654 // cv - [in] array with control vertex value. 00655 // Returns: 00656 // true if the point can be set. 00657 bool SetCV( 00658 int cv_index, 00659 ON::point_style pointstyle, 00660 const double* cv 00661 ); 00662 00663 // Description: 00664 // Set location of a control vertex. 00665 // Parameters: 00666 // cv_index - [in] control vertex index (0 <= cv_index < m_order) 00667 // point - [in] control vertex location. If the bezier 00668 // is rational, the weight will be set to 1. 00669 // Returns: 00670 // true if successful. 00671 // See Also: 00672 // ON_BezierCurve::CV, ON_BezierCurve::SetCV, 00673 // ON_BezierCurve::SetWeight, ON_BezierCurve::Weight 00674 bool SetCV( 00675 int cv_index, 00676 const ON_3dPoint& point 00677 ); 00678 00679 // Description: 00680 // Set value of a control vertex. 00681 // Parameters: 00682 // cv_index - [in] control vertex index (0 <= cv_index < m_order) 00683 // point - [in] control vertex value. If the bezier 00684 // is not rational, the euclidean location of 00685 // homogenoeous point will be used. 00686 // Returns: 00687 // true if successful. 00688 // See Also: 00689 // ON_BezierCurve::CV, ON_BezierCurve::SetCV, 00690 // ON_BezierCurve::SetWeight, ON_BezierCurve::Weight 00691 bool SetCV( 00692 int cv_index, 00693 const ON_4dPoint& point 00694 ); 00695 00696 // Description: 00697 // Get location of a control vertex. 00698 // Parameters: 00699 // cv_index - [in] control vertex index (0 <= cv_index < m_order) 00700 // pointstyle - [in] specifes what kind of values to get 00701 // ON::not_rational 00702 // cv[] is an array of length m_dim that defines 00703 // a euclidean (world coordinate) point 00704 // ON::homogeneous_rational 00705 // cv[] is an array of length (m_dim+1) that defines 00706 // a rational homogeneous point. 00707 // ON::euclidean_rational 00708 // cv[] is an array of length (m_dim+1). The first 00709 // m_dim values define the euclidean (world coordinate) 00710 // location of the point. cv[m_dim] is the weight 00711 // ON::intrinsic_point_style 00712 // If m_is_rat is true, cv[] has ON::homogeneous_rational 00713 // point style. If m_is_rat is false, cv[] has 00714 // ON::not_rational point style. 00715 // cv - [out] array with control vertex value. 00716 // Returns: 00717 // true if successful. false if cv_index is invalid. 00718 bool GetCV( 00719 int cv_index, 00720 ON::point_style pointstyle, 00721 double* cv 00722 ) const; 00723 00724 // Description: 00725 // Get location of a control vertex. 00726 // Parameters: 00727 // cv_index - [in] control vertex index (0 <= cv_index < m_order) 00728 // point - [out] Location of control vertex. If the bezier 00729 // is rational, the euclidean location is returned. 00730 // Returns: 00731 // true if successful. 00732 bool GetCV( 00733 int cv_index, 00734 ON_3dPoint& point 00735 ) const; 00736 00737 // Description: 00738 // Get value of a control vertex. 00739 // Parameters: 00740 // cv_index - [in] control vertex index (0 <= cv_index < m_order) 00741 // point - [out] Homogenous value of control vertex. 00742 // If the bezier is not rational, the weight is 1. 00743 // Returns: 00744 // true if successful. 00745 bool GetCV( 00746 int cv_index, 00747 ON_4dPoint& point 00748 ) const; 00749 00750 // Description: 00751 // Zeros control vertices and, if rational, sets weights to 1. 00752 bool ZeroCVs(); 00753 00754 // Description: 00755 // Make beizer rational. 00756 // Returns: 00757 // true if successful. 00758 // See Also: 00759 // ON_Bezier::MakeNonRational 00760 bool MakeRational(); 00761 00762 // Description: 00763 // Make beizer not rational by setting all control 00764 // vertices to their euclidean locations and setting 00765 // m_is_rat to false. 00766 // See Also: 00767 // ON_Bezier::MakeRational 00768 bool MakeNonRational(); 00769 00770 // Description: 00771 // Increase degree of bezier. 00772 // Parameters: 00773 // desired_degree - [in] 00774 // Returns: 00775 // true if successful. false if desired_degree < current degree. 00776 bool IncreaseDegree( 00777 int desired_degree 00778 ); 00779 00780 // Description: 00781 // Change dimension of bezier. 00782 // Parameters: 00783 // desired_dimension - [in] 00784 // Returns: 00785 // true if successful. false if desired_dimension < 1 00786 bool ChangeDimension( 00787 int desired_dimension 00788 ); 00789 00791 // Tools for managing CV and knot memory 00792 00793 // Description: 00794 // Make sure m_cv array has a certain length. 00795 // Parameters: 00796 // desired_cv_capacity - [in] minimum length of m_cv array. 00797 // Returns: 00798 // true if successful. 00799 bool ReserveCVCapacity( 00800 int desired_cv_capacity 00801 ); 00802 00803 // Description: 00804 // Trims (or extends) the bezier so the bezier so that the 00805 // result starts bezier(interval[0]) and ends at 00806 // bezier(interval[1]) (Evaluation performed on input bezier.) 00807 // Parameters: 00808 // interval -[in] 00809 // Example: 00810 // An interval of [0,1] leaves the bezier unchanged. An 00811 // interval of [0.5,1] would trim away the left half. An 00812 // interval of [0.0,2.0] would extend the right end. 00813 bool Trim( 00814 const ON_Interval& interval 00815 ); 00816 00817 // Description: 00818 // Split() divides the Bezier curve at the specified parameter. 00819 // The parameter must satisfy 0 < t < 1. You may pass *this as 00820 // one of the curves to be returned. 00821 // Parameters: 00822 // t - [in] (0 < t < 1 ) parameter to split at 00823 // left_side - [out] 00824 // right_side - [out] 00825 // Example: 00826 // ON_BezierCurve crv = ...; 00827 // ON_BezierCurve right_side; 00828 // crv.Split( 0.5, crv, right_side ); 00829 // would split crv at the 1/2, put the left side in crv, 00830 // and return the right side in right_side. 00831 bool Split( 00832 double t, 00833 ON_BezierCurve& left_side, 00834 ON_BezierCurve& right_side 00835 ) const; 00836 00837 // Description: 00838 // returns the length of the control polygon 00839 double ControlPolygonLength() const; 00840 00841 /* 00842 Description: 00843 Use a linear fractional tranformation for [0,1] to reparameterize 00844 the bezier. The locus of the curve is not changed, but the 00845 parameterization is changed. 00846 Parameters: 00847 c - [in] 00848 reparameterization constant (generally speaking, c should be > 0). 00849 If c != 1, then the returned bezier will be rational. 00850 Returns: 00851 true if successful. 00852 Remarks: 00853 The reparameterization is performed by composing the input Bezier with 00854 the function lambda: [0,1] -> [0,1] given by 00855 00856 t -> c*t / ( (c-1)*t + 1 ) 00857 00858 Note that lambda(0) = 0, lambda(1) = 1, lambda'(t) > 0, 00859 lambda'(0) = c and lambda'(1) = 1/c. 00860 00861 If the input Bezier has control vertices {B_0, ..., B_d}, then the 00862 output Bezier has control vertices 00863 00864 (B_0, ... c^i * B_i, ..., c^d * B_d). 00865 00866 To derive this formula, simply compute the i-th Bernstein polynomial 00867 composed with lambda(). 00868 00869 The inverse parameterization is given by 1/c. That is, the 00870 cumulative effect of the two calls 00871 00872 Reparameterize(c) 00873 Reparameterize(1.0/c) 00874 00875 is to leave the bezier unchanged. 00876 See Also: 00877 ON_Bezier::ScaleConrolPoints 00878 */ 00879 bool Reparameterize( 00880 double c 00881 ); 00882 00883 // misspelled function name is obsolete 00884 ON_DEPRECATED bool Reparametrize(double); 00885 00886 /* 00887 Description: 00888 Scale a rational Bezier's control vertices to set a weight to a 00889 specified value. 00890 Parameters: 00891 i - [in] (0 <= i < order) 00892 w - [in] w != 0.0 00893 Returns: 00894 True if successful. The i-th control vertex will have weight w. 00895 Remarks: 00896 Each control point is multiplied by w/w0, where w0 is the 00897 input value of Weight(i). 00898 See Also: 00899 ON_Bezier::Reparameterize 00900 ON_Bezier::ChangeWeights 00901 */ 00902 bool ScaleConrolPoints( 00903 int i, 00904 double w 00905 ); 00906 00907 /* 00908 Description: 00909 Use a combination of scaling and reparameterization to set two 00910 rational Bezier weights to specified values. 00911 Parameters: 00912 i0 - [in] control point index (0 <= i0 < order, i0 != i1) 00913 w0 - [in] Desired weight for i0-th control point 00914 i1 - [in] control point index (0 <= i1 < order, i0 != i1) 00915 w1 - [in] Desired weight for i1-th control point 00916 Returns: 00917 True if successful. The returned bezier has the same locus but 00918 probably has a different parameterization. 00919 Remarks: 00920 The i0-th cv will have weight w0 and the i1-rst cv will have 00921 weight w1. If v0 and v1 are the cv's input weights, 00922 then v0, v1, w0 and w1 must all be nonzero, and w0*v0 00923 and w1*v1 must have the same sign. 00924 00925 The equations 00926 00927 s * r^i0 = w0/v0 00928 s * r^i1 = w1/v1 00929 00930 determine the scaling and reparameterization necessary to 00931 change v0,v1 to w0,w1. 00932 00933 If the input Bezier has control vertices 00934 00935 (B_0, ..., B_d), 00936 00937 then the output Bezier has control vertices 00938 00939 (s*B_0, ... s*r^i * B_i, ..., s*r^d * B_d). 00940 See Also: 00941 ON_Bezier::Reparameterize 00942 ON_Bezier::ScaleConrolPoints 00943 */ 00944 bool ChangeWeights( 00945 int i0, 00946 double w0, 00947 int i1, 00948 double w1 00949 ); 00950 00952 // Implementation 00953 public: 00954 // NOTE: These members are left "public" so that expert users may efficiently 00955 // create bezier curves using the default constructor and borrow the 00956 // knot and CV arrays from their native NURBS representation. 00957 // No technical support will be provided for users who access these 00958 // members directly. If you can't get your stuff to work, then use 00959 // the constructor with the arguments and the SetKnot() and SetCV() 00960 // functions to fill in the arrays. 00961 00962 00963 // dimension of bezier (>=1) 00964 int m_dim; 00965 00966 // 1 if bezier is rational, 0 if bezier is not rational 00967 int m_is_rat; 00968 00969 // order = degree+1 00970 int m_order; 00971 00972 // Number of doubles per cv ( >= ((m_is_rat)?m_dim+1:m_dim) ) 00973 int m_cv_stride; 00974 00975 // The i-th cv begins at cv[i*m_cv_stride]. 00976 double* m_cv; 00977 00978 // Number of doubles in m_cv array. If m_cv_capacity is zero 00979 // and m_cv is not NULL, an expert user is managing the m_cv 00980 // memory. ~ON_BezierCurve will not deallocate m_cv unless 00981 // m_cv_capacity is greater than zero. 00982 int m_cv_capacity; 00983 00984 #if 8 == ON_SIZEOF_POINTER 00985 // pad to a multiple of 8 bytes so custom allocators 00986 // will keep m_cv aligned and tail-padding reuse will 00987 // not be an issue. 00988 int m_reserved_ON_BezierCurve; 00989 #endif 00990 }; 00991 00992 00993 class ON_CLASS ON_BezierSurface 00994 { 00995 public: 00996 ON_BezierSurface(); 00997 ON_BezierSurface( 00998 int dim, 00999 int is_rat, 01000 int order0, 01001 int order1 01002 ); 01003 01004 ~ON_BezierSurface(); 01005 ON_BezierSurface(const ON_BezierSurface&); 01006 ON_BezierSurface(const ON_PolynomialSurface&); 01007 ON_BezierSurface& operator=(const ON_BezierSurface&); 01008 ON_BezierSurface& operator=(const ON_PolynomialSurface&); 01009 01010 bool IsValid() const; 01011 void Dump( ON_TextLog& ) const; // for debugging 01012 int Dimension() const; 01013 01014 bool Create( 01015 int dim, 01016 int is_rat, 01017 int order0, 01018 int order1 01019 ); 01020 01021 void Destroy(); 01022 void EmergencyDestroy(); // call if memory used by ON_NurbsCurve becomes invalid 01023 01024 /* 01025 Description: 01026 Loft a bezier surface through a list of bezier curves. 01027 Parameters: 01028 curve_list - [in] list of curves that have the same degree. 01029 Returns: 01030 True if successful. 01031 */ 01032 bool Loft( const ON_ClassArray<ON_BezierCurve>& curve_list ); 01033 01034 /* 01035 Description: 01036 Loft a bezier surface through a list of bezier curves. 01037 Parameters: 01038 curve_count - [in] number of curves in curve_list 01039 curve_list - [in] array of pointers to curves that have the same degree. 01040 Returns: 01041 True if successful. 01042 */ 01043 bool Loft( 01044 int count, 01045 const ON_BezierCurve* const* curve_list 01046 ); 01047 01048 bool GetBBox( // returns true if successful 01049 double*, // minimum 01050 double*, // maximum 01051 int bGrowBox = false // true means grow box 01052 ) const; 01053 01054 bool GetBoundingBox( 01055 ON_BoundingBox& bbox, 01056 int bGrowBox 01057 ) const; 01058 01059 ON_BoundingBox BoundingBox() const; 01060 01061 bool Transform( 01062 const ON_Xform& 01063 ); 01064 01065 // Description: 01066 // Rotates the bezier surface about the specified axis. A positive 01067 // rotation angle results in a counter-clockwise rotation 01068 // about the axis (right hand rule). 01069 // Parameters: 01070 // sin_angle - [in] sine of rotation angle 01071 // cos_angle - [in] sine of rotation angle 01072 // rotation_axis - [in] direction of the axis of rotation 01073 // rotation_center - [in] point on the axis of rotation 01074 // Returns: 01075 // true if bezier surface successfully rotated 01076 // Remarks: 01077 // Uses ON_BezierSurface::Transform() function to calculate the result. 01078 bool Rotate( 01079 double sin_angle, 01080 double cos_angle, 01081 const ON_3dVector& rotation_axis, 01082 const ON_3dPoint& rotation_center 01083 ); 01084 01085 // Description: 01086 // Rotates the bezier surface about the specified axis. A positive 01087 // rotation angle results in a counter-clockwise rotation 01088 // about the axis (right hand rule). 01089 // Parameters: 01090 // rotation_angle - [in] angle of rotation in radians 01091 // rotation_axis - [in] direction of the axis of rotation 01092 // rotation_center - [in] point on the axis of rotation 01093 // Returns: 01094 // true if bezier surface successfully rotated 01095 // Remarks: 01096 // Uses ON_BezierSurface::Transform() function to calculate the result. 01097 bool Rotate( 01098 double rotation_angle, 01099 const ON_3dVector& rotation_axis, 01100 const ON_3dPoint& rotation_center 01101 ); 01102 01103 // Description: 01104 // Translates the bezier surface along the specified vector. 01105 // Parameters: 01106 // translation_vector - [in] translation vector 01107 // Returns: 01108 // true if bezier surface successfully translated 01109 // Remarks: 01110 // Uses ON_BezierSurface::Transform() function to calculate the result. 01111 bool Translate( 01112 const ON_3dVector& translation_vector 01113 ); 01114 01115 // Description: 01116 // Scales the bezier surface by the specified facotor. The scale is 01117 // centered at the origin. 01118 // Parameters: 01119 // scale_factor - [in] scale factor 01120 // Returns: 01121 // true if bezier surface successfully scaled 01122 // Remarks: 01123 // Uses ON_BezierSurface::Transform() function to calculate the result. 01124 bool Scale( 01125 double scale_factor 01126 ); 01127 01128 ON_Interval Domain( 01129 int // 0 = "u" domain, 1 = "v" domain 01130 ) const; 01131 01132 bool Reverse( int ); // reverse parameterizatrion 01133 // Domain changes from [a,b] to [-b,-a] 01134 01135 bool Transpose(); // transpose surface parameterization (swap "s" and "t") 01136 01137 bool Evaluate( // returns false if unable to evaluate 01138 double, double, // evaluation parameter 01139 int, // number of derivatives (>=0) 01140 int, // array stride (>=Dimension()) 01141 double* // array of length stride*(ndir+1)*(ndir+2)/2 01142 ) const; 01143 01144 ON_3dPoint PointAt(double s, double t) const; 01145 01146 bool GetNurbForm( ON_NurbsSurface& ) const; 01147 01148 bool IsRational() const; // true if NURBS curve is rational 01149 01150 int CVSize() const; // number of doubles per control vertex 01151 // = IsRational() ? Dim()+1 : Dim() 01152 01153 int Order( // order = degree + 1 01154 int // dir 01155 ) const; 01156 01157 int Degree( // degree = order - 1 01158 int // dir 01159 ) const; 01160 01161 /* 01162 Description: 01163 Expert user function to get a pointer to control vertex 01164 memory. If you are not an expert user, please use 01165 ON_BezierSurface::GetCV( ON_3dPoint& ) or 01166 ON_BezierSurface::GetCV( ON_4dPoint& ). 01167 Parameters: 01168 cv_index0 - [in] (0 <= cv_index0 < m_order[0]) 01169 cv_index1 - [in] (0 <= cv_index1 < m_order[1]) 01170 Returns: 01171 Pointer to control vertex. 01172 Remarks: 01173 If the Bezier surface is rational, the format of the 01174 returned array is a homogeneos rational point with 01175 length m_dim+1. If the Bezier surface is not rational, 01176 the format of the returned array is a nonrational 01177 euclidean point with length m_dim. 01178 See Also 01179 ON_BezierSurface::CVStyle 01180 ON_BezierSurface::GetCV 01181 ON_BezierSurface::Weight 01182 */ 01183 double* CV( 01184 int cv_index0, 01185 int cv_index1 01186 ) const; 01187 01188 /* 01189 Description: 01190 Returns the style of control vertices in the m_cv array. 01191 Returns: 01192 @untitled table 01193 ON::not_rational m_is_rat is false 01194 ON::homogeneous_rational m_is_rat is true 01195 */ 01196 ON::point_style CVStyle() const; 01197 01198 double Weight( // get value of control vertex weight 01199 int,int // CV index ( >= 0 and < CVCount() ) 01200 ) const; 01201 01202 bool SetWeight( // set value of control vertex weight 01203 int,int, // CV index ( >= 0 and < CVCount() ) 01204 double 01205 ); 01206 01207 bool SetCV( // set a single control vertex 01208 int,int, // CV index ( >= 0 and < CVCount() ) 01209 ON::point_style, // style of input point 01210 const double* // value of control vertex 01211 ); 01212 01213 bool SetCV( // set a single control vertex 01214 int,int, // CV index ( >= 0 and < CVCount() ) 01215 const ON_3dPoint& // value of control vertex 01216 // If NURBS is rational, weight 01217 // will be set to 1. 01218 ); 01219 01220 bool SetCV( // set a single control vertex 01221 int,int, // CV index ( >= 0 and < CVCount() ) 01222 const ON_4dPoint& // value of control vertex 01223 // If NURBS is not rational, euclidean 01224 // location of homogeneous point will 01225 // be used. 01226 ); 01227 01228 bool GetCV( // get a single control vertex 01229 int,int, // CV index ( >= 0 and < CVCount() ) 01230 ON::point_style, // style to use for output point 01231 double* // array of length >= CVSize() 01232 ) const; 01233 01234 bool GetCV( // get a single control vertex 01235 int,int, // CV index ( >= 0 and < CVCount() ) 01236 ON_3dPoint& // gets euclidean cv when NURBS is rational 01237 ) const; 01238 01239 bool GetCV( // get a single control vertex 01240 int,int, // CV index ( >= 0 and < CVCount() ) 01241 ON_4dPoint& // gets homogeneous cv 01242 ) const; 01243 01244 bool ZeroCVs(); // zeros control vertices and, if rational, sets weights to 1 01245 01246 bool MakeRational(); 01247 01248 bool MakeNonRational(); 01249 01250 bool Split( 01251 int, // 0 split at "u"=t, 1= split at "v"=t 01252 double, // t = splitting parameter must 0 < t < 1 01253 ON_BezierSurface&, // west/south side returned here (can pass *this) 01254 ON_BezierSurface& // east/north side returned here (can pass *this) 01255 ) const; 01256 01257 bool Trim( 01258 int dir, 01259 const ON_Interval& domain 01260 ); 01261 01262 // returns the isocurve. 01263 ON_BezierCurve* IsoCurve( 01264 int dir, // 0 first parameter varies and second parameter is constant 01265 // e.g., point on IsoCurve(0,c) at t is srf(t,c) 01266 // 1 first parameter is constant and second parameter varies 01267 // e.g., point on IsoCurve(1,c) at t is srf(c,t) 01268 double c, // value of constant parameter 01269 ON_BezierCurve* iso=NULL // When NULL result is constructed on the heap. 01270 ) const; 01271 01272 bool IsSingular( // true if surface side is collapsed to a point 01273 int // side of parameter space to test 01274 // 0 = south, 1 = east, 2 = north, 3 = west 01275 ) const; 01276 01277 01279 // Tools for managing CV and knot memory 01280 bool ReserveCVCapacity( 01281 int // number of doubles to reserve 01282 ); 01283 01285 // Implementation 01286 public: 01287 // NOTE: These members are left "public" so that expert users may efficiently 01288 // create bezier curves using the default constructor and borrow the 01289 // knot and CV arrays from their native NURBS representation. 01290 // No technical support will be provided for users who access these 01291 // members directly. If you can't get your stuff to work, then use 01292 // the constructor with the arguments and the SetKnot() and SetCV() 01293 // functions to fill in the arrays. 01294 01295 01296 int m_dim; // >= 1 01297 int m_is_rat; // 0 = no, 1 = yes 01298 int m_order[2]; // order = degree+1 >= 2 01299 int m_cv_stride[2]; 01300 double* m_cv; 01301 int m_cv_capacity; // if 0, then destructor does not free m_cv 01302 #if 8 == ON_SIZEOF_POINTER 01303 // pad to a multiple of 8 bytes so custom allocators 01304 // will keep m_cv aligned and tail-padding reuse will 01305 // not be an issue. 01306 int m_reserved_ON_BezierSurface; 01307 #endif 01308 }; 01309 01310 01311 01312 01313 class ON_CLASS ON_BezierCage 01314 { 01315 public: 01316 ON_BezierCage(); 01317 01318 ON_BezierCage( 01319 int dim, 01320 bool is_rat, 01321 int order0, 01322 int order1, 01323 int order2 01324 ); 01325 01326 01327 /* 01328 Description: 01329 Construct a bezier volume that maps the unit cube 01330 to a bounding box. 01331 Parameters: 01332 bbox - [in] target bounding box 01333 order0 - [in] 01334 order1 - [in] 01335 order2 - [in] 01336 */ 01337 ON_BezierCage( 01338 const ON_BoundingBox& bbox, 01339 int order0, 01340 int order1, 01341 int order2 01342 ); 01343 01344 01345 /* 01346 Description: 01347 Construct a bezier volume that maps the unit cube 01348 to an eight sided box. 01349 Parameters: 01350 box_corners - [in] 8 points that define corners of the 01351 target volume. 01352 01353 7______________6 01354 |\ |\ 01355 | \ | \ 01356 | \ _____________\ 01357 | 4 | 5 01358 | | | | 01359 | | | | 01360 3---|----------2 | 01361 \ | \ | 01362 \ |t \ | 01363 s \ | \ | 01364 \0_____________\1 01365 r 01366 01367 order0 - [in] 01368 order1 - [in] 01369 order2 - [in] 01370 */ 01371 ON_BezierCage( 01372 const ON_3dPoint* box_corners, 01373 int order0, 01374 int order1, 01375 int order2 01376 ); 01377 01378 ~ON_BezierCage(); 01379 01380 ON_BezierCage(const ON_BezierCage& src); 01381 01382 ON_BezierCage& operator=(const ON_BezierCage& src); 01383 01384 01385 /* 01386 Description: 01387 Tests class to make sure members are correctly initialized. 01388 Returns: 01389 True if the orders are all >= 2, dimension is positive, 01390 and the rest of the members have settings that are 01391 valid for the orders and dimension. 01392 */ 01393 bool IsValid() const; 01394 01395 void Dump( ON_TextLog& text_log) const; 01396 01397 01398 /* 01399 Description: 01400 The dimension of the image of the bazier volume map. 01401 This is generally three, but can be any positive 01402 integer. 01403 Returns: 01404 Dimesion of the image space. 01405 */ 01406 int Dimension() const; 01407 01408 01409 /* 01410 Description: 01411 Creates a bezier volume with specified orders. 01412 Parameters: 01413 dim - [in] 01414 is_rat - [in] 01415 order0 - [in] 01416 order1 - [in] 01417 order2 - [in] 01418 Returns: 01419 True if input was valid and creation succeded. 01420 */ 01421 bool Create( 01422 int dim, 01423 bool is_rat, 01424 int order0, 01425 int order1, 01426 int order2 01427 ); 01428 01429 /* 01430 Description: 01431 Create a Bezier volume with corners defined by a bounding box. 01432 Parameters: 01433 bbox - [in] target bounding box - the bezier will 01434 map the unit cube onto this bounding box. 01435 order0 - [in] 01436 order1 - [in] 01437 order2 - [in] 01438 */ 01439 bool Create( 01440 const ON_BoundingBox& bbox, 01441 int order0, 01442 int order1, 01443 int order2 01444 ); 01445 01446 /* 01447 Description: 01448 Create a bezier volume from a 3d box 01449 Parameters: 01450 box_corners - [in] 8 points that define corners of the volume 01451 01452 7______________6 01453 |\ |\ 01454 | \ | \ 01455 | \ _____________\ 01456 | 4 | 5 01457 | | | | 01458 | | | | 01459 3---|----------2 | 01460 \ | \ | 01461 \ |t \ | 01462 s \ | \ | 01463 \0_____________\1 01464 r 01465 01466 */ 01467 bool Create( 01468 const ON_3dPoint* box_corners, 01469 int order0, 01470 int order1, 01471 int order2 01472 ); 01473 01474 01475 /* 01476 Description: 01477 Frees the CV array and sets all members to zero. 01478 */ 01479 void Destroy(); 01480 01481 /* 01482 Description: 01483 Sets all members to zero. Does not free the CV array 01484 even when m_cv is not NULL. Generally used when the 01485 CVs were allocated from a memory pool that no longer 01486 exists and the free done in ~ON_BezierCage would 01487 cause a crash. 01488 */ 01489 void EmergencyDestroy(); 01490 01491 01492 /* 01493 Description: 01494 Reads the definition of this class from an 01495 archive previously saved by ON_BezierVolue::Write. 01496 Parameters: 01497 archive - [in] target archive 01498 Returns: 01499 True if successful. 01500 */ 01501 bool Read(ON_BinaryArchive& archive); 01502 01503 /* 01504 Description: 01505 Saves the definition of this class in serial binary 01506 form that can be read by ON_BezierVolue::Read. 01507 Parameters: 01508 archive - [in] target archive 01509 Returns: 01510 True if successful. 01511 */ 01512 bool Write(ON_BinaryArchive& archive) const; 01513 01514 01515 /* 01516 Description: 01517 Gets the axis aligned bounding box that contains 01518 the bezier's control points. The bezier volume 01519 maps the unit cube into this box. 01520 Parameters: 01521 boxmin - [in] array of Dimension() doubles 01522 boxmax - [in] array of Dimension() doubles 01523 bGrowBox = [in] if true and the input is a valid box 01524 then the input box is grown to 01525 include this object's bounding box. 01526 Returns: 01527 true if successful. 01528 */ 01529 bool GetBBox( 01530 double* boxmin, 01531 double* boxmax, 01532 int bGrowBox = false 01533 ) const; 01534 01535 bool Transform( 01536 const ON_Xform& xform 01537 ); 01538 01539 // Description: 01540 // Rotates the bezier surface about the specified axis. A positive 01541 // rotation angle results in a counter-clockwise rotation 01542 // about the axis (right hand rule). 01543 // Parameters: 01544 // sin_angle - [in] sine of rotation angle 01545 // cos_angle - [in] sine of rotation angle 01546 // rotation_axis - [in] direction of the axis of rotation 01547 // rotation_center - [in] point on the axis of rotation 01548 // Returns: 01549 // true if bezier surface successfully rotated 01550 // Remarks: 01551 // Uses ON_BezierCage::Transform() function to calculate the result. 01552 bool Rotate( 01553 double sin_angle, 01554 double cos_angle, 01555 const ON_3dVector& rotation_axis, 01556 const ON_3dPoint& rotation_center 01557 ); 01558 01559 // Description: 01560 // Rotates the bezier surface about the specified axis. A positive 01561 // rotation angle results in a counter-clockwise rotation 01562 // about the axis (right hand rule). 01563 // Parameters: 01564 // rotation_angle - [in] angle of rotation in radians 01565 // rotation_axis - [in] direction of the axis of rotation 01566 // rotation_center - [in] point on the axis of rotation 01567 // Returns: 01568 // true if bezier surface successfully rotated 01569 // Remarks: 01570 // Uses ON_BezierCage::Transform() function to calculate the result. 01571 bool Rotate( 01572 double rotation_angle, 01573 const ON_3dVector& rotation_axis, 01574 const ON_3dPoint& rotation_center 01575 ); 01576 01577 // Description: 01578 // Translates the bezier surface along the specified vector. 01579 // Parameters: 01580 // translation_vector - [in] translation vector 01581 // Returns: 01582 // true if bezier surface successfully translated 01583 // Remarks: 01584 // Uses ON_BezierCage::Transform() function to calculate the result. 01585 bool Translate( 01586 const ON_3dVector& translation_vector 01587 ); 01588 01589 // Description: 01590 // Scales the bezier surface by the specified facotor. The scale is 01591 // centered at the origin. 01592 // Parameters: 01593 // scale_factor - [in] scale factor 01594 // Returns: 01595 // true if bezier surface successfully scaled 01596 // Remarks: 01597 // Uses ON_BezierCage::Transform() function to calculate the result. 01598 bool Scale( 01599 double scale_factor 01600 ); 01601 01602 ON_Interval Domain( 01603 int // 0 = "u" domain, 1 = "v" domain, 2 = "w" domain 01604 ) const; 01605 01606 // returns false if unable to evaluate 01607 bool Evaluate( 01608 double r, 01609 double s, 01610 double t, 01611 int der_count, 01612 int v_stride, 01613 double* v // array of length stride*(ndir+1)*(ndir+2)/2 01614 ) const; 01615 01616 /* 01617 Description: 01618 Evaluates bezer volume map. 01619 Parameters: 01620 rst - [in] 01621 Returns: 01622 Value of the bezier volume map at (r,s,t). 01623 */ 01624 ON_3dPoint PointAt( 01625 double r, 01626 double s, 01627 double t 01628 ) const; 01629 01630 /* 01631 Description: 01632 Evaluates bezer volume map. 01633 Parameters: 01634 rst - [in] 01635 Returns: 01636 Value of the bezier volume map at (rst.x,rst.y,rst.z). 01637 */ 01638 ON_3dPoint PointAt( 01639 ON_3dPoint rst 01640 ) const; 01641 01642 bool IsRational() const; // true if NURBS curve is rational 01643 01644 bool IsSingular( // true if surface side is collapsed to a point 01645 int // side of parameter space to test 01646 // 0 = south, 1 = east, 2 = north, 3 = west 01647 ) const; 01648 01649 int CVSize() const; // number of doubles per control vertex 01650 // = IsRational() ? Dim()+1 : Dim() 01651 01652 int Order( // order = degree + 1 01653 int // dir 01654 ) const; 01655 01656 int Degree( // degree = order - 1 01657 int // dir 01658 ) const; 01659 01660 /* 01661 Description: 01662 Expert user function to get a pointer to control vertex 01663 memory. If you are not an expert user, please use 01664 ON_BezierCage::GetCV( ON_3dPoint& ) or 01665 ON_BezierCage::GetCV( ON_4dPoint& ). 01666 Parameters: 01667 cv_index0 - [in] (0 <= cv_index0 < m_order[0]) 01668 cv_index1 - [in] (0 <= cv_index1 < m_order[1]) 01669 Returns: 01670 Pointer to control vertex. 01671 Remarks: 01672 If the Bezier surface is rational, the format of the 01673 returned array is a homogeneos rational point with 01674 length m_dim+1. If the Bezier surface is not rational, 01675 the format of the returned array is a nonrational 01676 euclidean point with length m_dim. 01677 See Also 01678 ON_BezierCage::CVStyle 01679 ON_BezierCage::GetCV 01680 ON_BezierCage::Weight 01681 */ 01682 double* CV( 01683 int i, 01684 int j, 01685 int k 01686 ) const; 01687 01688 /* 01689 Description: 01690 Returns the style of control vertices in the m_cv array. 01691 Returns: 01692 @untitled table 01693 ON::not_rational m_is_rat is false 01694 ON::homogeneous_rational m_is_rat is true 01695 */ 01696 ON::point_style CVStyle() const; 01697 01698 double Weight( // get value of control vertex weight 01699 int i, 01700 int j, 01701 int k 01702 ) const; 01703 01704 bool SetWeight( // set value of control vertex weight 01705 int i, 01706 int j, 01707 int k, 01708 double w 01709 ); 01710 01711 bool SetCV( // set a single control vertex 01712 int i, 01713 int j, 01714 int k, 01715 ON::point_style, // style of input point 01716 const double* // value of control vertex 01717 ); 01718 01719 // set a single control vertex 01720 // If NURBS is rational, weight 01721 // will be set to 1. 01722 bool SetCV( 01723 int i, 01724 int j, 01725 int k, 01726 const ON_3dPoint& point 01727 ); 01728 01729 // set a single control vertex 01730 // value of control vertex 01731 // If NURBS is not rational, euclidean 01732 // location of homogeneous point will 01733 // be used. 01734 bool SetCV( 01735 int i, 01736 int j, 01737 int k, 01738 const ON_4dPoint& hpoint 01739 ); 01740 01741 bool GetCV( // get a single control vertex 01742 int i, 01743 int j, 01744 int k, 01745 ON::point_style, // style to use for output point 01746 double* // array of length >= CVSize() 01747 ) const; 01748 01749 bool GetCV( // get a single control vertex 01750 int i, 01751 int j, 01752 int k, 01753 ON_3dPoint& // gets euclidean cv when NURBS is rational 01754 ) const; 01755 01756 bool GetCV( // get a single control vertex 01757 int i, 01758 int j, 01759 int k, 01760 ON_4dPoint& // gets homogeneous cv 01761 ) const; 01762 01763 bool ZeroCVs(); // zeros control vertices and, if rational, sets weights to 1 01764 01765 bool MakeRational(); 01766 01767 bool MakeNonRational(); 01768 01769 01771 // Tools for managing CV and knot memory 01772 01773 /* 01774 Description: 01775 cv_capacity - [in] number of doubles to reserve 01776 */ 01777 bool ReserveCVCapacity( 01778 int cv_capacity 01779 ); 01780 01782 // Implementation 01783 public: 01784 // NOTE: These members are left "public" so that expert users may efficiently 01785 // create bezier curves using the default constructor and borrow the 01786 // knot and CV arrays from their native NURBS representation. 01787 // No technical support will be provided for users who access these 01788 // members directly. If you can't get your stuff to work, then use 01789 // the constructor with the arguments and the SetKnot() and SetCV() 01790 // functions to fill in the arrays. 01791 01792 01793 int m_dim; 01794 bool m_is_rat; 01795 int m_order[3]; 01796 int m_cv_stride[3]; 01797 int m_cv_capacity; 01798 double* m_cv; 01799 }; 01800 01801 01802 class ON_CLASS ON_BezierCageMorph : public ON_SpaceMorph 01803 { 01804 public: 01805 ON_BezierCageMorph(); 01806 ~ON_BezierCageMorph(); 01807 01808 /* 01809 Description: 01810 Create a Bezier volume. 01811 Parameters: 01812 P0 - [in] 01813 P1 - [in] 01814 P2 - [in] 01815 P3 - [in] 01816 P0,P1,P2,P3 defines a parallepiped in world space. The morph 01817 maps this parallepiped to the (0,1)x(0,1)x(0,1) unit cube 01818 and then applies the BezierCage map. 01819 01820 01821 ______________ 01822 |\ |\ 01823 | \ | \ 01824 | \P3____________\ 01825 | | | | 01826 | | | | 01827 | | | | 01828 P2---|---------- | 01829 \ | \ | 01830 \ |z \ | 01831 y \ | \ | 01832 \P0____________P1 01833 x 01834 01835 01836 point_countX - [in] 01837 point_countY - [in] 01838 point_countZ - [in] 01839 Number of control points in the bezier volume map. The 01840 bezier volume in the returned morph is the identity map 01841 which can be modified as needed. 01842 Returns: 01843 True if resulting morph is valid. 01844 See Also: 01845 ON_BezierCage::SetBezierCage 01846 ON_BezierCage::SetXform 01847 */ 01848 bool Create( 01849 ON_3dPoint P0, 01850 ON_3dPoint P1, 01851 ON_3dPoint P2, 01852 ON_3dPoint P3, 01853 int point_countX, 01854 int point_countY, 01855 int point_countZ 01856 ); 01857 01858 /* 01859 Description: 01860 Set the world to unit cube map. 01861 Parameters: 01862 world2unitcube - [in] 01863 Tranformation matrix that maps world coordinates 01864 to the unit cube (0,1)x(0,1)x(0,1). 01865 Returns 01866 True if current bezier volum and input transformation 01867 matrix are valid. In all cases, the morph's m_xyz2rst 01868 member is set. 01869 See Also: 01870 ON_BezierCage::Create 01871 ON_BezierCage::SetBezierCage 01872 */ 01873 bool SetXform( ON_Xform world2unitcube ); 01874 01875 /* 01876 Description: 01877 Set the unit cube to world map. 01878 Parameters: 01879 world2unitcube - [in] 01880 Bezier volume map from the unit cube (0,1)x(0,1)x(0,1) 01881 to world space. 01882 Returns 01883 True if current transformation matrix and input 01884 bezier volume are valid. In all cases, the 01885 morph's m_rst2xyz member is set. 01886 See Also: 01887 ON_BezierCage::Create 01888 ON_BezierCage::SetXform 01889 */ 01890 bool SetBezierCage( ON_BezierCage& unitcube2world ); 01891 01892 const ON_Xform& WorldToUnitCube() const; 01893 const ON_BezierCage& BezierCage() const; 01894 01895 bool Read(ON_BinaryArchive& archive); 01896 bool Write(ON_BinaryArchive& archive) const; 01897 01898 /* 01899 Description: 01900 Transforms the morph by transforming the bezier volume map. 01901 Parameters: 01902 xform - [in] 01903 Returns 01904 True if input is valid. 01905 */ 01906 bool Transform(const ON_Xform& xform); 01907 01908 private: 01909 bool m_bValid; 01910 01911 // transforms world (x,y,z) coordinate into 01912 // unit cube. 01913 ON_Xform m_xyz2rst; 01914 01915 // function that maps unit cube into world 01916 ON_BezierCage m_rst2xyz; 01917 }; 01918 01919 #if defined(ON_DLL_TEMPLATE) 01920 01921 // This stuff is here because of a limitation in the way Microsoft 01922 // handles templates and DLLs. See Microsoft's knowledge base 01923 // article ID Q168958 for details. 01924 #pragma warning( push ) 01925 #pragma warning( disable : 4231 ) 01926 ON_DLL_TEMPLATE template class ON_CLASS ON_ClassArray<ON_BezierCurve>; 01927 ON_DLL_TEMPLATE template class ON_CLASS ON_SimpleArray<ON_BezierCurve*>; 01928 ON_DLL_TEMPLATE template class ON_CLASS ON_ClassArray<ON_BezierSurface>; 01929 ON_DLL_TEMPLATE template class ON_CLASS ON_SimpleArray<ON_BezierSurface*>; 01930 ON_DLL_TEMPLATE template class ON_CLASS ON_ClassArray<ON_BezierCage>; 01931 ON_DLL_TEMPLATE template class ON_CLASS ON_SimpleArray<ON_BezierCage*>; 01932 ON_DLL_TEMPLATE template class ON_CLASS ON_ClassArray<ON_BezierCageMorph>; 01933 ON_DLL_TEMPLATE template class ON_CLASS ON_SimpleArray<ON_BezierCageMorph*>; 01934 #pragma warning( pop ) 01935 01936 #endif 01937 01938 #endif