Chapter 2

Stable PID Control and Systematic Tuning of PID Gains

Abstract

Although great progress has been made in a century-long effort to design and implement robotic exoskeletons, many design challenges continue to limit the performance of the system. One of the limiting factors is the lack of simple and effective control systems for the exoskeleton [56,137]. The position error caused by gravitational torques can be reduced by introducing an integral component to the PD control. In order to assure asymptotic stability, several components were previously added to the classic linear PID controllers, for example, fourth-order filter [101], nonlinear derivative term [4], nonlinear integral term (saturated function) [71], input saturation, and nonlinear observer [2].

Linear PID is the simplest and the most popular industrial controller, since tuning its internal parameters does not require a model of the plant and can be performed experimentally. Lyapunov function was previously used for the tuning procedure of a linear PID [72]. However, the inertia matrix and the gravitational torque vector of the system have to be clearly defined [63,73]. If the robot dynamic can be rewritten into a decoupled linear system with bounded nonlinear system, the stability of linear PID can be proven [117]. The asymptotic stability was not achieved.

In this chapter, the semiglobal asymptotic stability is proven along with a new approach for tuning the parameters of the PID controller. We apply this method on an upper limb exoskeleton. Experimental results show that this new PID tuning method is simple, systematic, and effective for robot control.

Keywords

Semiglobal asymptotic stability; PID gains; Systematic tuning

2.1 Stable PD and PID control for exoskeleton robots

The dynamics of a serial n-link exoskeleton robot can be written as [131]

M(q)q+C(q,q)q+g(q)+f(q)=τ

Image (2.1)

where qnImage denotes the joint positions, qnImage denotes the joint velocities, M(q)n×nImage is the inertia matrix, C(q,q)n×nImage is the centripetal and Coriolis matrix, fRnImage is the frictional terms (Coulomb friction), τnImage is the input control vector, and g(q)nImage is the gravity vector, which satisfies

g(q)=qU(q)U=ni=1mighi

Image (2.2)

where hi=yiImage, yiImage is in the vector oi=[xi,yi,zi]TImage, oiImage is given by the first three elements of the fourth column of the homogeneous transformation matrix.

The robot (2.1) has the following structural properties, which will be used in the stability analysis of the PID control.

Property 2.1. The inertia matrix is symmetric and positive definite, i.e.,

m1x2xTMxm2x2

Image

where xRnImage, m1Image and m2Image are known positive scalar constant, and .Image denotes the Euclidean vector norm.

Property 2.2. The centripetal and Coriolis matrix is skew-symmetric, i.e.,

xT[M(q)2C(q,q)]x=0

Image (2.3)

C(q,˙q)˙qkc˙q2,kc>0

Image (2.4)

˙M(q)=C(q,˙q)+C(q,˙q)T

Image (2.5)

where Ck,ij(q)=(Bijqk+BikqjBjkqi)Image, kc=12maxqRnnk=1Ck(q)Image, and C0(q)Image is a bounded matrix.

Property 2.3. The gravitational torques vector g(q)Image in (2.2) is Lipschitz:

g(x)g(y)kgxy

Image (2.6)

2.1.1 Stable PD control

The classic industrial PD law for the robot (2.1) is

τ=Kp(qqd)Kd(qqd)=PD1

Image (2.7)

where KpImage and KdImage are positive definite, symmetric, and constant matrices, which correspond to proportional and derivative coefficients, qdnImage is the desired joint position, qdnImage is the desired joint velocity.

In regulation case, the desired position is constant, qd=0Image. We use the Lyapunov function candidate as

VPD=12˙qTM˙q+12˜qTKp˜q

Image (2.8)

where ˜q=qqdImage.

By the property ˙qT[M(q)2C(q,q)]˙q=0Image and the matrix inequality [159]

XTY+YTXXTΛX+YTΛ1Y,

Image

which is valid for any X, YRn×mImage and any 0<Λ=ΛTRn×nImage, the modeling error ˙qT(G+F)Image can be estimated as

˙qT(G+F)˙qTK1˙q+(G+F)TK11(G+F)

Image

where K1Image is any positive definite matrix, the derivative of (2.8) is

VPD=˙qTKd˙q+˙qT(G+F)˙qT(KdK1)˙q+ˉd

Image (2.9)

where (g+f)TK11(g+f)ˉdImage, ˉdImage can be regarded as upper bound of G+FImage.

  • •  If G and F are zero, the PD control (2.7) can assure

VPD˙qT(KdK1)˙q

Image

  • When we choose Kd>K1Image, VPD0Image, the closed-loop system is stable.
  • •  If G and F are not zero, when we choose Kd>K1Image, the regulation error ˜qImage is bounded (stable), and ˙q(KdK1)Image converges to ˉdImage [54]
  • •  If G and F are known, the PD control is modified as

τ=Kp(qqd)Kd(qqd)+F+G

Image

  • then

VPD˙qT(KdK1)˙q

Image

  • When we choose Kd>K1Image, VPD0Image, and the closed-loop system is stable.

In tracking the case, the purpose is to make the joint motors follow the desired positions. The desired joint positions are generated by the path planning or trajectory planning, and are sent to the joint motors [72]. The tracking control can be divided into several regulations by the path planning.

We can also use the following auxiliary error method. We define x1=qImage as the link position vector, x2=˙qImage as the link velocity vector. The tracking error is

x1=x1xd1x2=˙x1˙xd1ddtx1=x2

Image

where xd1Image is link position desired and xd2Image is link velocity desired. The auxiliary error is defined as

r=x2+Λx1

Image

where Λ=ΛT>0Image. The PD control (2.7) becomes

τ=Kvr

Image (2.10)

When the dynamics of the robot (2.1) are known, the PD control with the known model compensation is

τ=Kvrf+(G+F)

Image (2.11)

where f=M(Λx1qd)+C(Λx1qd)Image.

We use the Lyapunov function candidate as

V=12rTMr

Image

From Property 2.2, rT[M2C]r=0Image,

V=rTKvr

Image (2.12)

Then r0Image when the dynamics of the robot are known.

  • •  If F and G in (2.1) are unknown, similar with (2.9), the PD control (2.10) has

VrTKvr+ˉd

Image

  • when Kd>KvImage, the regulation error r is bounded (stable) and converges to ˉdImage.
  • •  If G and F are known, or the dynamic of the robot (2.1) is known, the PD control (2.11) makes the closed-loop system stable.
  • •  If G and F are zero, the PD control (2.10) can assure V0Image, the closed-loop system is stable.

In general, the regulation error of the PD control law (2.7) is bounded in a ball with radius ˉdImage.

The stability property is not enough for robot control. The steady-state error caused by gravity and friction may be big. The derived gain KdImage has to be increased to decrease them. In this way the closed-loop system becomes slow. This big settling time does not allow us to increase KdImage as we want.

We use the stability property of PD control (2.7) to stabilize the open loop unstable robot (2.1). For any Kd>K1Image (K1>0Image), the following closed-loop system is stable:

M(q)q+C(q,q)q+g(q)+f(q)=PD1

Image (2.13)

when the robot dynamics contain the gravitational torques vector g(q)Image. Gravity compensation is a popular method to modify the PD control (2.7). The new PD control is

τ=PD1+ˆg(q)

Image (2.14)

where g(q)=ˆg(q)+˜g(q)Image, ˆg(q)Image, and ˜g(q)Image are the gravity estimation and estimation error and in this case (2.9) become

VPD˙qT(KdK1)˙q+ˉd1

Image (2.15)

where ˉd1Image is the upper bound of (˜g+f)Image, (˜g+f)TK11(˜g+f)ˉd1Image. Normally, ˉd1<<ˉdImage, because ˜gImage is the estimation error of the gravity. The closed-loop system (2.13) becomes

M(q)q+C(q,q)q+g(q)+f(q)=PD1+ˆg(q)

Image

Similar stability results as before can be obtained and only the upper bound of the gravity becomes smaller.

2.1.2 Stable PID control

The position control objective is to evaluate the torque applied to the joints so that the robot joint displacements tend asymptotically to constant desired joint positions. Given a desired constant position qdRnImage, semiglobal asymptotic stability of robot control is to design the input torque τ in (2.1) to cause regulation error

˜q=qdq

Image

˜q0Image and ˜q0Image when initial conditions are in arbitrary large domain of attraction. Classic linear PID law is

τ=Kp˜q+Kit0˜q(τ)dτ+Kd˜q

Image

where KpImage, KiImage, and KdImage are proportional, integral, and derivative gains of the PID controller, respectively.

The common linear PID control does not include any component of the robot dynamics into its control law. In order to assure asymptotic stability of PID control, the simplest approach is to modify the linear PID into a nonlinear one. This chapter will work on the linear PID, which is the most popular industrial controller. In [117] the robot dynamic was rewritten in a decoupled linear system and bounded nonlinear system; this linear PID control could not guarantee asymptotic stability. Sufficient conditions of the linear PID in [72] were given via Lyapunov analysis. However, these conditions are not explicit; the PID gains could not be decided with these conditions directly, and a complex tuning procedure was needed [73].

Because ˙qd=0Image, ˜q=˙qImage, the PID control law can be expressed via the following equations:

τ=Kp˜qKd˙q+ξ˙ξ=Ki˜q,ξ(0)=ξ0

Image (2.16)

In matrix form, it is

ddt[ξ˜q˜q]=[Ki˜q˙q¨qd+M1(C˙q+gKp˜q+Kd˙qξ)]

Image (2.17)

The closed-loop system of the robot (2.13) is

M(q)¨q+C(q,˙q)˙q+g(q)=Kp˜qKd˙q+ξ,˙ξ=Ki˜q

Image

The equilibrium is [ξ,˜q,˜q]=[ξ,0,0]Image. Since at equilibrium point q=qdImage the equilibrium is [g(qd),0,0]Image. In order to move the equilibrium to origin, we define ˜ξ=ξg(qd)Image. The closed-loop equation becomes

M(q)¨q+C(q,˙q)˙q+g(q)=Kp˜qKd˙q+˜ξ+g(qd)˜ξ=Ki˜q

Image (2.18)

Theorem 2.1

Consider the robot dynamic (2.1) controlled by the linear PID controller (2.16). The closed-loop system (2.18) is semiglobally asymptotically stable at the equilibrium x=[ξg(qd),˜q,˜q]T=0Image, provided that control gains satisfy

λm(Kp)32kgλM(Ki)βλm(Kp)λM(M)λm(Kd)β+λM(M)

Image (2.19)

where β=λm(M)λm(Kp)3Image, kgImage satisfies (2.6), λm(A)Image is the minimum eigenvalue of A, and λM(A)Image is the maximum eigenvalue of A.

Proof

We construct a Lyapunov function as

V=12˙qTM˙q+12˜qTKp˜q+U(q)ku+˜qTg(qd)+α2˜ξTK1i˜ξ+˜qT˜ξ+32g(qd)TK1pg(qd)α˜qTM˙q+α2˜qTKd˜q

Image (2.20)

where ku=minq{U(q)}Image, U(q)Image is defined in (2.2), kuImage is added such that V(0)=0Image. α is a design positive constant. We first prove V is a Lyapunov function, V0Image. The term 12˜qTKp˜qImage is separated into three parts, and V=4i=1ViImage:

V1=16˜qTKp˜q+˜qTg(qd)+32g(qd)TK1pg(qd)V2=16˜qTKp˜q+˜qT˜ξ+α2˜ξTK1i˜ξV3=16˜qTKp˜qα˜qTM˙q+12˙qTM˙qV4=U(q)ku+α2˜qTKd˜q0

Image

It is easy to find

V1=12[˜qg(qd)]T[13KpII3K1p][˜qg(qd)]0

Image

When α3λm(K1i)λm(Kp)Image,

V21216λm(Kp)˜q2˜q˜ξ+αλm(K1i)2˜ξ2=12(13λm(Kp)˜q3λm(Kp)˜ξ)20

Image

Because

yTAxyAxyAx|λM(A)|yx

Image

when α13λm(M)λm(Kp)λM(M)Image,

V312(λm(M)˙q22αλM(M)˜q˙q+13λm(Kp)˜q2)=12(λm(M)˙q13λm(Kp)˜q)20

Image

Obviously, if

13λm(K1i)λ32m(Kp)λ12m(M)λM(M)

Image (2.21)

there exists

13λm(M)λm(Kp)λM(M)α3λm(K1i)λm(Kp)

Image (2.22)

This means if KpImage is sufficiently large or KiImage is sufficiently small, (2.21) is established, and V(˙q,˜q,˜ξ)Image is globally positive definite. Now we compute its derivative. Taking the derivative of V, we get

˙V=˙qTM¨q+12˙qTM˙q+˜qTKp˜q+g(q)T˙q+˜qTg(qd)+α˜ξTK1i˜ξ+˜qT˜ξ+˜qT˜ξα(˜qTM˙q+˜qTM˙q+˜qTM¨q)α˜qTKd˙q

Image (2.23)

Using (2.3), ddtU(q)=˙qTg(q)Image, ddtg(qd)=0Image, and ddt[˜qTg(qd)]=˜qTg(qd)Image, the first three terms of (2.23) become

˙qTg(q)˙qTKd˙q+˙qT˜ξ+˙qTg(qd)

Image

Because ˜qTg(qd)=˙qTg(qd)Image and ˜ξ=Ki˜qImage, the first seven terms of (2.23) are

˙qTKd˙q+α˜qT˜ξ+˜qTKi˜q

Image (2.24)

Now we discuss the last term of (2.23). From (2.5), we have

˜qTM˙q=˜qTC˙q+˜qTCT˙q

Image

From (2.1),

˜qTM¨q=˜qTC˙q˜qTg(q)+˜qTKp˜q˜qTKd˙q+˜qT˜ξ+˜qTg(qd)

Image

For the regulation case, ˜qTM˙q=˙qTM˙qImage, using (2.4) and (2.6) the last two terms of (2.23) are

α{˜qTKp˜q˙qTM˙q+˜qTCT˙q+˜qT[g(qd)g(q)]+˜qT˜ξ}α˙qTM˙qα˜qTKp˜q+αkc˜q˙q2+αkg˜q2α˜qT˜ξ

Image (2.25)

From (2.24) and (2.25),

˙V˙qT(KdαMαkc˜q)˙q˜qT(αKpKiαkg)˜q[λm(Kd)αλM(M)αkc˜q]˙q2[αλm(Kp)λM(Ki)αkg]˜q2

Image

If

˜qλM(M)αkc

Image (2.26)

and

λm(Kd)(1+α)λM(M)λm(Kp)1αλM(Ki)+kg

Image (2.27)

then ˙V0Image, ˜qImage decreases. From (2.22), if

λm(Kd)λM(M)+13λm(M)λm(Kp)λm(Kp)13λm(K1i)λm(Kp)λM(Ki)+kg

Image (2.28)

then (2.27) is established. Using (2.21) and λm(K1i)=1λM(Ki)Image, (2.28) is (2.19).

˙VImage is negative semidefinite. Define a ball Σ of radius σ>0Image centered at the origin of the state space, which satisfies these conditions:

Σ={˜q:˜qλM(M)αkc=σ}

Image

˙VImage is negative semidefinite on the ball Σ. There exists a ball Σ of radius σ>0Image centered at the origin of the state space on which ˙V0Image. The origin of the closed-loop equation (2.18) is a stable equilibrium. Since the closed-loop equation is autonomous, we use LaSalle's theorem. Define Ω as

Ω={x(t)=[˜q,˙q,˜ξ]R3n:˙V=0}={˜ξRn:˜q=0Rn,˙q=0Rn}

Image

From (2.23), ˙V=0Image if and only if ˜q=˙q=0Image. For a solution x(t)Image to belong to Ω for all t0Image, it is necessary and sufficient that ˜q=˙q=0Image for all t0Image. Therefore it must also hold that ¨q=0Image for all t0Image. We conclude that from the closed-loop system (2.18), if x(t)ΩImage for all t0Image, then

g(q)=g(qd)=˜ξ+g(qd)˜ξ=0

Image

implies that ˜ξ=0Image for all t0Image. So x(t)=[˜q,˙q,˜ξ]=0R3nImage is the only initial condition in Ω for which x(t)ΩImage for all t0Image.

Finally, we conclude from all this that the origin of the closed-loop system (2.18) is locally asymptotically stable. Because 1αλm(K1i)λm(Kp)Image, the upper bound for ˜qImage can be

˜qλM(M)kcλM(Ki)λm(Kp)

Image

It establishes the semiglobal stability of our controller, in the sense that the domain of attraction can be arbitrarily enlarged with a suitable choice of the gains. Namely, increasing KpImage the basin of attraction will grow. □

Remark 2.1

From above stability analysis, we see the three gain matrices of the linear PID control (2.16) can be chosen directly from the conditions (2.19). The most important contribution of our method is the tuning procedure of the PID parameters can be calculated directly. It is more simple than the tuning procedures in [2,4,71–73,101,117]. No modeling information is needed. This linear PID control is exactly the same as the industrial robot controllers, and is semiglobally asymptotically stable. λM(M)Image can be estimated as [72]

λM(M)β,βn(maxi,j|mij|)

Image

2.2 PID parameters tuning in closed-loop

We use the following three important properties of robot PID control to derive a systematic tuning method:

  1. 1.  In the regulation case, a robot can be stabilized by any PD controller providing their gains are positive big enough.
  2. 2.  The closed-loop behaviors of robot PID control are similar with linear systems.
  3. 3.  The control torque of each joint is independent of the robot dynamics.

The turning steps are shown in Fig. 2.1. Here, PD1Image is a PD controller, PID2Image is the PID controller after parameters tuning, PID3Image is the PID controller after the parameters refining, and PID4Image is the PID controller after stability criterion. The final PID controller is τ.

Image
Figure 2.1 PID tuning scheme.

Since the robot dynamic is not stable in an open loop, it is impossible to send step commands to all joints of the robot to tune PID gains. We use the following closed-loop tuning method.

The PD control (2.14) cannot guarantee zero of the steady-state error. The integrator is the most effective tool to eliminate steady-state error. PD control (2.7) becomes PID control as

τ=Kp˜q+Kit0˜q(τ)dτ+Kdd˜qdt=PID2

Image (2.29)

where KpImage, KiImage, and KdImage are proportional, integral, and derivative gains of the PID controller, respectively. The integrator gain KiImage has to be increased when the steady-state error is big. This causes big overshoot, long settling time, and is less robust. PD1Image is defined in (2.7) as

PD1=Kp(qqd)Kd(qqd)

Image

From (2.15), we know that any PD controller can guarantee stability (bounded) of any robot manipulator in the regulation case. The stability property assures us to find another PID controller for the closed-loop system as in Fig. 2.2A. The total control system is

τ=Kp1(qqd1)Kd1(qqd1)+ˆg(q)qd1=Kp2(qqd)+Kd2(qqd)Kp˜q+Kit0(qqd)dτ

Image (2.30)

Image
Figure 2.2 PID tuning in closed-loop.

However, the controller (2.30) loses the PID form. Another tuning method in the closed-loop is to change PD1 directly; see Fig. 2.2B. Although the closed-loop system is different when PD1 is changed, the stability is always guaranteed with (2.15) with the change of PD1. The introduction of an integrator may destroy the stability, and in the next section we will show how to assure stability with PID control. We use Fig. 2.2B to adjust PID gains such that we can tune the PID controllers one by one.

Since PD/PID control is linear, the change of PD1 is the same as adding another controller PID2 to PD1. From (2.9), we know that the closed-loop system with PD1 is stable. When we apply a PID2 control to the closed-loop system (2.13), it is

M(q)q+C(q,q)q+˜g(q)+f(q)PD1=PID2

Image (2.31)

A gravity compensation to the closed-loop system (2.13) is

M(q)q+C(q,q)q+g(q)+f(q)PD1=ˆg(q)

Image (2.32)

When we apply the PID control and the gravity compensation to the closed-loop system (2.31), it is

M(q)q+C(q,q)q+g(q)+f(q)PD1=PID2+ˆg(q)

Image (2.33)

The total control torque to the robot is

τ=PID2+PD1+ˆg(q)

Image (2.34)

From (2.31) to (2.34), we see that the control torque to the robot manipulator is linearly independent of the robot dynamic (2.1). In the general case, if we tune PID controllers m times, they can be expressed as

M(q)¨q+C(q,˙q)˙q+g(q)+f(q)=mj=1PIDj+ˆg(q)

Image (2.35)

where

mj=1PIDj=mj=1Kp,j˜q+mj=1Ki,jt0˜q(τ)dτ+mj=1Kd,jd˜qdt

Image

PD1 is a special PID with Ki=0Image. This property allows us to start a PID control with small gains such that the closed-loop system is stable. Then any other tuning rule can be applied to obtain new PID gains one by one. The final PID gains are the summation of all these controllers (gains).

2.2.1 Linearization of the closed-loop system

Although the robot dynamics are strong nonlinear, the behaviors of the closed-loop system with PD/PID control are similar with the transient responses of a linear system. On the other hand, after PID control, each joint of the robot can be characterized as a single input–single output (SISO) system.

Several methods can be used to linearize the robot models. If the velocity and gravity are neglected, the terms C(q,˙q)˙qImage and g(q)Image in the nonlinear dynamics (2.1) are zero. The resulting system is a linear model [45]:

M(q)¨q=u

Image (2.36)

Obviously, it is an oversimplified model. Since the velocity dependent term C(q,˙q)˙qImage representing Coriolis-centrifugal forces, it is negligible for small joint velocities. A rate linearization scheme can be used as [44]

A¨q+Bq=u

Image (2.37)

where A=M(q)|q=q0Image, B=g(q)q|q=q0Image, q0Image is an operating point. Many experiments show that even at low speeds, C(q,˙q)Image is not zero [127].

The velocity and gravity are main control issues of robots, and they are dominant components of the dynamics. When the robot model is completely known, Taylor series expansion can be applied [89]. At the operating point q0Image the nonlinear model (2.1) can be approximated by

A¨q+D˙q+Bq=τ

Image (2.38)

where A=M(q)|q=q0Image, B=[g(q)+C(q,˙q)]q|q=q0Image, D=C(q,˙q)˙q|q=q0Image.

We use this identification-based linearization method. For each joint, the typical linear model is a first-order system with transportation delay as

Gp=Km1+Tmsetms

Image (2.39)

The response is characterized by three parameters: the plant gain KmImage, the delay time tmImage, and the time constant TmImage. These are found by drawing a tangent to the step response at its point of inflection and noting its intersections with the time axis and the steady state value.

Sometimes the first-order (2.39) model cannot describe the complete nonlinear dynamic of the robot. A reasonable linear model of the robot is a Taylor series model as in (2.38). The model can be written in the frequency domain:

qi(s)τi(s)=KmT2ms2+2ξmTms+1etms

Image (2.40)

or

qi(s)τi(s)=Km(1+Tm1s)(1+Tm2s)etms

Image

The responses of this second-order model are similar with mechanical motions. If there exists a big overshoot a negative zero is added in (2.40)

qi(s)τi(s)=Km(1+Tm3s)(1+Tm1s)(1+Tm2s)etms

Image (2.41)

The normal input signals for the PID tuning are step and repeat inputs.

2.2.2 PD/PID tuning

Because the robot can be approximated by a linear system, some tuning rules for linear systems can be applied for the closed-loop system tuning. We first give PD tuning rules. When each joint can be approximated by a first-order system,

Gp=Km1+Tmsetms

Image

Here, KmImage, TmImage, and tmImage are obtained from Fig. 2.3.

Image
Figure 2.3 Step response of a linear system.

The linear PID law in time domain (2.29) can be transformed into the frequency domain:

τ(s)=Kc(1+1Tis+Tds)E(s)=Gc(s)E(s)=PID2

Image

Similar with Ziegler–Nichols [161] and Cohen–Coon [20] tuning methods, we use a heuristic method to tune a PID controller. For PD control, our tuning law is shown in Table 2.1. Here, we use the similar tuning formulas with Ziegler–Nichols. By several experiments, we found a=1Image is good.

Table 2.1

Ziegler–Nichols and Cohen–Coon methods for PI/PD

Kc Image Ti Image Td Image
Ziegler–Nichols tuning aTmKmτm Image 0.5τm
Cohen–Coon method TmKmτm(43+τm4Tm) Image 4Tmτm11Tm+2τm Image
Our Method Tm2Km Image T m1

Image

If each joint is approximated by a second-order system,

qi(s)ui(s)=KmT2ms2+2ξmTms+1

Image

The PD gains are tuned similarly with [58] and [24]; see Table 2.2.

Table 2.2

PD tuning for the second-order model

Kc Image Ti Image Td Image
Method 1 [58] 5Tm1ξmKmTm3 Image Tm1+0.1ξm0.8Tm1ξm Image
Method 2 [24] Tm2Km Image T m1
Our Method Tm2Km Image T m1

Image

When PD control cannot provide good performances, PID control should be used. The PID gains for the first-order model is decided by Table 2.3.

Table 2.3

PID tuning for the first-order model

Kc Image Ti Image Td Image
Ziegler–Nichols tuning aTmKmτmImage, 2τm 0.5τm
Cohen–Coon method TmKmτmτm4Tm Image τm(32Tm+6τm)13Tm+8τm Image 4Tmτm11Tm+2τm Image
Our Method Tm2Km Image T m2 T m1

Image

Here, Kc=KpImage is a proportional gain, Ti=KcKiImage is a time constant, and Td=KdKcImage is a derivative time constant.

The PID gains for the second-order model is decided by Table 2.4.

Table 2.4

PID tuning for the second-order model

Kc Image Ti Image Td Image
Method 1 5Tm1ξmKmTm3 Image 2Tm1ξm Tm1+0.1ξm0.8Tm1ξm Image
Method 2 Tm2Km Image T m2 T m1
Our Method 20ξmTmKm Image 15ξmTm T2m10 Image

Image

2.2.3 Refine PID gains

From (2.35), we see the PID gains are linear independent, and we can modify them directly. The refinement of PID2 is the same as adding a new PID controller, PID3, into (2.34). We use Table 2.5 to refine PID gains.

Table 2.5

Refined PID (PID3)

Rise Overshoot Settling Steady Error Stability
Kp Decrease Increase Small Increase Decrease Degrade
Ki Small Decrease Increase Increase Large Decrease Degrade
Kd Small Decrease Decrease Increase Minor Decrease Improve

Image

After we refine the process, the robot control is

τ=PD1+PID2+PID3+ˆg(q)

Image (2.42)

In order to decrease the steady-state error, we should increase KiImage. In order to get less settling time, we should decrease KdImage. In order to get less overshoot, we should decrease KpImage. However, the above tuning process does not guarantee stability of the closed-loop system. In the next subsection, we will give the bounds of the PID gains to assure PID control is stable.

2.2.4 Stability conditions for PID gains

For the robot dynamic controlled by the PID controller (2.35), the closed-loop system (2.18) is semiglobally asymptotically stable at the equilibrium x=[ξg(qd),˜q,˜q]T=0Image, provided that control gains satisfy (2.19). The three gain matrices of the linear PID control (2.35) can be chosen directly from the conditions (2.19). From (2.35), we know that the PID control with gravity compensation (2.42) is

τ=3j=1PIDj+ˆg(q)=PIDf+ˆg(q)

Image

Now we apply the condition (2.19) to PIDfImage. If the gains of PIDfImage are not in the bound of (2.19), we add a new PID controller, PID4Image, such that the gains of PIDf+PID4Image are in the bounds of (2.19). The final control torque to the robot is

τ=PD1+PID2+PID3+PID4+ˆg(q)

Image

Table 2.6 gives a comparative analysis of the proposed method with other PID tuning methods.

Table 2.6

Comparison of the PID tuning method

PID tuning method system model stability systematic adaptive
Our Method linear/nonlinear no yes yes no

Ziegler–Nichols [161]

Cohen–Coon [20]

linear no no yes no
Model based [24,58] linear/nonlinear yes no no yes
Lyapunov method [21,22] nonlinear no yes no no
Frequency domain linear no no yes no
Optimization method [81] linear yes no no no
Adaptive tuning [143] linear yes no no yes
Intelligent method [85,129] linear/nonlinear no no no yes
Impedance method [21,56] robot yes no no no

Image

Here, we compare our method with the other eight PID tuning algorithms in six properties. It can be seen that apart from adaptive ability, our method is better than the others for robot control.

2.3 Application to an exoskeleton

The upper limb exoskeleton robot in UC-Santa Cruz is shown in Fig. 2.4. It has 7-DoF (degrees-of-freedom) as in Fig. 2.5. The computer control platform of this exoskeleton robot is a PC104 with an Intel [email protected] GHz processor and 512 Mb RAM. The motors for the first four joints are mounted in the base such that the large mass of the motors can be removed. Torque transmission from the motors to the joints is achieved using a cable system. The other three small motors are mounted in link five.

Image
Figure 2.4 The UCSC 7-DoF exoskeleton robot.
Image
Figure 2.5 Model of the 7-DoF exoskeleton robot.

The real-time control program operated in Windows XP with Matlab 7.1, Windows Real-Time Target and C++. All of the controllers employed a sampling frequency of 1 kHz. The properties of the exoskeleton with respect to base frame are shown in Table 2.7.

Table 2.7

Parameters of the exoskeleton

Joint Mass (kg) Center (m) Length (m)
1 3.4 0.3 0.7
2 1.7 0.05 0.1
3 0.7 0.1 0.2
4 1.2 0.02 0.05
5 1.8 0.02 0.05
6 0.2 0.04 0.1
7 0.5 0.02 0.05

Image

We first use the following PD1 to stabilize the robot:

Kp1=diag[150,150,100,150,100,100,100]Kd1=diag[330,330,300,320,320,300,300]

Image (2.43)

The joint velocities are estimated by the standard filters:

˜˙q(s)=bss+aq(s)=18ss+30q(s)

Image

Here, the main weight of the exoskeleton is in the first four joints. The potential energy is

U=m1gl1s1+m2g(l1s1+c2l2s1)+m3ga3s1s2+m4g[a4c4(c1s3+c2c3s1)+a4s4(c1c3c2s1s3)+a3s1s2]

Image

The gravity compensation in (2.18) is calculated by

ˆg=qU(q)

Image

Then we use the step responses of linear systems to approximate the closed-loop responses of the robot via PD1. The step responses of the closed-loop systems of the robot and the linear systems are shown in Fig. 2.6, where in the dash lines are the step responses of the following second-order linear systems:

G1=0.9360s2+9s+1,G2=120s2+3s+1G3=0.95.5s2+4s+1,G4=0.8530s2+8s+1

Image (2.44)

Image
Figure 2.6 The step responses of the closed-loop systems.

In order to tuning the gains of the PID (2.29), this PID is rewritten as

PIDt=Kc(˜q+1Tit0˜q(τ)dτ+Td˜q)

Image

where Kc=KpImage is proportional gain, Ti=KcKiImage is integral time constant, and Td=KdKcImage is derivative time constant. We use the following tuning rule:

Kc=20ξmTmKm,Ti=15ξmTm,Td=T2m10

Image (2.45)

to tune the PID parameters. This rule is similar with [58] and [24], in their case Kc=5Tm1ξmKmTm3Image, Ti=2Tm1ξmImage, Td=Tm1+0.1ξm0.8Tm1ξmImage. It is different with the other two famous rules, Ziegler–Nichols and Cohen–Coon methods, where Kc=aTmKmτmImage, Ti=2τmImage, Td=0.5τmImage or Kc=TmKmτm(43+τm4Tm)Image, Ti=τm(32Tm+6τm)13Tm+8τmImage, Td=4Tmτm11Tm+2τmImage. Because their rules are suitable for the process control, our rule is for mechanical systems. By the rule (2.45) the PID2 are

Kp2=diag[90,30,40,90,10,150,10]Ki2=diag[1,2,20,1.5,3,1,2]Kd2=diag[500,410,350,400,50,30,400]

Image (2.46)

The control torque becomes u=PID1+ˆg(q)+PID2Image. The control results of Joint 1 are shown in Fig. 2.7.

Image
Figure 2.7 PID tuning process of Joint 1.

After this refine turning, PID3 is

Kp3=diag[5,4,5,6,3,4,2]Ki3=diag[32,28,21,25,21,21,22]Kd3=diag[5,4,4,10,6,10,10]

Image (2.47)

The final control is

PIDf=PD1+ˆg(q)+PID2+PID3

Image (2.48)

The stability condition (2.19) gives a sufficient condition for the minimal values of proportional and derivative gains and maximal values of integral gains. We find that the final control (2.48) satisfies the conditions (2.19). The final control results for Joint 3 and Joint 7 are shown in Fig. 2.8.

Image
Figure 2.8 PID control for Joint 3 and Joint 7.

2.4 Conclusions

In this chapter the linear PID control for a class of exoskeleton robots is addressed. The conditions of the semiglobal asymptotic stability is very simple, and the linear PID control is exactly the same as the industrial controller. The systematic tuning method for PID control is proposed. This method can be applied to any robot manipulator. By using several properties of robot manipulators, the tuning process becomes simple and is easily applied in real applications. Some concepts for PID tuning are novel, such as step responses for the closed-loop systems under any PD control, and the joint torque is separated into several independent PID. We finally apply this method on an upper limb exoskeleton. Real experiment results give validation of our PID tuning method.

Bibliography

[2] J. Alvarez-Ramirez, R. Kelly, I. Cervantes, Semiglobal stability of saturated linear PID control for robot manipulators, Automatica 2003;39:989–995.

[4] S. Arimoto, Fundamental problems of robot control: part I, innovations in the realm of robot servo-loops, Robotica 1995;13(1):19–27.

[20] G.H. Cohen, G.A. Coon, Theoretical consideration of retarded control, Trans. Am. Soc. Mech. Eng. 1953;75:827–834.

[21] P.H. Chang, J.H. Jung, A systematic method for gain selection of robust PID control for nonlinear plants of second-order controller canonical form, IEEE Trans. Control Syst. Technol. 2009;17(2):473–483.

[22] C.-Y. Chang, Adaptive fuzzy controller of the overhead cranes with nonlinear disturbance, IEEE Trans. Ind. Inform. 2007;3(2):164–172.

[24] I.L. Chien, P.S. Fruehauf, Consider IMC tuning to improve controller performance, Chem. Eng. Prog. 2002:33–41.

[44] D.F. Golla, S.C. Garg, P.C. Hughes, Linear state-feedback control of manipulators, Mech. Mach. Theory 1981;16:93–103.

[45] A.A. Goldenberg, A. Bazerghi, Synthesis of robot control for assembly processes, Mech. Mach. Theory 1986;21(1):43–62.

[54] D. Hernandez, W. Yu, M.A. Moreno, Neural PD control with second-order sliding mode compensation for robot manipulators, 2011 International Joint Conference on Neural Networks, IJCNN'11. San Jose, USA. 2011:2395–2402.

[56] N. Hogan, Skeletal muscle impedance in the control of motor actions, J. Mech. Med. Biol. 2002;2(3):359–373.

[58] H.P. Huang, J.C. Jeng, K.Y. Luo, Auto-tune system using single-run relay feedback test and model-based controller design, J. Process Control 2005;15:713–727.

[63] E.M. Jafarov, M.N.A. Parlakçı, Y. Istefanopulos, A new variable structure PID-controller design for robot manipulators, IEEE Trans. Control Syst. Technol. 2005;13(1):122–130.

[71] R. Kelly, Global positioning of robot manipulators via PD control plus a class of nonlinear integral actions, IEEE Trans. Autom. Control 1998;43(7):934–938.

[72] R. Kelly, V. Santibáñez, L. Perez, Control of Robot Manipulators in Joint Space. London: Springer-Verlag; 2005.

[73] R. Kelly, A tuning procedure for stable PID control of robot manipulators, Robotica 1995;13:141–148.

[81] B. Kristiansson, B. Lennartsson, Robust and optimal tuning of PI and PID controllers, IEE Proc., Control Theory Appl. 2002;149(1):17–25.

[85] F.L. Lewis, K. Liu, A. Yesildirek, Neural net robot controller with guaranteed tracking performance, IEEE Trans. Neural Netw. 1995;6(3):703–715.

[89] C.J. Li, An efficient method for linearization of dynamic models of robot manipulators, IEEE Trans. Robot. Autom. 1989;5(4):397–408.

[101] E.V.L. Nunes, L. Hsu, F. Lizarralde, Arbitrarily small damping allows global output feedback tracking of a class of Euler–Lagrange systems, 2008 American Control Conference. Seattle, USA. 2008:378–382.

[117] P. Rocco, Stability of PID control for industrial robot arms, IEEE Trans. Robot. Autom. 1996;12(4):606–614.

[127] A. Swarup, M. Gopal, Comparative study on linearized robot models, J. Intell. Robot. Syst. 1993;7(3):287–297.

[129] Y.L. Sun, M.J. Er, Hybrid fuzzy control of robotics systems, IEEE Trans. Fuzzy Syst. 2004;12(6):755–765.

[131] M.W. Spong, M. Vidyasagar, Robot Dynamics and Control. Canada: John Wiley & Sons Inc.; 1989.

[137] W. Truccolo, G.M. Friehs, J.P. Donoghue, L.R. Hochberg, Primary motor cortex tuning to intended movement kinematics in humans with tetraplegia, J. Neurosci. 2008;28(5):1163–1178.

[143] Q.G. Wang, Y. Zhang, X. Guo, Robust closed-loop identification with application to auto-tuning, J. Process Control 2001;11:519–530.

[159] A.S. Poznyak, E.N. Sanchez, W. Yu, Differential Neural Networks for Robust Nonlinear Control - Identification, State Estimation and Trajectory Tracking. Singapore: World Scientific Publishing Co.; 2001.

[161] J.G. Ziegler, N.B. Nichols, Optimum settings for automatic controllers, Trans. Am. Soc. Mech. Eng. 1942;64:759–768.

..................Content has been hidden....................

You can't read the all page of ebook, please click here login for view all page.
Reset
3.141.199.243