Proceedings of the 18th World Congress The International Federation of Automatic Control Milano (Italy) August 28 - September 2, 2011
Contour Following Using C2 PH Quintic Spline Curve Interpolators Javad Jahanpour*, Mi-Ching Tsai **, Ming-Yang Cheng***, I-Han Liu** *Department of Mechanical Engineering, Islamic Azad University, Mashhad branch, Mashhad, Iran, (e-mail:
[email protected] ) **Department of Mechanical Engineering, National Cheng Kung University, Tainan, 701, Taiwan, (e-mail:
[email protected] ) ***Department of Electrical Engineering, National Cheng Kung University, Tainan, 701, Taiwan, (e-mail:
[email protected] ) Abstract: This paper presents a C2 Pythagorean-Hodograph (PH) spline curve interpolator for contourfollowing tasks. To generate the C2 PH quintic spline curve, a uniform knot sequence is employed. The Scurve motion planning architecture with variable feedrate for a planar C2 PH quintic spline curve is also developed. In particular, C1 cubic feed acceleration/deceleration is imposed on the first and last PH quintic spline segments. The proposed interpolation algorithm along with a simple position loop controller is employed to perform a closed C2 PH quintic spline curve following task. Experimental results indicate that the proposed interpolator is not only feasible for machining the complicated parametric curves represented in C2 PH quintic spline form but also yields satisfactory contouring performance for variable feedrate control. Keywords: PH curves, Cubic B-spline curves, Time-dependent feedrate, parametric interpolators.
1.
INTRODUCTION
Developments of parametric interpolator as well as feed acceleration/deceleration motion planning scheme are among the most important issues in developing motion controllers. Although several interpolators have been proposed for the standard free-form parametric curves, e.g. Splines and NURBS (Non-uniform rational B-spline) (Erkorkmaz and Altintas, 2005; Cheng et al., 2002; Cheng et al., 2004; Sekar et al., 2008; Park et al., 2005), most of them rely on numerical integration to compute the arc length. As a result, it is not possible to obtain the exact arc length information using those approaches. However, the inaccurate arc length information results in fluctuation in the desired feedrate. To cope with this problem, Tsai and Cheng (2003) proposed a predictor-corrector interpolator (PCI) for NURBS curves, while Erkorkmaz and Altintas (2005) developed an iterative interpolation technique for Spline curves. Pythagorean hodograph (PH) curves (Farouki and Sakkalis, 1990) are a special family of free-form parametric curves. One of the attractive features of the PH curves is that the arc length of a PH curve can be computed precisely by evaluating a polynomial function of the curve parameter (Moon et al., 2001; Farouki and Sagar, 1996), which makes it suitable for exact real-time CNC interpolation algorithms. In general, a single PH curve cannot represent complicated open and closed shapes precisely. Nevertheless, the aforementioned difficulties can be circumvented by employing the PH spline curves. The PH spline curves not only inherit the geometrical properties of the B-spline curves but also posses the advantages of the PH
978-3-902661-93-7/11/$20.00 © 2011 IFAC
curves. Recently, several approaches have focused on the design of PH spline curves through the use of control polygons of the B-spline and NURBS curves (Pelosi et al., 2007; Jahanpour et al., 2010). In both papers, the nodal points, which are the points on the curve corresponding to the specified knot points, are employed to construct the C2 PH spline curves. As previously mentioned, the C2 PH spline inherits the advantage of the PH curves. That is, its arc length can be precisely computed by evaluating a polynomial function. In contrast, the computation of arc length for the B-spline and NURBS curves requires numerical integration, which only gives an approximate solution. The advantage in arc length calculation makes C2 PH spline particularly suitable in applications that employ the ACC/DEC before interpolation architecture. Hence, the C2 PH quintic spline curves and their interpolation algorithms are the focus of this paper. To construct the C2 PH quintic spline curves, a uniform knot sequence is used. The Newton–Raphson algorithm and the method of selecting the starting point proposed by Farouki et al. (2001) are employed to solve the system of quadratic equations. In addition, the S-curve motion planning architecture with variable feedrate for a planar C2 PH quintic spline curve is developed. To evaluate the effectiveness of the proposed interpolation algorithm, several closed C2 PH quintic spline curve following tasks have been conducted. The rest of the paper is organized as follows: Section 2 gives a brief review on the B-spline curves. Section 3 summarizes the system of equations that define C2 PH quintic interpolating splines. In Section 4, real-time interpolations using the PH quintic curves are introduced and the S-curve motion planning
9361
10.3182/20110828-6-IT-1002.00134
18th IFAC World Congress (IFAC'11) Milano (Italy) August 28 - September 2, 2011
architecture with variable feedrate for a planar C2 PH quintic spline curve is proposed. Experimental results are presented in Section 5. Finally, Section 6 concludes the paper. 2.
REVIEW ON B-SPLINE CURVES
The B-spline curve of degree p defined by given n + 1 control points P0, P1, … ,Pn and the knot vector U = {u0 , u1 ,, um } is: n
c (u ) N k , p (u ) Pk
(1)
wrapped, i.e. P0 = Pn- p+1 , P1 = Pn- p +2 ,..., Pp-2 = Pn-1 and Pp-1 = Pn . In addition, the uniform knot sequence is adopted, i.e., u0 = 0 , u1 = 1/ m , u2 = 2 / m ,..., um = 1 . Note that the domain of the curve is éêu p , um- p ùú , and non-zero values of the ë û basis functions at the points u p , u p+1 ,, um- p provide m - 2 p + 1 nodal points on the curve. Using the above wrapped control points and uniform knots, the nodal points on the NURBS curves of degree 3 are computed as follows: q k 3 c (u k ) 1 / B w k 3 Pk 3 4w k 2 Pk 2 w k 1Pk 1
k 0
where N k , p (u ) 's are the B-spline basis functions of degree p
for k 3,..., n 1 and B w k 3 4w k 2 w k 1
(5)
described by: u u u uk N k , p (u ) N k , p 1 (u ) k p 1 N k 1, p 1 (u ) (2) uk p uk uk p 1 uk 1 and 1 if u [u j , u j 1 ) (3) N j ,0 (u ) 0 otherwise. The De Cox-Boor's algorithm (Cox, 1972a; de Boor, 1972b) can be used to determine the point on a B-spline curve corresponding to a specific parameter value u. Hence, one can easily find the nodal points, which are the points on the Bspline curve corresponding to the specified knot points u0,u1,…,um with m=n+p+1. In the following, the procedure of obtaining the nodal points on the open/closed cubic B-spline curves, which are mainly used to construct the open /closed C2 PH quintic spline curves, are to be presented.
For the closed cubic B-spline curve, i.e. p=3 and w 0 w 1 =...= w n 1 , Equation (5) yields the following n-1 nodal points on the cubic B-spline curve: (6) q k 3 c u k Pk 3 4Pk 2 Pk 1 / 6, for k 3,..., n 1
2.1. Open cubic B-spline curves
Where s (x ) = x ¢ 2 (x ) + y ¢ 2 (x ) = d (r (x )) is the rate of change
To generate the open B-spline curve that is tangent to the first and last legs of the control polygon, the first and last knots must be of multiplicity p+1. Using the uniform knots: u 0 = u1 = u 2 = u 3 = 0 , u k = k - 3 for k = 4, , n , and u m -3 = u m -2 = u m -1 = u m = n - 2 along with unit weights corresponding to the given control points, i.e. w 0 w 1 =...= w n 1 , the nodal points are computed by the following equation for the case of cubic B-spline curve via (1), see Jahanpour, (2010). q0 c(u3 ) P0 ,
q1 c (u 4 ) 3P1 7 P2 2P3 / 12,
The complex representation for a planar PH curve can be expressed as: r (x ) = x (x ) + iy (x ) , where x Î [0,1] is a real parameter (Moon et al., 2001). Note that r() is a PH curve if there exist polynomials u(),v() such that its derivative, i.e., hodograph, satisfies:
x ¢( x ) = u 2 (x ) - v 2 (x ) y ¢(x ) = 2u (x )v (x )
s (x ) = u 2 (x ) + v 2 (x )
(7) d (x )
of r() with respect to the curve parameter . 3.1. C2 PH quintic spline equations A C2 PH spline refers to the connected PH curves that interpolate the nodal points of the corresponding cubic Bspline curve. The interpolation of the n1 nodal points q0, , qn 2 begins by writing the hodograph of the PH quintic segment ri (x ) , [0,1] of the spline curve, between points qi-1 and qi. The polynomial wi (x ) = ui (x ) + ivi (x ) related to the ri (x ) must be quadratic. When expressed in Bernstein form,
q k 3 c (u k ) Pk 3 4 Pk 2 Pk 1 / 6, for k 5,..., n 1
the corresponding hodograph in complex form is: 1 1 ri( ) [ ( zi 1 zi )(1 )2 zi 2(1 ) ( zi zi 1 ) 2 ]2 (8) 2 2 The continuity conditions for consecutive spans i and i +1 are: ri 1 ri1 0 , and ri1 ri1 0 . Expanding (8) and
q n 3 c (u n ) 2Pn 3 7 Pn 2 3Pn 1 /12,
qn 2 c(un 1 ) Pn
PH SPLINE CURVES
3.
(4)
2.2. Closed cubic B-spline curves
substituting it into the interpolation condition integral
In this paper, instead of using the periodic knot sequence used by Pelosi et al., (2007), the cyclic interpretation of the control points is employed to construct the closed cubic Bspline curves. That is, the first p and last p control points are
1
0 ri( )d qi qi 1
by taking ri (0) = q i -1 as the integration
constant will yield the following equation: f i (z i 1 , z i , z i 1 ) 3z i21 27z i2 3z i21 z i 1z i 1 13z i 1z i 13z i z i 1 60q i 0
9362
(9)
18th IFAC World Congress (IFAC'11) Milano (Italy) August 28 - September 2, 2011
where Dqi = qi - qi-1 for i=1,…,M. However, the first and last equations, i.e. f1 ( z1 ,, zM ) = 0 and f M (z 1 ,, z M ) = 0 , must be modified or additional equations must be introduced through the end conditions discussed in the following subsection. 3.2. End conditions If derivatives di = r1' (0) and d f = rM' (1) at the end-nodal points q0 and qM are specified, the interpolation equations (9) hold for all segments i=1,2,…,M and interpolation of the derivatives di , df yields two further equations: f 0 ( z 0 , z1 ) ( z 0 z1 ) 2 4 d i 0 (10) f M 1 ( z M , z M 1 ) ( z M z M 1 ) 2 4d f 0
for a sampling interval Dt , the parameter values x1 , x2 , at times Dt , 2Dt , are computed by the following equation: (14) s ( k ) F (kt ), k 0,1,...
Equation (14) has a unique real root for each k. k can be computed by the Newton–Raphson method (Tsai et al., 2001): s( ( r 1) ) F (k t ) (15) k( r ) k( r 1) k , r 1, 2,... ( k( r 1) ) with k( 0) k 1 . Consider the case where V is a polynomial of t. Using the normalized time variable τ = t/T and expressing V(t) in the Bernstein basis form on the unit interval [0,1] , we have n
V ( ) v k bkn ( )
2
For the closed C PH quintic spline, the end conditions: qM = q0 , rM' (1) = r1' (0) , and rM" (1) = r1" (0) should be satisfied. To this end, (8) is replaced by (11), see Albrecht and Farouki (1996): 1 1 r1( ) [ ( z M z1 )(1 ) 2 z1 2(1 ) ( z1 z2 ) 2 ]2 2 2 1 1 2 rM ( ) [ ( zM 1 zM )(1 ) zM 2(1 ) ( zM z1 ) 2 ]2 2 2
(11)
Therefore, the first and last equations of the system described by (9) become: f1 ( z1 ,..., zM ) 3zM2 27 z12 3z22 zM z2 13zM z1 13z1 z2 60q1 0 f M ( z1 ,..., z M ) 3 z M2 1 27 z M2 3 z12 z M 1 z1 13 z M 1 z M 13 z M z1 60 qM 0
(12) Note that the same choice of sign must be used in f1 and fM (Farouki et al., 2001). In order to solve (9) subject to the above end conditions, a numerical method such as the Newton–Raphson iteration algorithm is required. In this paper, the starting approximation is calculated using the method developed in Farouki et al. (2001), in which the starting approximation to the solution is estimated by setting zi-1 = zi = zi +1 in (9):
z i2 q i for i 1,...M 4.
(13)
2
C PH QUINTIC SPLINE INTERPOLATOR
In the following, real-time interpolation by PH quintic curves developed in Farouki and Sagar (1996) will be briefly reviewed first. Then, the S-curve motion planning architecture with variable feedrate for a planar C2 PH quintic spline curve is proposed.
(16)
k 0
where b n ( ) n (1 ) n k k and vk are the Bernstein-basis k k functions and coefficients, respectively. Given a polynomial V of odd degree n in (16), one can define a feedrate profile that matches V=Vi for t0 and V=Vf for t>T with C(n-1)/2 continuity. In this paper, in order to obtain smooth motion along the path and also ensure continuity of both the feed acceleration/deceleration and feed jerk, the Scurve C1 cubic and C2 quintic profiles are preferred to the C0 linear one (Tsai et al., 2001). Fig. 1 shows the C1 cubic and C2 quintic variable feedrate acceleration profiles defined by (16) when Vi=0. 4.1.2 Constant feedrate For the case of constant feedrate, the arc length is determined as: s(k ) kV f T , where Vf is the constant feedrate. Similarly,
k is computed by the Newton–Raphson method: s ( ( r 1) ) kV f T k( r ) k( r 1) k , r 1, 2,... ( k( r 1) )
(17)
The initial approximation for (17) is given by Farouki and Sagar (1996) V T (18) k(0) k 1 f (( k 1) )
4.1 Review on real-time interpolation by PH curves 4.1.1 Time-dependent feedrate Consider a time-dependent feedrate function V (t ) for t [0, T ] imposed on the PH curve, in which V (t ) F (t ) . Thus, the arc length is determined as: s( ) F (t ) . Accordingly,
Fig.1 Feed accelerations from V = 0 for t ≤0 to V = Vf for t ≥ T using C1 cubic, and C2 quintic variable feedrates defined by (16) (Tsai et al., 2001).
9363
18th IFAC World Congress (IFAC'11) Milano (Italy) August 28 - September 2, 2011
4.2 Modified motion planning along the C2 PH quintic spline curves The modified motion planning structure consisting of variable and constant feedrate profiles for interpolating a C2 PH quintic spline curve is introduced in the following: 1. Acceleration from full stop to the constant feedrate on the first PH quintic segment r1() during [0, T ] : In this phase of motion, the C1 cubic feedrate acceleration along the PH quintic segment r1() is imposed. 2. Constant velocity: This phase of motion starts from the end of the acceleration period along the PH quintic segment r1() and ends at the beginning of the deceleration period along the PH quintic segment rM(). The C2 PH quintic spline curve is interpolated under constant feedrate Vf. 3. Deceleration from the PH quintic segment rM() with constant velocity to full stop: The C1 cubic feedrate deceleration along the last PH quintic segment rM() is imposed during this phase. 5.
EXPERIMENT SETUP AND RESULTS
5.1. Experimental setup In the experiment, two AC servomotors equipped with incremental encoders (2500×4 pulses/rev) are employed. Both servo drives are set to the velocity mode throughout the experiments. All the control algorithms are implemented using a PMC32-6000 motion control equipped with a TI TMS320C32 DSP. For each axis, a simple position loop controller with a velocity command feed-forward is used to reduce the tracking error. The control block diagram of the experimental system is shown in Fig.2. The input commands computed by the C2 PH quintic spline interpolator, i.e. Xcom (Ycom) and X com ( Ycom ), are the desired position and velocity commands for the X (Y) axis, respectively. Kpx, Kpy are the position loop gains and Kvx, Kvy are the feed-forward gains. Also, Xact and Yact in Fig.2, represent the actual positions for the X axis and Y axis, respectively. The transfer functions of the controlled plant from the velocity command to the position output are obtained using the dynamic analyzer HP3563A, for both the motions of the Xand Y-axes respectively, as follows: Gx =
Fig.2. Block diagram of the servo controller of the experimental system. 5.2. Case study A closed C2 PH quintic spline curve “Heart” is used in the contour-following task throughout the experiments. The control points for constructing the “Heart” curve are: P0 = -20 - 50i , P1 = 0 + 5i , P2 = 0 - 5i , P3 = -20 + 50i , P4 = 40 + 50i , P5 = 75 - 5i , P6 = 75 + 5i , P7 = 40 - 50i , P8 = P0 , P9 = P1 , P10 = P2 The above control points give the C2 PH B-spline curve consisting of eight PH quintic segments. The total curve length is Sheart=289.7626 mm. Additionally, the arc length of the first and last PH quintic segments are S1heart=12.229 mm and S8heart=36.6574 mm, respectively. The contour-following task is conducted under two different motion planning schemes proposed in Section 4 so as to evaluate the performance of the proposed approach. In particular, two different settings for variable feedrate profiles in Fig.2 are used: Vf=100 mm/s, T=0.12 s and Vf=120 mm/s, T=0.12 s. From Fig.1, the acceleration (deceleration) curve length traveled by C1 cubic feedrate acceleration (deceleration) is given by S acc / dec = V f ´T / 2 . Thus, for the cases of Vf=100 mm/s, and Vf=120 mm/s, only 6 mm and 7.2 mm of the first and the last PH quintic segments of the curve (with S1heart, S8heart) are traveled, respectively. Note that in both the interpolation algorithms and experiments, the sampling period ∆t is set to 1 ms.
35.8958 rad/s 39.2008 rad/s ( ) , and Gy = ( ) 1+ 0.0033185s voltage 1 + 0.0042222s voltage
Based on the measured transfer functions Gx and Gy, one can determine appropriate position loop gains in Fig.2, in which they are set to Kpx=62 s-1, Kpy=47 s-1, Kvx= Kvy=0.57 throughout the experiment. Fig.3. Feedrate command used in the experiments generated by the proposed interpolator for the “Heart” contour-following task with Vf=100 mm/s and T=0.12 s.
9364
18th IFAC World Congress (IFAC'11) Milano (Italy) August 28 - September 2, 2011
Using the above parameters, the C2 PH quintic B-spline curve interpolator generates the feedrate command employed in the experiment. For example, the feedrate profile associated with Vf=100 mm/s and T=0.12 s is shown in Fig.3. The X and Y feedrate components are also depicted as dashed curves in Fig.3. As can be seen in Fig.3, the feedrate command generated by the proposed interpolator is not only able to achieve smooth motion transition between different phases along the path but also to avoid any fluctuations in the desired feedrate. 5.3 Experimental results Experimental results for the contour-following task with Vf=100 mm/s are given in Fig.4. The contour-following motion started from the point q0= 3.335.83i mm and traveled in a clockwise direction. The tracking performance is illustrated in Fig.4 (a). It can be observed that the actual trajectory closely matches the desired one. As can be seen in Fig.4 (b), the maximum contour error is 0.168 mm that occurred at the turning point shown in the inset of Fig. 4(a). The curvature profile is shown in Fig.4(c), where the amount of the curvature at the turning point is 0.217 mm-1 which differs by a small amount of 0.55% with respect to the desired tool path. Fig.4(b) and Fig.4(c) show that the contour error at the point with the largest curvature is larger than that for the other smoother portions of the curve. To compare the actual feedrate with the desired feedrate command along the curve, the actual feedrate profile and the desired feedrate profile for this case are given in Fig.5. Although the desired feedrate profile does not have any fluctuations, the sudden change of motion in the X direction results in a small variation in the actual feedrate profile. The maximum variation in the actual feedrate profile is about 2.5 % as shown in the inset of Fig.5, which is related to the aforementioned turning region with the largest curvature on the “Heart” curve. Experimental results for the contour-following task with Vf=120 mm/s are given in Fig.6. It can be observed that the actual trajectory also closely matches the desired one as shown in Fig.6 (a), where the maximum contour error is 0.218 mm as indicated by Fig.6 (b). For this case, the maximum variation in the actual feedrate profile that occurred at the turning region with a curvature of 0.218 mm-1 is 3.49 % as shown in Fig.6 (c). Table 1 summarizes the experimental results of the “Heart” contour-following task with two different cases for the velocity planning.
(a)
(b)
(c)
Fig.4. Experimental results for the “Heart” contour-following task with Vf=100 mm/s (a). Position along the “Heart” curve using the proposed interpolator (b). Contour error for “Heart” tracking (c). Curvature profile.
Table 1: Experimental results for the “Heart” contourfollowing task. Motion planning parameters Vf=100 mm/s, T=0.12 s Vf=120 mm/s, T=0.12 s
Total machining time(s)
Maximum actual feedrate fluctuation (%)
Maximum actual curvature (1/mm)
Maximum contour error (mm)
3.019
2.5
0.217
0.168
2.536
3.49
0.218
0.218
Fig.5. Feedrate profile along the “Heart” curve with Vf=100 mm/s using C2PH spline curve interpolator.
9365
18th IFAC World Congress (IFAC'11) Milano (Italy) August 28 - September 2, 2011
ACKNOWLEDGMENT The authors would like to thank Islamic Azad University of Mashhad and the Ministry of Education, Taiwan, for kind supporting of this research. REFERENCES
(a)
(b)
(c)
Fig.6. Experimental results for the “Heart” contour-following task with Vf=120 mm/s (a). Position along the “Heart” curve using the proposed interpolator (b). Contour error for “Heart” tracking (c). Curvature profile. 6.
CONCLUSIONS
This paper has developed a C2 PH quintic spline curve interpolator for contour-following tasks. The PH spline curve inherits the advantages of the PH curves and attractive properties of the B-spline curves so that it can be used to represent the complicated open and closed shapes used in the CAD/CAM systems. Using a combination of time-dependent and constant feedrates, the S-curve motion planning architecture with variable feedrate for a planar C2 PH quintic spline curve has also been developed. Accordingly, the toolpath interpolation yields a feedrate command without any fluctuation. Experimental results demonstrated that the proposed interpolator is feasible for machining the parametric curves represented in the C2 PH quintic spline form. Moreover, it is able to achieve satisfactory contouring performance for variable feedrate control.
Albrecht, G., Farouki, R.T., (1996). Construction of C2 Pythagorean hodograph interpolating splines by the homotopy method. Adv Comput Math, 5(4), 417–442. Cox, M.G. (1972a). The numerical evaluation of B-splines. J. Inst. Maths. Appl. 10, 134–149. Cheng, C.W., Tsai, M.C. (2004). Real-time variable feedrate NURBS curve interpolator for CNC machining. Int J Adv Manuf Technol 23(11-12), 865–873. Cheng, M.Y., Tsai, M.C., and Kuo, J.C. (2002). Real-time NURBS command generators for CNC servo controllers. Int J Mach Tool Manufact, 42(7), 801-813. De Boor, C., (1972b). On calculating with B-splines. J. Approx. Theory 6, 50–62. Erkorkmaz, K., Altintas, Y. (2005). Quintic spline interpolation with minimal feed fluctuation. ASME J of Manuf Sci Eng, 127(2), 339-349. Farouki, R.T., Sakkalis, T. (1990). Pythagorean Hodographs. IBM J Res Dev, 34(5),736-752. Farouki, R.T., Sagar, S. (1996). Real-time CNC interpolators for Pythagorean-hodograph curves. Comput Aided Geom Des, 13(7), 583-600. Farouki, R.T., Kuspa, B.K., Manni, C., and Sestini, A. (2001). Efficient solution of the complex quadratic tridiagonal system for C2 PH quintic splines. Numer Algor, 27(1), 35– 60. Jahanpour, J., Tsai, M.C., and Cheng, M.Y., (2010). High speed contouring control with NURBS-based C2 PH spline curves. Int J Adv Manuf Technol, 49, 663-674. Moon, H.P., Farouki, R.T., and Choi, H.I. (2001). Construction and shape analysis of PH quintic Hermite interpolants. Comput Aided Geom Des,18(2), 93-115. Park, J., Nam, S., and Yang, M. (2005). Development of a realtime trajectory generator for NURBS interpolation based on the two-stage interpolation method. Int J Adv Manuf Technol, 26(4), 359-365. Pelosi, F., Sampoli, M.L., Farouki, R.T., and Manni, C. (2007). A control polygon scheme for design of planar C2 PH quintic spline curves. Comput Aided Geom Des, 24(1), 28–52. Sekar, M., Narayanan, V.N., and Yang, S.H. (2008). Design of jerk bounded feedrate with ripple effect for adaptive nurbs interpolator. Int J Adv Manuf Technol, 37( 5-6), 545–552. Tsai, Y.F., Farouki, R.T., and Feldman, B. (2001). Performance analysis of CNC interpolators for timedependent feed rates along PH curves. Comput Aided Geom Des,18(3), 245-265. Tsai, M.C., Cheng, C.W. (2003). A real-time predictorcorrector interpolator for CNC machining. Trans ASME J Manuf Sci Eng, 125 (3), 449–460.
9366