Predictive functional control of a PUMA robot
←
→
Page content transcription
If your browser does not render page correctly, please read the page content below
ACSE 05 Conference, 19-21 December 2005, CICC, Cairo, Egypt Predictive functional control of a PUMA robot A. Vivas, V. Mosquera Department of Electronic, Instrumentation and Control, University of Cauca Calle 5 No. 4-70, Popayán, Colombia avivas@unicauca.edu.co http://www.ai.ucauca.edu.co Abstract In the past decade, model predictive control (MPC) This paper describes an efficient approach for nonlinear has become a good control strategy for a large number of model predictive control, applied to a 6-DOF arm robot. process [8], [9]. Several works [10], [11], [12] have The model is first linearized and decoupled by feedback, shown that model based predictive control could be of a secondly a model predictive control scheme, great interest for handling constrained processes by implemented with an optimized dynamic model and optimizing, over some manipulated inputs, forecasts of running within small sampling period, is exhibited. Major process behavior. It provides good performances in term simulation results performed using numerical values of of rapidity, disturbances and errors cancellations. an industrial PUMA 560 robot prove the effectiveness of However, a significant number of industrial applications the proposed approach. The nonlinear model-based can be found, for instance, in chemicals industries or predictive control and the widely used computed torque food processing that are processes with relatively slow control are compared. Tracking performance and dynamics. But very few results concern the computation robustness with respect to external disturbances or errors of the model predictive control with nonlinear and high in the model are enlightened. dynamic process such as robot links [13], [14], where the model is highly nonlinear and the digital control has to be performed within only few milliseconds. Keywords: Robot control, dynamic modelisation, computed torque control, predictive control. An special predictive strategy is presented in this study (predictive functional control [15], [16]), and it will 1. Introduction be compared with the computed torque control. The robot platform used to test these controllers is a PUMA 560 robot, widely used in robotics research, for which there is Many strategies have been used in the last years for a substantial literature. Test will remark the performances robot control [1], [2], [3]. In industrial and commercial in tracking and robustness behavior. robot arms, controllers are still usually PID. But robotic manipulators have many serially linked components, the This paper is organized as follows: Section (2) manipulator dynamics is highly nonlinear with strong resumes the dynamic model formulation of a robot, couplings existing between joints, that complicate the Section (3) details the model predictive functional control, task of a simple PID, especially if the velocities and Section (4) is dedicated to define the model based control accelerations of the robot are high. Better solutions are strategies of this study, Section (5) list major simulation then implemented with model based controllers, that use results in terms of tracking performance and robustness. a mathematical model of the robot to explicitly Finally, conclusions are given in Section (6). compensate the dynamic terms. The most common strategy of model based control is the computed torque control [4], [5], widely used for industrial robot arms. This strategy is relatively easy to implement but the 2. Dynamic model formulation uncertainties presents in the model difficult to design an effective control algorithm based on an exact It is well known that the behavior of an n-DOF rigid- mathematical model. Other solutions may be then link arm is governed by the following equation: implemented to give to the system the robustness needed [6], [7]. Γ = A(q )q+ C (q, q )q + g (q ) (1)
ACSE 05 Conference, 19-21 December 2005, CICC, Cairo, Egypt Where Γ is the actuation torque, A(q ) is a symmetric Internal Modeling: The model used is a linear one given and positive definite inertia matrix, C (q, q ) is the matrix by: of the Coriolis and centrifugal forces, and g(q) is the xM (n) = FM xM (n −1) + GM u(n −1) gravity force. This robot dynamic equation can also be written in a compact form: yM ( n) = C M T x M ( n) (5) Γ = A(q ) q+ H (q , q ) (2) where xM is the state, u is the input, yM is the measured model output, FM, GM and CM are respectively matrices where H includes centrifugal, Coriolis and gravitational or vectors of the right dimension. forces. If the system is unstable, the problem of robustness The dynamic terms in Eq.(2) are highly nonlinear and caused by the controller's cancellation of the poles is coupled. The first step is to design a linearizer to usually solved by a model decomposition [15]. dynamically linearize and decouple the robot dynamic model. The possibility of finding such a linearizing Reference trajectory: The predictive control strategy of controller is guaranteed by the particular form of system the MPC is summarized in Figure 1. Given the set point dynamic. In fact, Eq.(2) is linear in the control Γ and has trajectory over a receding horizon [0, h], the predicted a full-rank matrix A(q) which can be inverted for any process output yˆ P will reach the future set point manipulator configuration. following a reference trajectory yR . Thus, the following linearization is proposed: In Figure 1, ε (n) = c(n) − yP (n) is the position Γ = Aˆ (q ) u + Hˆ (q , q ) (3) tracking error at time n, c is the set point trajectory, yP is the process output, and CLTR is the closed loop time response. where u represents a new input vector. Â and Ĥ are estimations of the real manipulator dynamics. In the Over the receding horizon, the reference trajectory absence of disturbance and when the dynamic model is yR , which is the path towards the future set point, is perfectly known, Â = A and Ĥ = H . In this case u has given by: the form of a joint acceleration: c(n + i ) − yR (n + i ) = α i (c(n) − yP ( n)) for 0 ≤ i ≤ h (6) u = q (4) where α (0< α
ACSE 05 Conference, 19-21 December 2005, CICC, Cairo, Egypt nh nB { } 2 D(n) = ∑ yˆ P (n + h j ) − yR (n + h j ) (7) yF (n + i ) = ∑ µk (n) yBK (i ) 0≤i ≤ k (15) j =1 k =1 where nh is the number of coincidence time point, hj are where y BK is the model output response to uBK . the coincidence time points over the prediction horizon. Assuming that the predicted future output error is The predicted output yˆ P is usually defined as: approximated by a polynomial function, it follows: de yˆ P (n + 1) = yM (n + i ) + eˆ(n + i ) 1≤ i ≤ h (8) eˆ(n + i ) = e(n) + ∑ em (n)i m for 1 ≤ i ≤ h (16) m =1 where yM is the model output and ê is the predicted future output error. where de is the degree of the polynomial approximation of the error, em are coefficients computed on-line It may be convenient to add a smoothing control term knowing the past and present output error. in the performance index. The index becomes: The minimization of the performance index without nh smoothing control term, in the case of the polynomial { } 2 D(n) = ∑ yˆ P (n + h j ) − yR (n + h j ) + λ {u (n) − u (n − 1)} (9) base functions, leads to the applied control variable: 2 j =1 u (n) = k0 {c( n) − yP (n)} where u is the control variable. max( dc , de ) Control variable: The future control variable is assumed + ∑ km {cm (n) − em (n)} + VX T xM (n) (17) m =1 to be composed of a priori known functions: where dc is the degree of the polynomial approximation nB u (n + i ) = ∑ µ k (n)u BK (i ) 0 ≤ i ≤ h (10) of the set point and the gains k0 , km , VX T are computed k =1 off-line [15]. where µk are the coefficients to be computed during the Therefore the control variable is composed of three optimization of the performance index, uBK are the base terms: the first one is due to the tracking position error, functions of the control sequence, nB is the number of the second one is placed especially for disturbance base functions. rejection and the last one corresponds to a model compensation. The choice of the base functions depends on the nature of the set point and the process. These base functions will be represented by: 4. Control strategies Description of the PUMA robot: The PUMA 560 u BK (i ) = i k −1 ∀k (11) (Programmable Universal Machine for Assembly) depicted in Figure 2 is a 6 DOF manipulator with In fact, only the first term is effectively applied for revolute joints that has been widely used in industry and the control, that is: still is in academia. The PUMA uses DC servo motors as its actuators, has high resolution relative encoders for nB accurate positioning and potentiometers for calibration. u (n) = ∑ µ k (n)u BK (0) (12) k =1 The model output is composed of two parts: yM (n + i ) = yUF (n + i ) + yF (n + i ) 1 ≤ i ≤ h (13) where yUF is the free (unforced) output response (u = 0), y F is the forced output response to the control variable given by Equation (10). Given Equation (6) and Equation (10), it follows: yUF (n + i ) = CM T FM xM (n) 0≤i ≤ h (14) Figure 2. PUMA 560 robot
ACSE 05 Conference, 19-21 December 2005, CICC, Cairo, Egypt Implementation of inverse dynamics control laws The resulting scheme is shown in Figure 3, in which indeed requires that parameters of the system dynamic two feedback loops are represented; an inner loop based model are accurately known. To simplify the dynamic on the manipulator dynamic model and a outer loop model, some parameters are grouping or eliminated to operating on the tracking error. The function of the inner obtain a set of base parameters for the PUMA robot [5], loop is to obtain a linear and decoupled input/output show in Table 1 and Table 2. In these tables, the term relationship, whereas the outer loop is required to “G” denotes the parameters that includes other terms. stabilize the overall system. An identification procedure gives the parameter Predictive functional control: The MPC algorithm is values show in Table 3 [18]. These estimated values will implemented with an internal model composed of a be considered as the nominal values during the double set of integrators, that represents the non-linear simulations. and decoupled system. To facilitate the stabilization process, two feedback loops are added to the internal Computed torque control: Assuming that only the model: a position and a velocity loop, with gains Kp = 2 motion is specified as desired position qd, the computed and Kv = 7 respectively. torque control (CTC) computes the required input control as follows: Three different base functions are used: step, ramp and parabola. The close loop response time (CLTR) is w = K p (q d − q ) − K v q (18) fixed to 32*Tsampling in order to ensure the compromise between the tracking performances and the disturbance rejection. Three coincidence time points on the prediction where Kp and Kv are the controller gains. The tuning of horizon are defined and the predicted future output error CTC controller for the PUMA robot leads to the gains is approximated by a polynomial of degree 2. The show in Table 4. smoothing control term is fixed at 0.35. PFC scheme is shown in Figure 4. Table 1. Inertia tensor parameters j XXj XYj XZj YYj YZj ZZj 1 0 0 0 0 0 ZZG1 Table 4. Kp and Kv gains 2 XXG2 0 0 0 0 ZZG2 1 2 3 4 5 6 3 XXG3 0 0 0 0 ZZG3 Kp 18000 10000 8900 6200 10500 5500 4 XXG4 0 0 0 0 ZZG4 Kv 19 16 16 14 18 16 5 XXG5 0 0 0 0 ZZG5 6 XXG6 0 0 0 0 ZZ6 Table 2. First moment of inertia, mass and motor inertia parameters Kp j MXj MYj MZj Mj Iaj Non-linear compensation and decoupling 1 0 0 0 0 0 q d u Aˆ (q) Γ 2 MXG2 MY2 0 0 0 q d Kv Robot qd 3 0 MYG3 0 0 Ia3 4 0 0 0 0 Ia4 q q Ki ∫ Hˆ (q, q) q 5 0 MYG5 0 0 Ia5 6 0 0 0 0 Ia6 Stabilizing linear control Table 3. Parameters of the PUMA robot Figure 3. Joint inverse dynamics control Parameter Values Parameter Values XXG2 -1.8566 ZZ6 5.8e-6 XXG3 0.3069 MXG2 5.3086 XXG4 6.0e-4 MY2 0.1120 XXG5 1.2e-4 MYG3 0.3420 Kp Non-linear compensation and XXG6 0.0 MYG5 0.0012 decoupling q ZZG1 2.4441 IA3 200e-6 qd PFC + - Γ Aˆ (q) Robot ZZG2 2.2558 IA4 3.3e-5 ZZG3 0.3150 IA5 3.3e-5 - Stabilizing linear q ZZG4 0.0039 IA6 3.3e-5 control Hˆ (q,q) Kv ZZG5 6.9e-6 q Note: the units for the inertia tensor parameters are Kg.m2, for the first moment of inertia Kg.m, and for the Figure 4. Predictive Functional Control motor inertia Kg.m2.
ACSE 05 Conference, 19-21 December 2005, CICC, Cairo, Egypt 5. Simulation results 3 2 Computed torque control and predictive functional control are implemented in simulation environment 1 (Matlab/Simulink). Tracking performance and 0 Control torque (N.m) robustness (disturbance rejection and errors in the model) -1 are compared. -2 -3 Tracking performances: These tests are running within 1 msecond sampling period. A fifth order trajectories with -4 trapezoidal velocity profile are designed as set point for -5 each motor, being the final positions 1.2, 0.7, 0.5, 0.3, -6 0.65, and 0.35 radians respectively. Figures 5 and 6 show -7 tracking error for CTC and PFC control respectively, and 0 200 400 600 800 1000 1200 1400 1600 1800 2000 Time (ms) Figures 7 and 8 show their control torques. -3 Figure 8. Control torque for PFC x 10 3 Tracking performances are very advantageous for the 2.5 predictive control. In the same way, control torque is a 2 little smaller for PFC due to its smoothing control term. Tracking error (rad) 1.5 Disturbance rejection: An unknown output disturbance is applied at 0.3 seconds. It is constant and equal to 0.2 1 radians for all motors. Figure 9 show disturbance rejection for CTC and Figure 10 for PFC control. 0.5 0 With the same controller tuning, PFC control is more robust than CTC control with respect to external -0.5 disturbances and also the time response to the 0 200 400 600 800 1000 1200 1400 1600 1800 2000 Time (ms) disturbances is better. Figure 5. Tracking error for CTC 0.25 -3 x 10 3 0.2 0.15 2.5 0.1 Disturbance rejection (rad) 2 0.05 Tracking error (rad) 0 1.5 -0.05 1 -0.1 0.5 -0.15 -0.2 0 -0.25 0 200 400 600 800 1000 1200 1400 1600 1800 2000 Time (ms) -0.5 0 200 400 600 800 1000 1200 1400 1600 1800 2000 Time (ms) Figure 9. Disturbance rejection for CTC Figure 6. Tracking error for PFC 0.25 3 0.2 2 0.15 1 0.1 Disturbance rejection (rad) 0 Control torque (N.m) 0.05 -1 0 -2 -0.05 -3 -0.1 -4 -0.15 -5 -0.2 -6 -0.25 -7 0 200 400 600 800 1000 1200 1400 1600 1800 2000 0 200 400 600 800 1000 1200 1400 1600 1800 2000 Time (ms) Time (ms) Figure 7. Control torque for CTC Figure 10. Disturbance rejection for PFC
ACSE 05 Conference, 19-21 December 2005, CICC, Cairo, Egypt Errors in the model: The model mismatch is obtained 7. References considering up to 10% errors from the nominal values given in Table 4. The desired trajectories are those of the tracking performances section. Figures 11 and 12 show [1] C. Samson, M. Le Borgne, B. Espinau. Robot the tracking error for CTC and PFC respectively. Equally, control. Oxford University Press, 1991. the predictive controller is more robust to changes on the [2] F. Lewis, C. Abdallah, D. Dawson. Control of robot parameters values. manipulators. Macmillan, 1993. 0.015 [3] C. Canudas, B. Siciliano, G. Bastin. Theory of robot control. Springer Verlag, 1996. 0.01 [4] M. Spong. Motion control of robot manipulator, in Handbook Control, W. Levine Editor, pages 1339 – 0.005 1350. CRC Press, 1996. [5] W. Khalil, E. Dombre. Modeling identification and Tracking error (rad) 0 control of robots. Hermes Penton Science, 2002. [6] H. Seraji. Adaptive Independent joint control of manipulators: Theory and experiment. In -0.005 proceedings of IEEE International Conference on Robotics and Automation, 1988. -0.01 [7] G. Park, D. Hwang. Robust controller design for a class of nonlinear robot manipulators with actuator -0.015 0 200 400 600 800 1000 1200 1400 1600 1800 2000 dynamics. International Journal of Systems Science, Time (ms) Vol. 33, No. 7, pp. 557 – 565, 2002. Figure 11. Tracking error for CTC [8] F. Allgöwer, T. Badgwell, J. Qin, J. Rawlings, S. 0.015 Wright. Nonlinear predictive control and moving horizon estimation - An introductory overview. In 0.01 proceedings of the European Conference Control, 1999. 0.005 [9] E. Camacho, C. Bordons. Model predictive control in the process industry. Springer-Verlag, 1995. Tracking error (rad) 0 [10] D. Clarke, C. Mohtadi, P. Tuffs. Generalised predictive control. Part. 1: The basic algorithm. Part. -0.005 2: Extensions and interpretations. Automatica, Vol. 23, No. 2, pp. 137 – 160, 1987. -0.01 [11] P. Boucher, D. Dümur, K. Rahmani. Generalised Predictive Cascade Control. In proceedings of European Conference Control, 1991. -0.015 0 200 400 600 800 1000 1200 1400 1600 1800 2000 [12] J. Rossiter. Predictive functional control: more than Time (ms) one way to prestabilise. In proceedings of the 15th Figure 12. Tracking error for PFC IFAC World Congress, 2002. [13] P. Poignet, M. Gautier. Nonlinear model predictive 6. Conclusion control of a robot manipulator. In proceedings of the 6th International Workshop on Advanced Motion Advanced motion control of a robot arm has been Control, 2000. considered in this study. This paper exhibits fully the [14] A. Vivas, P. Poignet. Predictive functional control of tracking performances of the PFC and its robustness a parallel robot. Control Engineering Practice, Vol. especially in the case of disturbance rejection and model 13, No. 7, pp. 863 - 874, 2005. mismatch, with a control scheme using the inverse [15] J. Richalet. Pratique de la Commande Prédictive. dynamic model. Hermès, 1993. [16] J. Richalet, E. Abu, C. Arber, H. Kuntze, A. Two model based control strategies are compared: Jacubasch, W. Schill. Predictive functional control - computed torque control and predictive functional control. Application to fast and accurate robots. In These controllers that use a feedback linearization, are proceedings of the 10th IFAC World Congress, 1997. applied to a PUMA 560 robot arm. The predictive [17] J. Richalet, A. Rault, J. Testud, J. Papon. Model strategy gives better results in tracking performance and predictive heuristic control: Applications to robustness, supplying solutions for the uncertainties that industrial process. Automatica, Vol. 14, 1978. the computed torque control can not resolve. Further [18] P. Corke, B. Armstrong-Hélouvry. A search for works will concern the implementation of this predictive consensus among model parameters reported for the control scheme computed with the inverse dynamic PUMA 560 robot. In proceedings of the IEEE model on a real PUMA type robot. Conference on Robotics and Automation, pp. 1608 - 1613, 1994.
You can also read