Chapter 9

PID Admittance Control in Joint Space

Abstract

Normal impedance/admittance needs robot models. The model for the exoskeleton includes forward kinematic, inverse kinematic, and dynamic models. The kinematics are used to calculate the relation between the joint angles and the arm position, while the dynamic model is applied to design controllers. It is impossible to design a model-based impedance/admittance control when a complete dynamic model of the robot is unknown [154].

When the admittance control is in joint space, it requires inverse kinematics of the robot. In this chapter, the admittance control is modified to only use the orientations of the end-effector to generate the desired joint angles to avoid inverse kinematics. The classic PD control is also modified with adaptive compensation and sliding mode compensation. The stability of these two PD controllers are proven. Real time experiments are presented for with a 2-DoF pan and tilt robot and a 4-DoF exoskeleton. The experiment results show the effectiveness of the proposed controllers.

Keywords

PID control; Admittance control; Joint space

9.1 PD admittance control

The dynamics of a n-link robot is

M ( q ) q ¨ + C ( q , q ˙ ) q ˙ + G ( q ) = u J T ( q ) f e

Image (9.1)

where qRnImage represents the link positions. M(q)Rn×nImage is the inertia matrix, C(q,q˙)Rn×nImage represents centrifugal and Coriolis matrix, G(q)RnImage is vector of gravitational torques, uRnImage denotes the joint driving torque, J(q)Rm×nImage is the Jacobian matrix, feRmImage represents the contact force and torque in the end-effector.

When the robot dynamic (9.1) is known, the traditional admittance control is

u = M ( q ) J 1 ( u i J ˙ q ˙ ) + C ( q , q ˙ ) q ˙ + G ( q ) + J T ( q ) f e u i = x ¨ r K v ( x ˙ x ˙ r ) K p ( x x r )

Image (9.2)

where Kp,KvRm×mImage denote the gains of the proportional and derivative (PD) controller.

For the human–robot cooperation, we assume the end-effector of the robot does not have contact with the environment, fe=0Image. This traditional admittance controller enhances robustness against the modeling error by using an inner position loop. However, the inner loop dynamics hinder accurate realization of desired admittance dynamics.

Since xrImage is the desired reference in the task space, it should be transformed into joint space as the desired angles qrImage:

x ˙ r = J ( q ) q ˙ r , q ˙ r = J 1 ( q ) x ˙ r q r = i n v k ( x r )

Image (9.3)

where invk()Image is the inverse kinematic of the robot (9.1).

We apply the output of the forces/torques sensor to the admittance model, and generate desired angles in joint space:

Image (9.4)

1-DoF robot

We can use one force to move any Cartesian position without the inverse kinematics. For more than one DoF, the relation between different forces are coupled, then the inverse kinematics are needed.

We propose a simplified admittance control, which does not need invk()Image. The basic idea is that we establish the relation between the orientation of the robot and the force/torque. We use the torques instead of the forces, because the orientation is a linear combination of the joint angles.

The orientations are practically decoupled in most of the cases. Even the orientations are coupled, we show in the following that the orientations are linear combinations of the robot joint angles.

2-DoF robot

A typical 2-DoF robot is the pan and tilt robot shown in Fig. 9.1. A six-axis force and torque sensor is used by the operator outside the manipulator. It measures the full six components of force and torque: vertical, lateral, and longitudinal forces as well as camber, steer, and torque movements. For the 2-DoF robot, we only use two of them.

Image
Figure 9.1 2-DoF pan and tilt robot.

To simplify the model, we assume that the links are thin and symmetric bars. Therefore the center of mass of each link is in its center. The orientations of the robot are defined as α, β, and γ, and they can be calculated directly from geometrical property:

α = π 2 β = q 2 γ = q 1

Image (9.5)

So the orientation of the robot is completely defined by the joint angles of the robot. The admittance control (9.2) generates three orientations and three positions in the task space. Two orientations in (9.5) can generate two desired angles on the robot in the joint space.

The Jacobian for the 2-DoF robot only includes the orientational components as

J ω = [ 0 sin ( q 1 ) 0 cos ( q 1 ) 1 0 ]

Image (9.6)

One advantage of (9.6) is that we do not need the kinematics of the robot.

4-DoF robot

A typical 4-DoF robot is shown in Fig. 9.2. As the pan and tilt robot, the links are also assumed to be thin and symmetric. The orientation of the robot is:

α = π 2 q 3 β = q 2 q 4 γ = q 1

Image (9.7)

The orientation in (9.7) has a linear combination of the robot joints at the β orientation. We cannot use only the angular component in the Jacobian JωImage, because the determinant would be zero. To avoid the singularity, we divided the orientation β in two terms:

β q 2 = q 2 β q 4 = q 4 β = β q 2 + β q 4

Image

Because the torques can form the joint positions, we can use both torque and force at the Y direction to generate βq2Image and βq4Image. This consideration is possible because the joint number is less than the Cartesian DoF, and there are still force components that can be used.

Image
Figure 9.2 4-DoF robot.

The force/torque transformation to joint position are

τ x α q 3 = π 2 α τ y β q 2 q 2 = β q 2 F y β q 4 q 4 = β q 4 τ z γ q 1 = γ

Image (9.8)

It is a one-to-one mapping from the force/torque to joint angles.

5-DoF robot

The orientation for a 5-DoF robot is:

α = π 2 q 3 β = q 2 q 4 γ = q 1 + q 5

Image (9.9)

Now the γ orientation has a linear combination.

Because the DoF of the robot n and the DoF of the force/torque sensor m satisfy

n < m

Image (9.10)

we can separate the orientations in two terms and use the force components to calculate one of them:

τ x α q 3 = π 2 α τ y β q 2 q 2 = β q 2 F y β q 4 q 4 = β q 4 τ z γ q 1 q 1 = γ q 1 F z γ q 5 q 5 = γ q 5

Image (9.11)

6-DoF robot

For a 6-DoF robot, n=mImage, the orientations are

α = π 2 q 3 q 6 β = q 2 q 4 γ = q 1 + q 5

Image (9.12)

All orientations have linear combinations of the joint angles. It is still possible to divide them in two terms, and use the force components as

τ x α q 3 q 3 = π 2 α q 3 F x α q 6 q 6 = α q 6 τ y β q 2 q 2 = β q 2 F y β q 4 q 4 = β q 4 τ z γ q 1 q 1 = γ q 1 F z γ q 5 q 5 = γ q 5

Image (9.13)

Since α orientation has a constant value, we can establish the division for it. The desired reference angles are qr=[q1,,q6]TImage.

Generally, the orientations of 2-DoF robot are defined by each joint of the robot, and we can apply the torques in certain directions directly. For more than three DoF robots, the orientations of the robot are defined by multiple joints. If the DoF of the robot is less than the DoF of the force/torque sensor, we can divide the force and torque components into the orientations. If the robot is redundant, i.e., n>6Image, m=6Image, we have to make certain assumptions in joint movement, such as limiting the range of motion or fix the joint.

9.2 PD admittance control with adaptive compensations

After the desired reference angle qrImage is obtained from the admittance control, we use PD control with compensations to control each joint. We define the tracking nominal error, Ω, as follows:

Ω = Λ ( q q r ) ( q ˙ q ˙ r ) = Λ q s q ˙ s

Image (9.14)

where ΛRn×nImage denote the partial-proportional matrix gain. When fe=0Image, the robot dynamics (9.1) can be linearly parameterized as

M ( q ) q ¨ + C ( q , q ˙ ) q ˙ + G ( q ) = Y Θ

Image

where Y=Y(q,q˙,q¨)Rn×pImage is a regressor composed of known nonlinear functions, and ΘRpImage is a vector which represents unknown but constant parameters.

The dynamics parametrization can be written in terms of a nominal reference q˙sImage and its derivative q¨sImage, as follows:

M ( q ) q ¨ s + C ( q , q ˙ ) q ˙ s + G ( q ) = Y s Θ

Image (9.15)

where Ys=Y(q,q˙,q˙s,q¨s)Rn×pImage is the regressor in terms of the nominal reference q˙sImage.

The following properties will be used to prove stability:

1) The inertia matrix M(q)Image is symmetric positive definite, and there exists a number β1>0Image such that

0 < λ m { M ( q ) } M ( q ) λ M { M ( q ) } β 1

Image (9.16)

where λM{A}Image and λm{A}Image are the maximum and minimum eigenvalues of the matrix A. The norm A=λM(ATA)Image stands for the induced Frobenius norm.

2) For the centripetal and Coriolis matrix C(q,q˙)Image, there exists a number β2>0Image such that

C ( q , q ˙ ) β 2 q ˙

Image (9.17)

and M˙(q)2C(q,q˙)Image is skew-symmetric, i.e.,

q ˙ T [ M ˙ ( q ) 2 C ( q , q ˙ ) ] q ˙ = 0

Image

The norm bImage of the vector bRnImage stands for the vector Euclidean norm.

3) For the gravitational torques vector G(q)Image, there exists a number β3>0Image such that

G ( q ) β 3

Image (9.18)

4) For the Jacobian J(q),J1(q)Image, and the time derivative of the Jacobian J˙(q)Image, there exist numbers ρiImage (i=0,1,2Image) such that

J ( q ) λ M { J ( q ) } ρ 0 J 1 ( q ) λ M { J 1 ( q ) } ρ 1 J ˙ ( q ) λ M { J ˙ ( q ) } ρ 2

Image (9.19)

When M, C, and G are unknown, (9.15) can be written in the adaptive form:

M ˆ ( q ) q ¨ s + C ˆ ( q , q ˙ ) q ˙ s + G ˆ ( q ) = Y s Θ ˆ

Image (9.20)

where Mˆ,Cˆ,G,ˆImage and ΘˆImage are estimates of M,C,GImage, and Θ, respectively.

We use the following PD control with adaptive compensation for each joint control:

u = K s Ω + Y s Θ ˆ = K s Λ q s + K s q ˙ s + Y s Θ ˆ

Image (9.21)

where KsRn×nImage denote the matrix gain of the controller.

The closed-loop system with the controller (9.21) is

M ( q ) Ω ˙ + [ C ( q , q ˙ ) + K s ] Ω = Y s Θ ˜

Image (9.22)

The product of the regressor YsImage with the parameter error vector Θ˜Image is

M ˜ ( q ) q ¨ s + C ˜ ( q , q ˙ ) q ˙ s + G ˜ ( q ) = Y s Θ ˜

Image (9.23)

where M˜=MˆM,C˜=CˆC,G˜=GˆGImage, and Θ˜=ΘˆΘImage.

Since the PD controller KsΩImage can cancel the uncertainties of M(q)Image and C(q,q˙)Image, we only estimate the gravitational torque vector G(q)Image, then the closed-loop system (9.22) becomes

u = K s Ω + Y s 1 Θ ˆ s 1 M ( q ) Ω ˙ + ( C ( q , q ˙ ) + K s ) Ω = Y s 1 Θ ˜ s 1 Y s 2 Θ s 2

Image (9.24)

Here, the product of the regressor is divided in two terms, the first term Ys1Θ˜s1=Ys1(q)Θ˜s1=G˜(q)Image corresponds to the gravity torque vector estimation, the second term Ys2Θs2=Ys2(q,q˙,q˙s,q¨s)Θs2=M(q)q¨s+C(q,q˙)q˙sImage corresponds to the inertia and Coriolis matrices, Θ=Θs1+Θs2Image, Ys=Ys1+Ys2Image.

Theorem 9.1

Consider the robot dynamic (9.1) with fe=0Image, controlled by (9.21), if KsImage satisfies the following condition:

λ m ( K s ) k ¯

Image (9.25)

where λm(Ks)Image is the minimum eigenvalue of KsImage, k¯Image is the estimated upper bound of Ys2Θs2Image, and the parameters are updated as

Θ ˜ ˙ s 1 = K Θ 1 Y s 1 T Ω

Image (9.26)

then the closed-loop system is semiglobally asymptotically stable.

Proof

We proposed the following Lyapunov function:

V ( Ω , Θ ˜ s 1 ) = 1 2 Ω T M ( q ) Ω + 1 2 Θ ˜ s 1 T K Θ Θ ˜ s 1

Image (9.27)

The first term corresponds to the kinetic energy of the closed-loop system, the second term is the adaptive term and KΘRp×pImage denote its matrix gain. Taking the time derivative of (9.27) along (9.24), gives rise to

V ˙ = Ω T M ( q ) Ω ˙ + 1 2 Ω T M ˙ ( q ) Ω + Θ ˜ s 1 K Θ Θ ˜ ˙ s 1 = Ω T K s Ω + Θ ˜ s 1 T ( K Θ Θ ˜ ˙ s 1 + Y s 1 T Ω ) Ω T Y s 2 Θ s 2

Image (9.28)

From (9.28) if the adaptation law is (9.26) the time derivative of V reduces to

V ˙ = Ω T K s Ω Ω T Y s 2 Θ s 2 λ m ( K s ) Ω 2 + Ω Y s 2 Θ s 2

Image

Using the properties (9.16), (9.17), and (9.19) on Ys2Θs2Image becomes

Y s 2 Θ s 2 M ( q ) q ¨ s + C ( q , q ˙ ) q ˙ s χ ( t )

Image

where χ(t)=f(q¨s,q˙s,q˙,βi,ρi)Image is a state dependent function. Therefore V˙Image is

V ˙ λ m ( K s ) Ω 2 + Ω χ ( t )

Image (9.29)

That implies that there exists a large enough gain KsImage such that λm(Ks)χ(t)Image and the nominal error converges into a set-bounded μχ(t)λm(Ks)Image as tImage; and by the Barbalat lemma the time derivative of the vector parameters error Θ˜˙s1Image converge into a set-bounded ϵ when ΩμImage as tImage.  □

9.3 PD admittance control with sliding mode compensations

The PD control with adaptive compensation (9.21) is still complex. Now we use a more simple compensator, sliding mode control, to compensate the PD control. The PD control with sliding mode compensation for each joint control is

u = K s Ω = K s ( q ˙ q ˙ s ) q ˙ s = q ˙ r Λ ( q q r ) ξ ξ ˙ = K m s g n [ Λ ( q q r ) + ( q ˙ q ˙ r ) ]

Image (9.30)

where KmRn×nImage is the sliding mode matrix gain, sgn(x)=[sgn(x1),sgn(x2),...,sgn(xn)]TImage. It is the second-order sliding mode.

The robot dynamics (9.1) with the controller (9.30) gives the closed-loop system as

M ( q ) Ω ˙ + ( C ( q , q ˙ ) + K s ) Ω = Y s Θ

Image

Theorem 9.2

Consider the robot dynamic (9.1) with fe=0Image, controlled by (9.30), if KsImage satisfy the following condition:

λ m ( K s ) k ¯

Image

k¯Image is the estimated upper bound of YsΘImage, then the closed-loop system is semiglobally asymptotically stable.

Proof

We proposed the following Lyapunov function:

V ( Ω ) = 1 2 Ω T M ( q ) Ω

Image (9.31)

Taking the time derivative of (9.31) gives rise to

V ˙ = Ω T M ( q ) Ω ˙ + 1 2 Ω T M ˙ ( q ) Ω = Ω T K s Ω Ω T Y s Θ λ m ( K s ) Ω 2 + Ω Y s Θ

Image

Using the properties (9.16) and (9.19) on YsΘImage become

Y s Θ M ( q ) q ¨ s + C ( q , q ˙ ) q ˙ s + G ( q ) υ ( t )

Image

where υ is a state dependent function bigger than χ in the adaptive compensation Therefore V˙Image is

V ˙ λ m ( K s ) Ω 2 + Ω υ ( t )

Image (9.32)

That implies that there exists a large enough gain KsImage such that λm(Ks)υ(t)Image and the nominal error converges into a set-bounded νυ(t)λm(Ks)Image as tImage. □

9.4 PID admittance control

The PID control structure is similar as the previous controller. The control law is

τ = J T ( q ) F K s J 1 ( q ) ( Δ q ˙ + Λ Δ q + Ψ 0 t Δ q d σ )

Image (9.33)

The closed-loop system of the model (9.24) under the control law (9.33) is

M ( q ) Ω ˙ + ( C ( q , q ˙ ) + K s ) Ω = Y s ( q , q ˙ , q ˙ s , q ¨ s ) Θ

Image (9.34)

The regressor is bounded by

Y s ( q , q ˙ , q ˙ s , q ¨ s ) Θ M ( q ) q ¨ s + C ( q , q ˙ ) q ˙ s + G ( q ) β 1 ρ 2 { x ¨ s + ρ 1 ρ 2 x ˙ s } + β 2 ρ 2 q ˙ x ˙ s + β 3 χ ( t )

Image (9.35)

Let us consider the following Lyapunov function candidate:

V ( Ω ) = 1 2 Ω T M ( q ) Ω

Image

that corresponds to the kinetic energy of the manipulator in closed loop. The time derivative of V along of (9.34) is

V ˙ = Ω T M ( q ) Ω ˙ + 1 2 Ω T M ˙ ( q ) Ω = Ω T ( Y s ( q , q ˙ , q ˙ s , q ¨ s ) Θ + ( C ( q , q ˙ ) + K s 1 2 M ˙ ( q ) ) Ω )

Image

Using dynamics properties, the above expression reduces to

V ˙ = Ω T K s Ω Ω T Y s ( q , q ˙ , q ¨ s , q ¨ s ) Θ

Image (9.36)

Using (9.35) in (9.36),

V ˙ λ m ( K s ) Ω 2 + Ω χ ( t )

Image

In order for V˙Image to be negative definite, it needs

Ω χ ( t ) λ m ( K s ) μ

Image

that indicates that there exists a big enough KsImage such that Ksχ(t)Image. Even more, we have the following:

1 2 λ m ( M ( q ) ) Ω 2 V ( Ω ) 1 2 λ M ( M ( q ) ) Ω 2

Image

it is defined φ1(r)=12λm(M(q))r2Image and φ2(r)=12λM(M(q))r2Image. The ultimate bound is

b = φ 1 1 ( φ 2 ( μ ) ) = χ ( t ) λ m ( K s ) λ M ( M ( q ) ) λ m ( M ( q ) ) χ ( t ) λ m ( K s ) β 1 β 0

Image

that implies that Ω is bounded by

χ ( t ) λ m ( K s ) Ω χ ( t ) λ m ( K s ) β 1 β 0

Image

Finally, we can conclude that the solutions of Ω are ultimately uniformly bounded. If it is considered that we have a big enough gain KsImage such that Ksχ(t)Image, V˙Image can be written as

V ˙ λ m ( K s ) Ω 2

Image

As in the previous controller, the nominal error ΩL2Image and ΩLImage because it is bounded and does not grow over the time. From (9.34), it is observed that

Ω ˙ = M 1 ( q ) L ( Y s ( q , q ˙ , q ˙ s , q ¨ s ) Θ L ( C ( q , q ˙ ) L + K s L ) Ω L )

Image

that implies Ω˙LImage and, therefore, from Barbalat's lemma, Ω converges into a ball of radio μ when tImage.

Consider the following Cartesian nominal reference:

q ˙ s = q ˙ r Λ Δ q ξ ξ ˙ = Ψ s g n [ ( S x ) ] S x = Δ q ˙ + Λ Δ q

Image

SxImage is the sliding surface that depends on the Cartesian error and its derivative.

The function sgn[x]=[sgn[x1]sgn[x2]sgn[xn]]TImage corresponds to the discontinuous function sign of xRnImage. The control law is given by

τ = J T ( q ) F K s J 1 ( q ) ( Δ q ˙ + Λ Δ q + Ψ 0 t s g n [ ( Δ q ˙ + Λ Δ q ) ] d σ )

Image

The Cartesian nominal reference is bounded by

q ˙ s q ˙ r + λ M ( Λ ) Δ q + ξ q ¨ s q ¨ r + λ M ( Λ ) Δ q ˙ + λ M ( Ψ )

Image

The system in closed-loop and its stability analysis is the same as the PID admittance control of the previous section.

9.5 Experimental results

We use two robots to test our stable PD admittance control. The 2-DoF pan and tilt robot shown in Fig. 9.1. The force/torque (F/T) sensor is the 6-DoF Schunk®. Another robot is a 4-DoF exoskeleton robot; see Fig. 9.2. The real time control environment is Simulink and Matlab 2012. The communication is the CAN protocol, which enables the PC to communicate with the actuators and the F/T sensor.

9.5.1 Pan and tilt robot

The parameters of the PD control are given in Table 9.1. Here, diag{val}r×rImage denotes a diagonal matrix of r×rImage with diagonal values val. (See also Figs. 9.39.6.)

Table 9.1

The parameters of PD control

Gain Classic PD Adaptive PD Sliding PD
K p diag{50×102}2×3Image
K D diag{100}2×2
Λ diag{90}2×2Image
K m diag{0.15}2×2
K Θ 1 × 10−3
K s diag{0.9}2×2Image

Image

Image
Figure 9.3 Applied torque in Y direction.
Image
Figure 9.4 Tracking of q1.
Image
Figure 9.5 Applied torque in Z direction.
Image
Figure 9.6 Tracking of q2.

9.5.2 4-DoF exoskeleton

In this application the human–machine interface is a 6-axis force/torque sensor, Mini40 F/T Sensor (ATI Industrial Automation). This sensor system includes a data acquisition system. It sends digital signals of three forces and three torques to the computer via the RS232 serial port. The reference signals are generated by (9.5). We choose Ba=diag[8,5,4,4,4,2,1]×104Image, Da=diag[2,1,2,2,2,2,1]×105Image, Ma=diag[3,3,2,1,2,1,1]×104Image. For the 4-DoF exoskeleton, the parameters for the PD controllers are given in the Table 9.2.

Table 9.2

The parameters of PD control

Gain Traditional PD Adaptive PD Sliding PD
K p diag{4×103}4×4Image
K d diag{10}4×4
Λ diag{90}4×4Image
K m diag{1}4×4
K Θ diag{0.1}2×2
K s diag{3}4×4 diag{2}4×4

Image

The admittance model is the same as above, with i=1,2,3,4Image. We only present the flexion-extension results of the shoulder and the elbow. The results are given in Figs. 9.79.10.

Image
Figure 9.7 Applied torque in Y direction.
Image
Figure 9.8 Tracking of q2.
Image
Figure 9.9 Applied force in Y direction.
Image
Figure 9.10 Tracking of q4.

The results show that the PD admittance control with compensations is better than the traditional controller. The proposed PD admittance controllers present high precision tracking despite the presence of gravitational terms.

9.6 Conclusion

In this chapter, novel admittance controllers are presented, which work in joint space. They do not need the inverse kinematics of the robot. These PD and PID controllers use adaptive and sliding mode compensations to improve the tracking accuracy. Stability of the controllers are proven via Lyapunov analysis. The proposed controllers are verified using a 2-DoF pan and tilt robot and a 4-DoF exoskeleton with a F/T sensor. The comparisons between traditional and proposed controllers are made.

Bibliography

[154] X. Li, W. Yu, A systematic tunning method of PID controller for robot manipulators, 9th IEEE International Conference on Control & Automation, ICCA11. Santiago, Chile. 2011:274–279.

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

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