SciELO - Scientific Electronic Library Online

 
vol.15 número4Patient opinion mining to analyze drugs satisfaction using supervised learningOptimization for benzeneacetic acid removal from aqueous solution using CaO2 nanoparticles based on Taguchi method índice de autoresíndice de materiabúsqueda de artículos
Home Pagelista alfabética de revistas  

Servicios Personalizados

Revista

Articulo

Indicadores

Links relacionados

  • No hay artículos similaresSimilares en SciELO

Compartir


Journal of applied research and technology

versión On-line ISSN 2448-6736versión impresa ISSN 1665-6423

J. appl. res. technol vol.15 no.4 Ciudad de México ago. 2017

https://doi.org/10.1016/j.jart.2017.02.004 

Articles

Parameter identification methods for real redundant manipulators

Claudio Urreaa 

José Pascala  * 

aGrupo de Automática, Department of Electrical Engineering, Universidad de Santiago de Chile, Chile


Abstract

This work presents the development, assessment and comparison of four techniques for identifying dynamic parameters in an industrial redundant manipulator robot with 5 degrees of freedom. Based on the Lagrange-Euler formulation, a linear model of the robot with unknown parameters is obtained. Then, these parameters are identified using the following techniques: least squares, artificial Adaline neural networks, artificial Hopfield neural networks and extended Kalman filter. The parameters identified are validated by using them for computationally simulating the performance of the redundant manipulator robot, to which are imposed reference trajectories different from the ones used in the estimation. To relate the trajectories performed by the redundant manipulator robot with the estimated parameters, the following error indexes are calculated: Residual Mean Square, Residual Standard Deviation and Agreement Index. Finally, to determine the sensitivity of the model identified - due to the variations of the estimated parameters - a new simulation is conducted on the robot, considering that its parameters vary in a restricted range. In addition, the RMS error index of the trajectories performed is determined. After this step, the parameters of the redundant manipulator robot were successfully identified and, thus, its mathematical model was known.

Keywords: Robot dynamics; System identification; Mathematical model; Error indices

1. Introduction

Four closely related types of problem may be distinguished in the systems theory, namely modeling, analysis, estimation and control (Kessman, 2011). Modeling and estimation are extremely important to system identification. Modeling is a critical step when applying the systems theory to real processes aimed at obtaining a mathematical model that adequately describes a physical situation to be represented. To achieve this goal, several specifications should be considered, such as the limits and variables of the system. Then, the relationships between these variables need to be specified based on previous knowledge as well as on the assumptions about the uncertainties of the model, which characterize its structure. On the other hand, after obtaining an observable and identifiable model, the estimation of its unknown variables is addressed using an input/output dataset. Basically, there is a distinction between states and parameter estimation. Therefore, systems identification consists in experimentally determining a temporary behavior of a process or system, based on a mathematical model and using measured signals to determine such a behavior. The error (deviation) between the real process and its mathematical system has to be minimized to represent the real process or system in the best possible way (Isermann & Münchhof, 2011).

In the identification process, data characterizing the dynamics of the real process or system is first obtained. Then, a set of models is chosen and, finally, the best mathematical model of the set is selected. It should be noted that a mathematical model may be deficient due to reasons such as (Ljung, 1987):

  • - The failure in the numerical procedure conducted to find the best mathematical model, given a specific criterion.

  • - Ill-chosen criterion.

  • - No mathematical model satisfactorily describes the system.

  • -The information (data) is not sufficient for the selection of an appropriate mathematical model.

In summary, the general problem of systems identification may be expressed as: once known the structure and the value of some of the input and output variables of the system under study, it is necessary to determine the set ofparameters that better adjusts to these measures (Anríquez, 2011). Figure 1 shows the general scheme of the identification of one system.

Fig. 1 System identification scheme (Isermann & Münchhof, 2011). 

2. Methods for parameter identification

The methods for parameter identification applied to the redundant manipulator robot are explained below:

2.1. Least squares

Among the parameter estimation methods, least squares is widely used in the identification of manipulator robots (Bona & Curatella, 2005), since it is based on the use of a linear model inverse with respect to the parameters. This method allows estimating base inertial parameters from the measurement or estimation of torques and joint positions, optimizing the root mean square error of the model under the assumption that measurement errors are negligible. However, one problem in the application of this method is the noise sensitivity present in the measured data (Kessman, 2011), because noise will limit the accuracy of the obtained parameters as well as the convergence rate of the algorithm. To overcome this problem, it is suggested to generate excitation trajectories or to apply a filter to data (Ha, Ko, & Kwon, 1989).

The dynamic model may be written as a set of unknown parameters linear equations, as shown in Eq. (1):

τ = Φ (q, q˙, q¨) · λ (1)

where τ corresponds to the generalized forces vector, q to the generalized coordinates vector, λ to the vector or unknown dynamic parameters and Φ to the observation matrix or regres-sor. By applying the identification model to the model shown in (1), the linear equation system in λ is obtained as:

τ = Φ q, q˙, q¨· λ+ρ (2)

where ρ is the residual error vector. The estimated λ^ value may be obtained as:

λ^ = minρ2 (3)

which is the same as calculating:

λ^ =ΦTΦ-1ΦTτ (4)

2.2. Adaline neural networks

A neural network consists of a set of simple processing units, which communicate by sending signals to one another through weighted connection. Adaline (adaptive linear element) is one type of neural network. For a one-layer network with one output and one linear activation function, the output is given by Eq. (5):

y= i=1nwixi+θ (5)

This network is able to represent a linear relation between the values of the output and input units. The purpose of this network is to produce a given value y = dp in the output when the set of values xip, i = 0, 1, ..., n. is applied to the inputs. It is intended to determine the coefficients (weights) wi, i = 0, 1, ...,n. so the input-output response is correct for a large number of arbitrarily chosen signal sets. In this case, the "delta rule" to adjust weights is used for Adaline, training the network in such a way that the best adjustment for each set of data composed of the input values xip and desired outputs dp is obtained. For each input datum, the network output differs from the desired value by dp- yp, where yp corresponds to the current output for this pattern. The "delta rule" uses a cost or error function based on this difference to adjust the weights. The error function is given by the mean squared error. Therefore, the total error E is defined

E=pEp=12pdp-yp2 (6)

where the p index extends over the set of input patterns and Ep represents the error over the p pattern. This procedure allows for finding the value of all weights that minimize the error function by means of the gradient descent method:

Δpwi=-γEpwi (7)

where γ is a constant of proportionality and, also:

Epwi=Epypypwi (8)

Due to the linear relationship showed in (5):

ypwi=xi (9)

And

Epyp=-(dp-yp) (10)

Finally, we obtain:

Δpwi=-γδpxi (11)

where δp= (dp- yp) is the difference between the desired output and the current output for the p pattern.

2.3. Hopfield neural networks

Hopfield neural networks or HNNs can be used for estimating parameters on-line. In Hopfield's formulation, the dynamic of neuron i is described by the ordinary differential Equation (12) (Alonso, Mendonca, & Rocha, 2009):

duidt=-1Ci1Riui(t)+jWijfiujt+Ii (12)

where ui is the neuron input i, fi is a strictly increasing, bounded, nonlinear continuous function, and Ci, Ri, Wij and Ii are parameters that correspond to a capacitance, a resistance, the weight associated to the connection of the j neuron with the i neuron, and the i neuron external input or bias. In Abe's formulation, it is assumed that Ci =1 and Ri = ∞.

The considered system is linear with respect to the parameters, i.e. ithas the form shown in Eq. (1), which (1) works under the following assumptions:

  • (a) τ, ΦC1.

  • (b) τ, Φ are bounded.

  • (c) τ(t),Φ(t) are known in each t instant.

  • (d) λ ∈ ]-c, c[n for some c >0 unknown.

Given Abe's formulation, considering a network with N neurons, ui denotes the total input of the i neuron, its derivative with respect to time is:

dui(t)dt=-1Cij=1NWijtS j(t)+Ii(t) (13)

where Sj represents the state (or output) of the j neuron. The input-state relation for the i neuron is given by:

Sit=αtanhui(t)β (14)

where α, β>0 and, thus, ∀i e N, tt0 Si(t) ∈ ]-α, α[. Using matrix notation, the network is as follows:

dudt=-(WtSt+I(t)) (15)

St=αtanh(u(t)β) (16)

where S(t), I(t) ϵ ℝN×1 and W ϵ ℝN×N, under the statespace representation is:

dSdt=-1αβDαStWtStI(t) (17)

where

DαSt=diag(α2-Si(t)2)i ϵ N (18)

This a nonlinear and non-autonomous dynamic system whose architecture is completely determined by the N number of neurons, with characteristics given by α, β, W and I.

This work considers a HNN whose state S(t) over time t is taking as the estimation λ(t) of the λ parameter, in other words, λ(t) = S(t); implicitly, there is a network with as many neurons as parameters to estimate. Then, taking α = c,Eq. (14) guarantees that the trajectory generated for the network is in a feasible region of the estimation problem. Therefore, from the representation of states in Eq. (17), it is considered that: W = Φ(t)TΦ(t) and I= Φ(t)Tτ. In this way, the dynamic of the HHN to be used as an on-line estimation algorithm is defined by:

dλ^dt(t)=1cβDc(λ^(t))Φ(t)T(τ-Φ(t)λ^(t)) (19)

The advantage of using HNN to resolve the estimation problem is that inverting W = Φ(t)TΦ(t), is not necessary, since the latter might be ill-conditioned. In addition, given its structure, prior knowledge is not required for selecting λ(t0), i.e. of the initial estimation of λ.

Finally, the λ parameter is a globally, uniformly and asymptotically stable balance point of this HNN if the following sustains:

I [t0,+], =t  IkerΦt={0} (20)

2.4. Extended Kalman filter

The extended Kalman filter is based on the direct dynamic model, which is nonlinear with respect to state and parameters. In this algorithm, physical parameters are considered under the use of an extended state. Kalman filter intends to estimate the x ϵ ℝn state of a process controlled in discrete time (Welch & Bishop, 2006). The algorithm has two steps that are executed in an iterative way, namely prediction, and correction or update of the state. However, when a system has non-linear characteristics, the formulation should be modified. This change in the algorithm is known as extended Kalman filter. In this case, the process will be represented by the following non-linear equations:

xk= f (xk-1, uk-1) + wk-1 (21)

zk = h (xk ) + vk (22)

where f corresponds to a non-linear function that allows for knowing the relation between the previous step state vector k−1 and the u input with the current state vector k, according to the following procedure:

  • 1. Prediction stage

    • 1.1 Prediction of the state:

x^k-- = f (xk-1, uk-1) (23)

    • 1.2 Prediction of error covariance matrix:

Pk-= Fk-1Pk-1Fk-1T + Q (24)

  • 2. Correction or updating stage

    • 2.1 Kalman gain calculation

Kk = Pk-HkT [HkPk-HkT + R]-1 (25)

    • 2.2 State update with measures Zk:

x^k = x^k- + Kk (zk - h (x^k-)) (26)

    • 2.3 Covariance matrix update:

Pk= (I - KkHk) Pk- (27)

where Fk-1 and Hk corresponds the Jacobian matrices described in Eqs. (28) and (29), respectively:

Fk-1=fxxk-1, uk-1 (28)

Hk=hxx^k- (29)

where Q and R are the process and observation noise covariance matrices, respectively. In addition, they are diagonal and symmetric. On the other hand, x^k-  Rn are the states estimated a priori at k instant, given the process behavior and x^k  IRn the a posteriori estimated state at k instant, given the measure Zk.

3. Model of the industrial redundant manipulator robot

The manipulator robot used in this study is redundant, since it has five degrees of freedom (DOF), and a PRRRP configuration. Figure 2 shows a scheme of manipulator robot and its coordinate assignment. In addition, its Denavit-Hartenberg parameters are presented in Table 1.

Fig. 2 Assignment of coordinate systems of the PRRRP manipulator robot. 

Table 1 Devanavit-Hartenberg parameters. 

Articulation θi di ai αi
1 l1 + d1 0
2 θ2 0 l2
3 θ3 0 l3
4 θ4 0 l4 180°
5 l5 + d5 0

The Lagrange-Euler formulation describes the behavior of a dynamic system in terms of work and energy stored in the system. The Lagrangian L is defined as:

L (qi, q˙i) = T - U (30)

From this Lagrangian, the dynamic system equations of motion are given by:

ddt Lq˙i-Lqi=Qi (31)

where L is the Lagrangian function, T the kinetic energy, U the potential energy, qi the generalized coordinates, and Qi the generalized force applied to qi. The general form of a manipulator robot dynamic model is shown in Annex A.

4. Simulation of the methods for parameter identification

Table 2 shows the dynamic parameters of each link of the redundant manipulator robot (mass, length, center of mass and inertia) (Urrea & Kern, 2016).

Table 2 Parameters of the redundant manipulator robot parameters with 5 DOL. 

Parameter Link 1 Link 2 Link 3 Link 4 Link 5 Unit
l 0.524 0.2 0.2 0.2 0.14 [m]
lc - 0.0229 0.0229 0.0229 - [m]
m 1.228 1.023 1.023 1.023 0.5114 [kg]
lzz - 0.0058 0.0058 0.0058 - [kg m2]

In this work, we consider the following methods for identifying the parameters of the redundant manipulator robot: least squares, Adaline neural networks, Hopfield neural networks and extended Kalman filter. A brief description of these methods is presented below:

4.1. Least squares

The least squares procedure to estimate the parameters of each link of the redundant manipulator robot might be summarized in the following steps:

  • - Using some formulation, generate a robot model that is linear with respect to the inertial parameters.

  • - Reducing the inertial parameters to a set of base parameters.

  • - Determining the optimal trajectory of the parameters and optimize the excitation of the trajectories.

There is a number of methodologies to determine both the parameters influencing the systems dynamic and the set of minimum parameters required to identify the models ofsuch systems (Choi, Yoon, Park, & Kim, 2011; Mayeda, Yoshida, & Ohashi, 1989; Mayeda, Yoshida, & Osuka, 1990; Radkhah, Kulic, & Croft, 2007). This work considers a numerical method that allows for identifying the set of independent parameters of the redundant manipulator robot, based on the analysis of the kernel of the regressor.

For a redundant manipulator robot with j links, ten inertial parameters are considered per link:

ξj=(mj  pg,jT  υjT)T (32)

where mj, pg,j = (xg,j yg,j zg,j)T and υj = (Ixx,j Iyy,j Izz,j Ixy,j Ixz,,j Iyz,j)T, are the mass, the position of the center of gravity, and the vector with the elements of the inertia tensor of the j link, respectively. A linear form may be composed by grouping the parameters as follows:

τ=Φ(q, q˙, q¨)λ(ξ)τ1τ2τn=ϕ1100    ϕ12ϕ220        ϕ1nϕ2nϕnnλ1(ξ-)λ2(ξ-)λn(ξ-) (33)

where

λjξ-=mj   mjpg,jT  πjT  υjTTϵ R16πj=mjxg,j2yg,j2zg,j2xg,jyg,jyg,jzg,jzg,jxg,jT (34)

The regressor Φ is not always linearly independent or has a full rank, thus there might not be a unique solution. Nevertheless, it is possible to reduce the number of unknown parameters and transform the system into: τ = Φ* λ*, where λ* is the vector for regrouped parameters. It is hard to find the linear relation between dependent and independent columns of the regressor, since dynamic relationships are complex. To find this relation, the kernel of the matrix is used, which denotes the relation between columns dependent and independent from the regressor in linear combinations. In this way, the new grouped parameters λ* and the full rank matrix Φ* may be found. The calculation is conducted in a recursive way, starting from the n joint up to the articulation 1.

In this case, the vector of regrouped parameters λ* is composed of eight elements to be identified, which are presented in Table 3. The structure of the regressor Φ* ∈ ℝ5×8 is described in Annex B.

Table 3 Grouped parameters of the redundant manipulator robot. 

Grouped parameters Inertial parameters
λ1* m1 + m2 + m3 + m4
λ2* m2lc22+m3l22+m4l22+m5l22+I2zz
λ3* m3lc32+m4l32+m5l32+I3zz
λ4* m3lc3l2+m4l3l2+m5l3l2
λ5* m4lc42+m5l42+I3zz
λ6* m4lc4l2+m5l4l2
λ7* m4lc4l3+m5l4l3
λ8* m5

4.1.1. Excitation trajectories

When a system identification experiment is designed, it is necessary to consider a trajectory that sufficiently excites the redundant manipulator robot parameters during the movement. Otherwise, some parameters will be impossible to identify, or will become too sensitive to noise (Swevers, Ganseman, De Schutter, & Van Brussel, 1996). Meanwhile, since the regressor Φ* depends on joint coordinates and its time derivatives, when the manipulator robot executes a particular trajectory GDL · npts equations will be obtained, generating an over-determined system. Thus, considering the points traveled in the trajectory, the system is given by the expression:

τ = W ·λ* (35)

where τ is the torque/force vector  RGLD·npts, w is the  RGLD·npts×np system observation matrix, λ* is the vector of the grouped parameters  Rnp, nptos is the number of samples and np corresponds to the number of parameters grouped. Then, to identify the parameters it is necessary to calculate:

λ*= (WTW)-1WTτ (36)

Parameters accuracy is closely related to the observation matrix W, so the purpose is to obtain a well-conditioned matrix that allows for enhancing the estimation results (Wu, Wang, & You, 2010). This implies finding the denominated "excitation trajectories", which correspond to an optimization problem that consists in minimizing a function like the one presented in (37) subjected to the constraints of Eq. (38):

min f (q, q˙, q¨) (37)

qmin  q  qmaxq˙min  q˙  q˙maxq¨min  q¨  q¨max (38)

where function f satisfies the criterion k(W) = (σmax/σmin), q, q˙, q¨ are the generalized coordinates of position, velocity and acceleration, respectively, σmax is the highest singular value of W and σmin the lowest singular value of W.

4.1.2. Trajectory parameterization

The prismaticjoints motion does not participate in the rotary joint dynamics. Thus, without loss of generality, trajectory optimization is only applied to rotaryjoints, since they are in conflict with the parameter estimation of least squares. The reverse is true for the prismatic link with linear characteristics. The excitation trajectories are planned using a polynomial of degree five (Benimeli, 2005) in the form of Eq. (39) and the elements to be optimized are their coefficients: a0i , a1i , . . ., a5i.

qi=a01+a1it+a2it2+a3it3+a4it4+a5it5 (39)

Reference sinusoidal trajectories are applied to the first and fifth link (prismatic joints). All the reference and output trajectories of all the joints of the redundant manipulator robot are shown in Figure 3. An electronic noise is observed due to the sensing (measuring) of the output trajectories.

Fig. 3 Reference and output trajectories of the redundant manipulator robot with 5 DOL. 

4.2. Adaline neural nefworks

Applying the linear model formulation to the parameters τ = Φ* ·λ* (see Annex B), we have that:

F1=Φ11*λ1*+Φ18*λ8*τ2=Φ22*λ2*+Φ23*λ3*+Φ24*λ4*+Φ25*λ5*+Φ26*λ6*+Φ27*λ7*τ3=Φ33*λ3*+Φ34*λ4*+Φ35*λ5*+Φ36*λ6*+Φ37*λ7*τ4=Φ45*λ5*+Φ46*λ6*+Φ47*λ7*F5=Φ58*λ8* (40)

Therefore, when using an Adaline network, the parameters to be identified coincide with the network weights. Below, one-layer neural networks are designed with their inputs corresponding to the elements of the regressor and their outputs to the elements of torque/forces. Figure 4 shows the scheme of the networks used for the identification of the parameters of the redundant manipulator robot.

Fig. 4 Adaline neural network for identification. (a) Network 1. (b) Network 2. 

4.3. Hopfield neural nefworks

For satisfactorily identifying the parameters of the redundant manipulator robot, all intervals of t ⊂ [0, + ∞] shouldsatisfy the condition given by Eq. (20). Figure 5 shows the response produced by the HNN. The last estimated valued is used for the comparison.

Fig. 5 Online estimation of Hopfield neural networks. 

4.4. Extended Kalman filter

In this method, use is made of the dynamic model of the redundant manipulator robot, i.e. the joint coordinates that mathematically depended on the force/torque applied to them are used. The direct dynamic model is symbolically calculated from the Lagrange-Euler formulation and the grouped parameters described in Table 3, and then is expressed in the state variables presented in Eq. (41). The parameters to be identified are included in an extended state of the algorithm with a time derivative of null values, as shown in Eq. (42):

x=d1d˙1θ2d˙5λ1*    θ˙2θ3θ˙3λ2*λ3*λ4*   θ4θ˙4d5 λ5*λ6*λ7*   λ8*T (41)

x˙=d˙1d¨1θ˙2d¨50    θ¨2θ˙3θ¨3000   θ˙4θ¨4d˙5 000   0T (42)

Euler approximation is used for the equations whose time derivative was calculated, as seen in Eq. (43):

x˙xk+1-xkt (43)

Therefore, from the equation above, xk+1= xk+ Δt·x˙k is obtained, whose sampling time is At = 0.02. In turn, the initial state vectors used are initial error covariance matrix, process noise covariance matrix and observation covariance matrix, as presented in Eq.(44):

x0=0, 1·11111     111111     111111    1TP0 R18×18,Pij=1Q=diag 11111     111111     111111    11R=10·diag11111     111111     111111    1 (44)

The reference trajectories used in this identification process are the same applied to the least square methods, i.e. those presented in Figure 3. The evolution of the parameter estimation curves is shown in Figure 6. In this case, the last value of the estimation is considered for error comparison.

Fig. 6 Evolution of the parameters estimated by extended Kalman filter. 

5. Results

Table 4 shows the base parameters identified for each of the studied methods.

Table 4 Estimated parameters. 

Parameter Least squares Adaline Hopfield Kalman
λ1* 4.2969 4.2027 4.2984 4.2966
λ2* 0.1094 0.1450 0.0822 0.0647
λ3* 0.0677 0.0500 0.0551 -0.0114
λ4* 0.0671 0.0652 0.0692 -0.0080
λ5* 0.0271 0.0259 0.0354 0.0742
λ6* 0.0260 0.0181 0.0578 0.0634
λ7* 0.0251 0.0459 0.0287 0.0859
λ8* 0.5114 0.6056 0.5136 0.5119

5.1. Trajectory validation

To validate the identified parameters, they are used in performance simulations on the redundant manipulator robot. In these simulations, validation trajectories different from those used in the estimation are imposed to the robot. To relate the trajectories performed by the redundant manipulator robot with the estimated parameters of the same, the following error indexes are calculated: Residual Mean Square (RMS), Residual Standard Deviation (RSD) and Agreement Index (AI); which are mathematically represented in Eqs. (45)-(47), respectively. RMS and RSD correspond to normalized percentage values between 0 and 1; indexes that explain the dispersion and deviation of the series, respectively. In addition, the AI index indicates the trend of the two series to be compared; the values that adopts may fluctuate between 0 and 1, where: 1 corresponds to a perfect match and 0 to absence of agreement. The trajectories performed by the redundant manipulator robot are shown in Figure 7, and their error indexes in Table 5. It should be noted that the trajectories presented in Figure 7 are basically overlapped, and that the values of the parameters do not show high sensitivity to following imposed trajectories:

RMS=i=1noi-pi2n (45)

RSD=i=1noi-pi2i=1noi2 (46)

AI=1-i=1noi-pi2i=1nOi'-pi'2      oi'=oi-ompi'=pi-pm (47)

where oi are the values observed, om the mean value of the observations, pi are the predicted values and n is the total number of observations.

Fig. 7 Validation trajectories. 

Table 5 Error indexes. 

Algorithm
Joint Least squares Adaline Hopfield Kalman
1 RMS 0.0000 0.0000 0.0000 0.0000
RSD 0.0000 0.0000 0.0000 0.0000
AI 1.0000 1.0000 1.0000 1.0000
2 RMS 0.0000 0.0000 0.0000 0.0001
RSD 0.0000 0.0001 0.0001 0.0002
AI 1.0000 1.0000 1.0000 1.0000
3 RMS 0.0000 0.0000 0.0000 0.0001
RSD 0.0000 0.0000 0.0000 0.0001
AI 1.0000 1.0000 1.0000 1.0000
4 RMS 0.0000 0.0000 0.0000 0.0001
RSD 0.0000 0.0000 0.0000 0.0002
AI 1.0000 1.0000 1.0000 1.0000
5 RMS 0.0000 0.0012 0.0000 0.0000
RSD 0.0000 0.0112 0.0003 0.0001
AI 1.0000 0.9998 1.0000 1.0000

To determine the sensitivity of the identified model, due to the variations of the estimated parameters, the redundant manipulator robot is simulated, considering that its parameters varied in a restricted range of values. Also, its RMS error index is calculated between the trajectories described. Table 6 presents the range of values for the variations in the 士50% parameters. In Figure 8, the evolution of the RMS index of the performed trajectories, with respect to each estimated parameter, is illustrated.

Table 6 Range of estimated parameters. 

Parameter Minimum value Maximum value
λ1* 2.1335 6.4004
λ2* 0.0547 0.1641
λ3* 0.0339 0.1016
λ4* 0.0334 0.1007
λ5* 0.0136 0.0407
λ6* 0.0130 0.0390
λ7* 0.0126 0.0377
λ8* 0.2557 0.7671

Fig. 8 Sensitivity of the model of the redundant manipulator robot. 

6. Conclusions

In this paper, we presented the identification of the parameters of an industrial redundant robot with 5 DOF. By means of the Lagrange-Euler formulation, the linear model with unknown parameters was obtained. To identify theseparameters, four methods were used, assessed and compared, namely least squares, Adaline neural networks, Hopfield neural networks, and extended Kalman filter.

The identified parameters were validated by computationally simulating the performance of the redundant manipulator robot. To this end, reference trajectories different from those used in the estimation were imposed to the robot.

To relate the trajectories described by the redundant manipulator robot with its estimated parameters, the following error indexes were calculated: Residual Mean Square, Residual Standard Deviation and Agreement Index.

The sensitivity of the identified model to parameter variation is low.

The parameters of the redundant manipulator robot were successfully identified and, therefore, the robot mathematical model was known. Thanks to this achievement, it is now possible to design, simulate, compare, validate and implement diverse strategies for controlling this industrial redundant robot with 5 DOF.

Acknowledgments

This work was supported by Proyectos Basales and the Vicerrectoría de Investigación, Desarrollo e Innovación of the Universidad de Santiago de Chile, Chile.

References

Alonso, H., Mendonca, T., & Rocha, P. (2009). Hopfield neural networks for on-line parameter estimation. Neural Networks, 22(4), 450-462. http://dx.doi.org/10.1016/j.neunet.2009.01.015 [ Links ]

Anríquez, M. (2011). Desarrollo de una nueva metodología de identificación de parámetros para sistemas no lineales: aplicación al modelo de Lorenz. Santiago, Chile: Universidad de Santiago de Chile. [ Links ]

Benimeli, F. (2005). Estimación de parámetros dinámicos en robots manipuladores. Valencia: Universidad Politécnica de Valencia. [ Links ]

Bona, B., & Curatella, A. (2005). Identification of industrial robot parameters for advanced model-based controllers design. In Proceedings ofthe 2005 IEEE international conference on robotics and automation (pp. 1681-1686). IEEE. http://dx.doi.org/10.1109/ROBOT.2005.1570355 [ Links ]

Choi, J. S., Yoon, J. H., Park, J. H., & Kim, P. J. (2011). A numerical algorithm to identify independent grouped parameters of robot manipulator for control. In 2011 IEEE/ASME international conference on advanced intelligent mechatronics (AIM) (pp. 373-378). IEEE. http://dx.doi.org/10.1109/AIM.2011.6027068 [ Links ]

Ha, I. J., Ko, M. S., & Kwon, S. K. (1989). An efficient estimation algorithm for the model parameters of robotic manipulators. IEEE Transactions on Robotics and Automation, 5(3), 386-394. http://dx.doi.org/10.1109/70.34777 [ Links ]

Isermann, R., & Münchhof, M. (2011). Neural networks and lookup tables for identification. Identification of Dynamic Systems, 501-537. http://dx.doi.org/10.1007/978-3-540-78879-9-20 [ Links ]

Kessman, K. J. (2011). System identification: An introduction (1st ed.). London: Springer-Verlag. http://dx.doi.org/10.1007/978-0-85729-522-4 [ Links ]

Ljung, L. (1987). System identification: Theory for the user. Prentice Hall. [ Links ]

Mayeda, H., Yoshida, K., & Ohashi, K. (1989). Base parameters of dynamic models for manipulators with rotational and translational joints. In International conference on robotics and automation (pp. 1523-1528). IEEE Comput. Soc. Press. http://dx.doi.org/10.1109/ROBOT.1989.100195 [ Links ]

Mayeda, H., Yoshida, K., & Osuka, K. (1990). Base parameters of manipulator dynamic models. IEEE Transactions on Robotics and Automation, 6(3), 312-321. http://dx.doi.org/10.1109/70.56663 [ Links ]

Radkhah, K., Kulic, D., & Croft, E. (2007). Dynamic parameters identification forthe CRS A460 robot. In IEEE/RSJinternational conference onintelligent robots and systems (pp. 3842-3847). [ Links ]

Swevers, J., Ganseman, C., De Schutter, J., & Van Brussel, H. (1996). Experimental robot identificacion using optimised periodic trajectories. Mechanical Systems and Signal Processing, 10(5), 561-577. http://dx.doi.org/10.1006/mssp.1996.0039 [ Links ]

Urrea, C., & Kern, J. (2016). Trajectory tracking control of a real redundant manipulator of the SCARA type. Journal of Electrical Engineering & Technology, 11(1), 215-226. http://dx.doi.org/10.5370/JEET.2016.11.L215 [ Links ]

Welch, G., & Bishop, G. (2006). An introduction to the Kalman filter (TR95-041). Chapel Hill: University of North Carolina at Chapel Hill, Department of Computer Science. [ Links ]

Wu, J., Wang, J., & You, Z. (2010). An overview of dynamic parameter identification of robots. Robotics and Computer-Integrated Manufacturing, 26(5), 414-419. http://dx.doi.org/10.1016/j.rcim.2010.03.013 [ Links ]

Peer Review under the responsibility of Universidad Nacional Autónoma de México.

Annex A. Dynamic model

The dynamic model of the manipulator robot was developed in (Urrea&Kern, 2016). Below arepresented thecomponents of the inertia matrix, the centrifugal force and Coriolis force vector and the gravity vector, respectively.

M11=m1+m2+m3+m4+m5 (A.1)

M12=M21=M13=M31=M14=M41=M25=M52=M35=M53=M45=M54=0 (A.2)

M15=M51=-m5 (A.3)

M22=lc22m2+l22+lc32+2l2lc3c3m3+l22+l32+lc42+2l2l3c3m4+2l3lc4c4+l2lc4c34m4+l22+l32+l42+2l2l3c3m5+2l3l4c4+l2l4c34m5+I2zz+I3zz+I4zz (A.4)

M23=M32=lc32+l2lc3c3m3+l22+lc42+l2l3c3+2l3lc4c4m4+l2lc4c34m4+l2l4cos34m5+l32+l42+l2l3c3+2l3l4c4m5+I3zz+I4zz (A.5)

M24=M42=lc42+l3lc4c4+l2lc4c34m4+l42+l3l4c4+l2l4c34m5+I4zz (A.6)

M33=lc32m3+l32+lc42+2l3lc4c4m4+l32+l42+2l3l4c4m5+I3zz+I4zz (A.7)

M34=M43=lc42+l3lc4c4m4+l42+l3l4c4m5+I4zz (A.8)

M44=lc42m4+l42m5+I4zz (A.9)

M55=m5 (A.10)

C11=C15+0 (A.11)

C12=-l2s3·θ˙32+2l2s3·θ˙2θ˙3(lc3m3+l3m4+l3m5)+l2s34·θ˙32+2l3s4+l2s34 θ˙3θ˙4(lc4m4+l4m5)+l2s34·θ˙2θ˙3-θ˙42+2θ˙2θ˙4(l2s34+l2s4)×lc4m4+l4m5 (A.12)

C13=lc3m3+l3m4+l3m5l2s3·θ˙22+l2s34·θ˙22-2θ˙2+θ˙3+θ˙4l3s4θ˙4(lc4m4+l4m5) (A.13)

C14=lc4m4+l4m5l3s4+l2s34θ˙22+l3s4·θ˙32+2l3s4·θ˙2θ˙3(lc4m4+l4m5) (A.14)

G=m1+m2+m3+m4+m5gz000-m5gzT (A.15)

where s3 = sin θ3, s4 = sin θ4, c3 = sin θ3, c4 =cos θ4, s34 = sin(θ3+ θ4) and c34 = cos(θ3 + θ4); m1, m2, m3, m4, m5 and l1, l2, l3, l4, l5 represent the masses and length of the first, second, third, fourth and fifth link, respectively; lc2lc3 and lc4 express the lengths from the origin to the mass center of the second, third and fourth link, accordingly. Finally, l2zz, l3zz and l4zz represent the moments of inertia of the second, third and fourth links, referred to the z axis of each joint, respectively.

Annex B. Linear model with regrouped parameters

Below are shown the elements of the regressor Φ* ∈ ℝ5×8, obtained from the linear formulation with grouped parameters τ = Φ**:

τ=Φ*·λ*:τ=F1τ2τ3τ4F5T (B.1)

Φ*=ϕ11*00000ϕ22*0000ϕ23*ϕ33*000ϕ24*ϕ34*ϕ44*0ϕ15*000ϕ55* (B.2)

ϕ11*=d¨1+g (B.3)

ϕ15*=d¨1-d¨5+g (B.4)

ϕ22*=θ¨1 (B.5)

ϕ23*=θ¨2+θ¨32θ¨2+θ¨3c3-2θ˙2θ˙3+θ˙32s3T (B.6)

ϕ24*=θ¨2+θ¨3+θ¨42θ¨2+θ¨3+θ¨4c34-2θ˙2θ˙4+θ˙3θ˙4+2θ˙2θ˙3+θ˙32+θ˙42s342θ¨2+θ¨3+θ¨4c4-2θ˙2θ˙4+θ˙3θ˙4+θ˙42s4T (B.7)

ϕ33*=θ¨2+θ¨3θ¨2c3+θ˙22s3T (B.8)

ϕ34*=θ¨2+θ¨3+θ¨4θ¨2c34+θ˙22s342θ¨2+2θ¨3+θ¨4c4-2θ˙4+θ˙3θ˙4+θ˙42s4T (B.9)

ϕ44*=θ¨2+θ¨3+θ¨4θ¨2c34+θ˙22s34θ¨2+θ¨3c4-θ˙22+θ˙32+2θ˙2θ˙3s4T (B.10)

ϕ55*=d¨1+d¨5-g (B.11)

Received: April 09, 2016; Accepted: February 16, 2017

*Corresponding author. E-mail address: claudio.urrea@usach.cl (C. Urrea).

Conflict of interest

The authors have no conflicts of interest to declare.

Creative Commons License This is an open-access article distributed under the terms of the Creative Commons Attribution License