Keywords

These keywords were added by machine and not by the authors. This process is experimental and the keywords may be updated as the learning algorithm improves.

1 Introduction to Motion Control

The dynamical model of robot manipulators will be recalled in this section. Furthermore, important properties of this dynamical model, which is useful in controller design, will then be addressed. Finally, different control tasks of the robot manipulators will be defined.

1.1 Dynamical Model

For motion control, the dynamical model of rigid robot manipulators is conveniently described by Lagrange dynamics. Let the robot manipulator have n links and let the ( n × 1 ) -vector q of joint variables be q = [ q 1 , , q n ] T . The dynamic model of the robot manipulator is then described by Lagrange’s equation [8.1, 8.2, 8.3, 8.4, 8.5, 8.6]

H ( q ) q ¨ + C ( q , q ˙ ) q ˙ + τ g ( q ) = τ ,
(8.1)

where H ( q ) is the ( n × n ) inertia matrix, C ( q , q ˙ ) q ˙ is the ( n × 1 ) -vector of Coriolis and centrifugal forces, τ g ( q ) is the ( n × 1 ) -vector of gravity force, and τ is the ( n × 1 ) -vector of joint control inputs to be designed. Friction and disturbance input have been neglected here.

Remark 8.1

Other contributions to the dynamic description of the robot manipulators may include the dynamics of the actuators, joint and link flexibility, friction, noise, and disturbances. Without loss of generality, the case of the rigid robot manipulators is stressed here.

The control schemes that we will introduce in this chapter are based on some important properties of the dynamical model of robot manipulators. Before giving a detailed introduction to these different schemes, let us first give a list of those properties.

Property 8.1

The inertia matrix is a symmetric positive-definite matrix, which can be expressed

λ h I n H ( q ) λ H I n ,
(8.2)

where λh and λH denote positive constants.

Property 8.2

The matrix N ( q , q ˙ ) = H ˙ ( q ) - 2 C ( q , q ˙ ) is skew-symmetric for a particular choice of C ( q , q ˙ ) (which is always possible), i. e.,

z T N ( q , q ˙ ) z = 0
(8.3)

for any ( n × 1 ) -vector z.

Property 8.3

The ( n × n ) -matrix C ( q , q ˙ ) satisfies

C ( q , q ˙ ) c o q ˙
(8.4)

for some bounded constant co.

Property 8.4

The gravity force/torque vector satisfies

τ g ( q ) g o
(8.5)

for some bounded constant go.

Property 8.5

The equation of motion is linear in the inertia parameters. In other words, there is a  ( r × 1 ) constant vector a and an ( n × r ) regressor matrix Y ( q , q ˙ , q ¨ ) such that

H ( q ) q ¨ + C ( q , q ˙ ) q ˙ + τ g ( q ) = Y ( q , q ˙ , q ¨ ) a .
(8.6)

The vector a is comprised of link masses, moments of inertia, and the link, in various combinations.

Property 8.6

The mapping τ q ˙ is passive; i. e., there exists α 0 such that

0 t q ˙ T ( β ) τ ( β ) d β - α , t < .
(8.7)

Remarks 8.1

  • Properties 8.3 and 8.4 are very useful since they allow us to establish upper bounds on the nonlinear terms in the dynamical model. As we will see further, several control schemes require knowledge of such upper bounds.

  • In Property 8.5, the parameter vector a is comprised of several variables in various combinations. The dimensionality of the parameter space is not unique, and the search over the parameter space is an important problem.

  • In this section, we assume that the robot manipulator is fully actuated and this indicates that there is an independent control input for each degree of freedom (GlossaryTerm

    DOF

    ). In contrast, the robot manipulators with joint or link flexibility are no longer fully actuated and the control problems are more difficult in general.

1.2 Control Tasks

It is instructive for comparative purposes to classify control objectives into the following two classes:

  • Trajectory tracking is aimed at following a time-varying joint reference trajectory specified within the manipulator workspace. In general, this desired trajectory is assumed to comply with the actuators’ capacity. In other words, the joint velocity and acceleration associated with the desired trajectory should not violate, respectively, the velocity and acceleration limit of the manipulator. In practice, the capacity of actuators is set by torque limits, which result in bounds on the acceleration that are complex and state dependent.

  • Regulation sometimes is also called point-to-point control. A fixed configuration in the joint space is specified; the objective is to bring to and keep the joint variable at the desired position in spite of torque disturbances and independently of the initial conditions. The behavior of transients and overshooting, are in general, not guaranteed.

The selection of the controller may depend on the type of task to be performed. For example, tasks only requiring the manipulator to move from one position to another without requiring significant precision during the motion between these two points can be solved by regulators, whereas such as welding, painting, and so on, require tracking controllers.

Remarks 8.2

  • The regulation problem may be seen as a special case of the tracking problem (for which the desired joint velocity and acceleration are zero).

  • The task specification above is given in the joint space and results in joint space control, which is the main content of this chapter. Sometimes, the task specification of the robot manipulators in terms of the desired trajectory of the end-effector (e. g., control with eye-in-hand) is carried out in the task space and gives rise to the operational space control, which will be introduced in Sect. 8.2.

1.3 Summary

In this section, we introduced the dynamical model of the robot manipulators and important properties of this dynamical model. Finally, we defined different control tasks of the robot manipulators.

2 Joint Space Versus Operational Space Control

In a motion control problem, the manipulator moves to a position to pick up an object, transports that object to another location, and deposits it. Such a task is an integral part of any higher-level manipulation tasks such as painting or spot-welding.

Tasks are usually specified in the task space in terms of a desired trajectory of the end-effector, while control actions are performed in the joint space to achieve the desired goals. This fact naturally leads to two kinds of general control methods, namely joint space control and operational space control (task space control) schemes.

2.1 Joint Space Control

The main goal of the joint space control is to design a feedback controller such that the joint coordinates q ( t ) R n track the desired motion q d ( t ) as closely as possible. To this end, consider the equations of motion (8.1) of an n-DOF manipulator expressed in the joint space [8.2, 8.4]. In this case, the control of robot manipulators is naturally achieved in the joint space, since the control inputs are the joint torques. Nevertheless, the user specifies a motion in terms of end-effector coordinates, and thus it is necessary to understand the following strategy.

Figure 8.1 shows the basic outline of the joint space control methods. Firstly, the desired motion, which is described in terms of end-effector coordinates, is converted to a corresponding joint trajectory using the inverse kinematics of the manipulator. Then the feedback controller determines the joint torque necessary to move the manipulator along the desired trajectory specified in joint coordinates starting from measurements of the current joint states [8.1, 8.4, 8.7, 8.8].

Fig. 8.1
figure 1

Generic concept of joint space control

Since it is always assumed that the desired task is given in terms of the time sequence of the joint motion, joint space control schemes are quite adequate in situations where manipulator tasks can be accurately preplanned and little or no online trajectory adjustments are necessary [8.1, 8.4, 8.7, 8.9]. Typically, inverse kinematics is performed for some intermediate task points, and the joint trajectory is interpolated using the intermediate joint solutions. Although the command trajectory consists of straight-line motions in end-effector coordinates between interpolation points, the resulting joint motion consists of curvilinear segments that match the desired end-effector trajectory at the interpolation points.

In fact, the joint space control includes simple proportional–derivative (GlossaryTerm

PD

) control, PID control, inverse dynamic control, Lyapunov-based control, and passivity-based control, as explained in the following sections.

2.2 Operational Space Control

In more complicated and less certain environments, end-effector motion may be subject to online modifications in order to accommodate unexpected events or to respond to sensor inputs. There are a variety of tasks in manufacturing where these type of control problem arise. In particular, it is essential when controlling the interaction between the manipulator and environment is of concern.

Since the desired task is often specified in the operational space and requires precise control of the end-effector motion, joint space control schemes are not suitable in these situations. This motivated a different approach, which can develop control schemes directly based on the dynamics expressed in the operational space [8.10, 8.11].

Let us suppose that the Jacobian matrix, denoted by J ( q ) R n × n , transforms the joint velocity ( q ˙ R n ) to the task velocity ( x ˙ R n ) according to

x ˙ = J ( q ) q ˙ .
(8.8)

Furthermore, assume that it is invertible. Then, the operational space dynamics is expressed as follows

f c = Λ ( q ) x ¨ + Γ ( q , q ˙ ) x ˙ + η ( q ) ,
(8.9)

where f c R n denotes the command forces in the operational space; the pseudo-inertia matrix is defined by

Λ ( q ) = J - T ( q ) H ( q ) J - 1 ( q ) ,
(8.10)

and Γ ( q , q ˙ ) and η ( q ) are given by

Γ ( q , q ˙ ) = J - T ( q ) C ( q , q ˙ ) J - 1 ( q ) - Λ ( q ) J ˙ ( q ) J - 1 ( q ) , η ( q ) = J - T ( q ) τ g ( q ) .

The task space variables are usually reconstructed from the joint space variables, via the kinematic mappings. In fact, it is quite rare to have sensors to directly measure end-effector positions and velocities. Also, it is worth remarking that an analytical Jacobian is utilized since the control schemes operate directly on task space quantities, i. e., the end-effector position and orientation.

The main goal of the operational space control is to design a feedback controller that allows execution of an end-effector motion x ( t ) R n that tracks the desired end-effector motion x d ( t ) as closely as possible. To this end, consider the equations of motion (8.9) of the manipulator expressed in the operational space. For this case, Fig. 8.2 shows a schematic diagram of the operational space control methods. There are several advantages to such an approach because operational space controllers employ a feedback loop that directly minimizes task errors. Inverse kinematics need not be calculated explicitly, since the control algorithm embeds the velocity-level forward kinematics (8.8), as shown in the figure. Now, motion between points can be a straight-line segment in the task space.

Fig. 8.2
figure 2

Basic concept of operational space control

3 Independent-Joint Control

By independent-joint control (i. e., decentralized control), we mean that the control inputs of each joint only depends on the measurement of the corresponding joint displacement and velocity. Due to its simple structure, this kind of control schemes offers many advantages. For example, by using independent-joint control, communication among different joints is saved. Moreover, since the computational load of controllers may be reduced, only low-cost hardware is required in actual implementations. Finally, independent-joint control has the feature of scalability, since the controllers on all the joints have the same formulation. In this section, two kinds of design of independent-joint control will be introduced: one focused on the dynamical model of each joint (i. e., based on the single-joint model) and the other based on the analysis of the overall dynamical model (i. e., the multijoint model) of robot manipulators.

3.1 Controller Design Based on the Single-Joint Model

The simplest independent-joint control strategy is to control each joint axis as a single-input single-output (GlossaryTerm

SISO

) system. Coupling effects among joints due to varying configuration during motion are treated as disturbance inputs. Without loss of generality, the actuator is taken as a rotary electric direct-current (GlossaryTerm

DC

) motor. Hence, the block diagram of the control scheme of joint i can be represented in the domain of the complex variables as shown in Fig. 8.3. In this scheme, θ is the angular variable of the motor, J is the effective inertia viewed from the motor side, Ra is the armature resistance (auto-inductance being neglected), and kt and kv are, respectively, the torque and motor constants. Furthermore, Gv denotes the voltage gain of the power amplifier so that the reference input is the input voltage Vc of the amplifier instead of the armature voltage Va. It has also been assumed that F m k v k t / R a , i. e., the mechanical (viscous) friction coefficient has been neglected with respect to the electrical coefficient. Now the input–output transfer function of the motor can be written as

M ( s ) = k m s ( 1 + s T m ) ,
(8.11)

where k m = G v / k v and T m = R a J / k v k t are, respectively, the voltage-to-velocity gain and the time constant of the motor.

Fig. 8.3
figure 3

Block scheme of a joint-driven system (after [8.4])

To guide selection of the control structure, start by noticing that an effective rejection of the disturbance d on the output θ is ensured by

  1. 1.

    A large value of the amplifier before the point of intervention of the disturbance

  2. 2.

    The presence of an integral action in the controller so as to cancel the effect of the gravitational component on the output at the steady state (i. e., constant θ).

In this case, as shown in Fig. 8.4, the types of control action with position and velocity feedback are characterized by [8.4]

G p ( s ) = K P , G v ( s ) = K V 1 + s T V s ,
(8.12)

where G p ( s ) and G v ( s ) correspond to the position and velocity control actions, respectively. It is worth noting that the inner control action G v ( s ) is in a form of propositional–integral (GlossaryTerm

PI

) control to yield zero error in the steady state under a constant disturbance d. Furthermore, kTP and kTV are both transducer constants, and the amplifier gain KV has been embedded in the gain of the inner controller. From the scheme of Fig. 8.4, the transfer function of the forward path is

P ( s ) = k m K P K V ( 1 + s T V ) s ( 1 + s T m ) ,
(8.13)

while that of the return path is

H ( s ) = k TP 1 + s k TV K P k TP .
(8.14)

The zero of the controller at s = - 1 / T V can be chosen so as to cancel the effects of the real pole of the motor at s = - 1 / T m . Then, by setting T V = T m , the poles of the closed-loop system move on the root locus as a function of the loop gain, k m K V k TV . By increasing the position feedback gain KP, it is possible to confine the closed-loop poles to a region of the complex plane with large absolute real part. Then, the actual location can be established by a suitable choice of KV.

Fig. 8.4
figure 4

Block scheme of position and velocity feedback (after [8.4])

The closed-loop input–output transfer function is

Θ ( s ) Θ r ( s ) = 1 k TP 1 + s k TP K P k TP + s 2 k m K P k TP K V ,
(8.15)

which can be compared with the typical transfer function of a second-order system

W ( s ) = 1 k TP 1 + 2 ζ s ω n + s 2 ω n 2 .
(8.16)

It can be recognized that, with a suitable choice of the gains, it is possible to obtain any value of natural frequency ωn and damping ratio ζ. Hence, if ωn and ζ are given as design specifications, the following relations can be found

K V k TV = 2 ζ ω n k m and K P k TP K V = ω n 2 k m .
(8.17)

For given transducer constants kTP and kTV, KV and KP will be chosen to satisfy the two equations above, respectively. On the other hand, the closed-loop disturbance/output function is

Θ ( s ) D ( s ) = s R a k t K P K TP K V ( 1 + s T m ) 1 + s k TV K P k TP + s 2 k m K P k TP K V ,
(8.18)

which shows that the disturbance rejection factor is X R ( s ) = K P k TP K V and is fixed, provided that KV and KP have been chosen via the approach above. Concerning the disturbance dynamics, the zero at the origin introduced by the PI, a real pole at s = - 1 / T m , and the pair of complex poles with real part - ζ ω n should be kept in mind. In this case, an estimate TR of the output recovery time needed by the control system to recover from the effect of a disturbance on the joint position can be evaluated by analyzing models of the transfer function above. Such an estimate can reasonably be expressed as T R = max { T m , 1 / ζ ω } .

3.2 Controller Design Based on the Multijoint Model

In recent years, independent-joint control schemes based on the complete dynamic model of the robot manipulators (i. e., a multijoint model) have been proposed. For example, following the approach of computed-torque-like control, [8.12] dealt with the regulation task for horizontal motions, and [8.13] and [8.14] handled the tracking task for arbitrary smooth trajectories. Since the overall dynamic model is considered, the effects of coupling among joints are handled. These schemes will be introduced in detail in Sect. 8.6.

3.3 Summary

In this section, we have presented two independent-joint control schemes: one is based on the single-joint model and the other is based on the multijoint model. The former focuses on the dynamics of a single joint and regards the interaction among joints as a disturbance. This control scheme is simple but may not be suitable for high-speed tracking. Hence, we introduce the latter, which considers the overall dynamical model of robot manipulators such that the interaction among joints can be handled.

3.3.1 Further Reading

There are different types of feedback applied in the independent-joint control based on the single-joint model (such as pure position feedback or position, velocity, and acceleration feedback). A complete discussion is given in [8.4]. When the joint control servos are required to track reference trajectories with high speeds and accelerations, the tracking capabilities of the above schemes are inevitably degraded. A possible remedy is to adopt decentralized feedforward compensation to reduce tracking errors [8.4, 8.5].

4 PID Control

Traditionally, control design in robot manipulators can be understood as the simple fact of tuning of a PD or PID compensator at the level of each motor driving the manipulator joints [8.1]. Fundamentally, a PD controller is a position and velocity feedback that has good closed-loop properties when applied to a double integrator system.

The PID control has a long history since Ziegler and Nichols’ PID tuning rules were published in 1942 [8.15]. Actually, the strong point of PID control lies in its simplicity and clear physical meaning. Simple control is preferable to complex control, at least in industry, if the performance enhancement obtained by using complex control is not significant enough. The physical meanings of PID control [8.16] are as follows:

  • P-control means the present effort making a present state into desired state

  • I-control means the accumulated effort using the experience information of previous states

  • D-control means the predictive effort reflecting the information about trends in future states.

4.1 PD Control for Regulation

A simple design method for manipulator control is to utilize a linear control scheme based on the linearization of the system about an operating point. An example of this method is a PD control with a gravity compensation scheme [8.17, 8.18]. Gravity compensation acts as a bias correction, compensating only for the amount of forces that create overshooting and an asymmetric transient behavior. Formally, it has the following form

τ = K P ( q d - q ) - K V q ˙ + τ g ( q ) ,
(8.19)

where KP and K V R n × n are positive-definite gain matrices. This controller is very useful for set-point regulation, i. e., q d = constant  [8.18, 8.7]. When this controller is applied to (8.1), the closed-loop equation becomes

H ( q ) q ¨ + C ( q , q ˙ ) q ˙ + K V q ˙ - K P e q = 0 ,
(8.20)

where e q = q d - q , and the equilibrium point is y = [ e q T , q ˙ T ] T = 0 . Now, the stability achieved by PD control with gravity compensation can be analyzed according to the closed-loop dynamic (8.20). Consider the positive-definite function

V = 1 2 q ˙ T H ( q ) q ˙ + 1 2 e q T K V e q .

Then, the derivative of function becomes negative semidefinite for any value of q ˙ by using Property 8.2 in Sect. 8.1 , i. e.,

V ˙ = - q ˙ T K V q ˙ - λ min ( K V ) q ˙ 2 ,
(8.21)

where λ min ( K V ) means the smallest eigenvalue of KV. By invoking the Lyapunov stability theory and LaSalle’s theorem [8.1], it can be shown that the regulation error will converge asymptotically to zero, while their high-order derivatives remain bounded. This controller requires knowledge of the gravity components (structure and parameters), though it is simple.

Now, consider simple PD control without gravity compensation

τ = K P ( q d - q ) - K V q ˙ ,
(8.22)

then the closed-loop dynamic equation becomes

H ( q ) q ¨ + C ( q , q ˙ ) q ˙ + τ g ( q ) + K V q ˙ - K P e q = 0 .
(8.23)

Consider the positive definite function

V = 1 2 q ˙ T H ( q ) q ˙ + 1 2 e q T K V e q + U ( q ) + U 0 ,

where U ( q ) denotes the potential energy with the relation of U ( q ) / q = τ g ( q ) and U0 is a suitable constant. Taking time derivative of V along the closed-loop dynamics (8.23) gives the same result (8.21) with previous one using gravity compensation. In this case, the control system must be stable in the sense of Lyapunov, but it can not conclude that the regulation error will converge to zero by LaSalle’s theorem [8.1]. Actually, the system precision (the size of the regulation error vector) will depend on the size of the gain matrix KP in the following form

e q K P - 1 g 0 ,
(8.24)

where g0 is that in Property 8.4 in Sect. 8.1. Hence, the regulation error can be arbitrarily reduced by increasing KP; nevertheless, measurement noise and other unmodeled dynamics, such as actuator friction, will limit the use of high gains in practice.

4.2 PID Control for Regulation

An integral action may be added to the previous PD control in order to deal with gravity forces, which to some extent can be considered as a constant disturbance (from the local point of view). The PID regulation controller can be written in the following general form

τ = K P ( q d - q ) + K I f ( q d - q ) d t - K V q ˙ ,

where K I R n × n is a positive-definite gain matrix, and:

  • If f ( q d - q ) = q d - q , we have PID control.

  • If K I ( - q ˙ ) d t is added, we have PI 2 D control.

  • If f ( ) = tanh ( ) , we have PD + nonlinear integral control.

Global asymptotic stability (GlossaryTerm

GAS

) by PID control was proved in [8.12] for robotic motion control system including external disturbances, such as Coulomb friction. Also, Tomei proved the GAS of PD control in [8.19] by using an adaptation for gravity term. On the other hand, Ortega et al. showed in [8.20] that PI 2 D control could yield semiglobal asymptotic stability (GlossaryTerm

SGAS

) in the presence of gravity and bounded external disturbances. Also, Angeli proved in [8.21] that PD control could achieve the input-output-to-state stability (GlossaryTerm

IOSS

) for robotic systems. Also, Ramirez et al. proved the SGAS (with some conditions) for PID gains in [8.22]. Also, Kelly proved in [8.23] that PD plus nonlinear integral control could achieve GAS under gravity.

Actually, a large integral action in PID control can cause instability of the motion control system. In order to avoid this, the integral gain should be bounded by an upper limit of the following form [8.1]

k P k V λ H 2 > k I ,

where λH is that in Property 8.1 in Sect. 8.1, K P = k P I , K I = k I I , and K V = k V I . This relation gives the guidelines for gain selection implicitly. Also, PID control has generated a great variety of PID control plus something, e. g., PID plus friction compensator, PID plus gravity compensator, PID plus disturbance observer.

4.3 PID Gain Tuning

The PID control can be utilized for trajectory tracking as well as set-point regulation. True tracking control will be treated after Sect. 8.5 . In this section, the simple but useful PID gain tuning method will be introduced for practical use. The general PID controller can be written in the following general form

τ = K V e ˙ q + K P e q + K I e q d t ,

or, in another form,

τ = K + 1 γ 2 I e ˙ q + K P e q + K I e q d t .
(8.25)

In a fundamental stability analysis of tracking control systems, Qu and Dorsey proved in [8.24] that PD control could satisfy uniform ultimate boundedness (GlossaryTerm

UUB

). Also, Berghuis and Nijmeijer proposed output feedback PD control, which satisfies semiglobal uniform ultimate boundedness (GlossaryTerm

SGUUB

) in [8.25] under gravity and a bounded disturbance. Recently, Choi et al. suggested inverse optimal PID control [8.26], assuring extended disturbance input-to-state stability (GlossaryTerm

ISS

).

Actually, if a PID controller (8.25) is repeatedly applied to the same set point or desired trajectory, then the maximum error will be proportional to the gains in the following form

max 0 t t f e q ( t ) γ 2 2 k γ 2 + 1 ,
(8.26)

where tf denotes the final execution time of a given task and K = k I . This relation can be utilized to tune the gain of a PID controller and is referred to as the compound tuning rule [8.16]. The compound tuning rule implicitly includes simple tuning rules as follows (γ tuning method):

  • Square tuning: max e q γ 2 , for a small k

  • Linear tuning: max e q γ , for a large k.

For example, suppose we select positive constant diagonal matrices K P = k P I , K I = k I I , while satisfying k P 2 > 2 k I . For small k, the maximum error will be reduced by 1 4 according to the square tuning rule, if we reduce the value γ by 1 2 . For large k, the maximum error will be proportionally reduced as γ according to the linear tuning rule. This means that we can tune the PID controller using only one parameter γ when the other gain parameters are fixed [8.16] ( ). Although these rules are very useful in tuning the control performance, they can be utilized only for repetitive experiments for the same set point or desired trajectory because the tuning rules consist of proportional relations.

4.4 Automatic Tuning

For simplicity, define the composite error to be

s ( t ) = e ˙ q + K P e q + K I e q d t .

Now simple auto-tuning PID control is suggested by choosing one tuning parameter K as shown in the following control form

τ = K ^ ( t ) + 1 γ 2 I s ( t ) ,

and its automatic tuning rule as follow

d K ^ i d t = Γ i s i 2 ( t ) , for  i = 1 , , n ,
(8.27)

where Γ i implies an update gain parameter for i-th control joint.

For practical use of the PID control, a target performance denoted by Ω is specified in advance

sup 0 t t f | s ( t ) | = Ω ,

in order to maintain the composite error within the region Ω. Moreover, since the auto-tuning rule has the decentralized type (8.27), we suggest the decentralized criterion for auto-tuning as follows

| s i | > Ω 2 n ,
(8.28)

where n is the number of the joint coordinates. As soon as the composite error arrives at the tuning region (8.28), the auto-tuning rule is implemented to assist the achievement of target performance. On the contrary, if the composite error stays in non-tuning region, namely, | s i | Ω / 2 n , then the auto-tuning process stops. For this case, we expect that the gain K ^ updated by an auto-tuning rule (8.27) would be larger than the matrix K Ω able to achieve the target performance Ω. As a matter of fact, the auto-tuning rule plays a nonlinear damping role in the auto-tuning region.

4.4.1 Matlab Example (Multimedia)

Simple automatic tuning example for one-link manipulator control system is shown in the multimedia source to help readers’ understanding.

4.4.2 Further Reading

The PID-type controllers were designed to solve the regulation control problem. They have the advantage of requiring knowledge of neither the model structure nor the model parameters. Also, the stability achieved by PID-type controllers was presented in this section. A range of books and papers [8.1, 8.15, 8.16, 8.22, 8.27, 8.28] are available to the robotics audience, detailing the individual tuning methods used in PID control and their concrete proofs.

5 Tracking Control

While independent PID controls are adequate in most set-point regulation problems, there are many tasks that require effective trajectory tracking capabilities such as plasma-welding, laser-cutting or high-speed operations in the presence of obstacles. In this case, employing local schemes requires moving slowly through a number of intermediate set points, thus considerably delaying the completion of the task. Therefore, to improve the trajectory tracking performance, controllers should take account of the manipulator dynamic model via a computed-torque-like technique.

The tracking control problem in the joint or task space consists of following a given time-varying trajectory q d ( t ) or x d ( t ) and its successive derivatives q ˙ d ( t ) or x ˙ d ( t ) and q ¨ d ( t ) or x ¨ d ( t ) , which describe the desired velocity and acceleration, respectively. To obtain successful performance, significant effort has been devoted to the development of model-based control strategies [8.1, 8.2, 8.7]. Among the control approaches reported in the literature, typical methods include the inverse dynamics control, the feedback linearization technique, and the passivity-based control method.

5.1 Inverse Dynamics Control

Though the inverse dynamics control has a theoretical background, such as the theory of feedback linearization discussed later, its starting point is mechanical engineering intuition based on cancelling nonlinear terms and decoupling the dynamics of each link. Inverse dynamics control in joint space has the form

τ = H ( q ) v + C ( q , q ˙ ) q ˙ + τ g ( q ) ,
(8.29)

which, applied to (8.1), yields a set of n decoupled linear systems, e. g., q ¨ = v , where v is an auxiliary control input to be designed. Typical choices for v are

v = q ¨ d + K V ( q ˙ d - q ˙ ) + K P ( q d - q ) ,
(8.30)

or with an integral component

v = q ¨ d + K V ( q ˙ d - q ˙ ) + K P ( q d - q ) + K I ( q d - q ) d t ,
(8.31)

leading to the error dynamics equation

e ¨ q + K V e ˙ q + K P e q = 0

for an auxiliary control input (8.30), and

e q ( 3 ) + K V e ¨ q + K P e ˙ q + K I e q = 0 ,

if an auxiliary control input (8.31) is used. Both error dynamics are exponentially stable by a suitable choice of the gain matrices KV and KP (and KI).

Alternatively, inverse dynamics control can be described in the operational space. Consider the operational space dynamics (8.9). If the following inverse dynamics control is used in the operational space,

f c = Λ ( q ) ( x ¨ d + K V e ˙ x + K P e x ) + Γ ( q , q ˙ ) x ˙ + η ( q ) ,

where e x = x d - x , the resulting error dynamics is

e ¨ x + K V e ˙ x + K P e x = 0 ,
(8.32)

and it is also exponentially stable. One apparent advantage of using this controller is that KP and KV can be selected with a clear physical meaning in operational space. However, as can be seen in (8.10), Λ ( q ) becomes very large when the robot approaches singular configurations [8.8]. This means that large forces in some direction are needed to move the arm.

5.2 Feedback Linearization

This approach generalizes the concept of inverse dynamics of rigid manipulators. The basic idea of feedback linearization is to construct a transformation as a so-called inner-loop control, which exactly linearizes the nonlinear system after a suitable state space change of coordinates. One can then design a second stage or outer-loop control in the new coordinates to satisfy the traditional control design specifications such as tracking, disturbance rejection, etc. [8.29, 8.5]. The full power of the feedback linearization scheme for manipulator control becomes apparent if one includes in the dynamic description of the manipulator the transmission dynamics, such as the elasticity resulting from shaft windup, gear elasticity, etc. [8.5].

In recent years, an impressive volume of literature has emerged in the area of differential-geometric methods for nonlinear systems. Most of the results in this area are intended to give abstract coordinate-free descriptions of various geometric properties of nonlinear systems and as such are difficult for the non-mathematician to follow. It is our intention here to give only the basic idea of the feedback linearization scheme and to introduce a simple version of this technique that finds an immediate application to the manipulator control problem. The reader is referred to [8.30] for a comprehensive treatment of the feedback linearization technique using differential-geometric methods.

Let us now develop a simple approach to the determination of linear state-space representations of the manipulator dynamics (8.1) by considering a general sort of output ξ R p

ξ = h ( q ) + r ( t ) ,
(8.33)

where h ( q ) is a general predetermined function of the joint coordinate q R n and r ( t ) is a general predetermined time function. The control objective will be to select the joint torque inputs τ in order to make the output ξ ( t ) go to zero.

The choice of h ( q ) and r ( t ) is based on the control purpose. For example, if h ( q ) = - q and r ( t ) = q d ( t ) , the desired joint space trajectory we would like the manipulator to follow, then ξ ( t ) = q d ( t ) - q ( t ) e q ( t ) is the joint space tracking error. Forcing ξ ( t ) to zero in this case would cause the joint variables q ( t ) to track their desired values q d ( t ) , resulting in a manipulator trajectory-following problem. As another example, ξ ( t ) could represent the operational space tracking error ξ ( t ) = x d ( t ) - x ( t ) e x ( t ) . Then, controlling ξ ( t ) to zero would result in trajectory following directly in operational space where the desired motion is usually specified.

To determine a linear state-variable model for manipulator controller design, let us simply differentiate the output ξ ( t ) twice to obtain

ξ ˙ = h q q ˙ + r ˙ = T q ˙ + r ˙ ,
(8.34)
ξ ¨ = T q ¨ + T ˙ q ˙ + r ¨ ,
(8.35)

where we defined a  ( p × n ) transformation matrix of the form

T ( q ) = h ( q ) q = h q 1 h q 2 h q n .
(8.36)

Given the output h ( q ) , it is straightforward to compute the transformation T ( q ) associated with h ( q ) . In the special case where ξ ˙ represents the operational space velocity error, then T ( q ) denotes the Jacobian matrix  J ( q ) .

According to (8.1),

q ¨ = H - 1 ( q ) [ τ - n ( q , q ˙ ) ] ,
(8.37)

with the nonlinear terms represented by

n ( q , q ˙ ) = C ( q , q ˙ ) q ˙ + τ g ( q ) .
(8.38)

Then (8.35 ) yields

ξ ¨ = r ¨ + T ˙ q ˙ + T ( q ) H - 1 ( q ) [ τ - n ( q , q ˙ ) ] .
(8.39)

Define the control input function

u = r ¨ + T ˙ q ˙ + T ( q ) H - 1 ( q ) [ τ - n ( q , q ˙ ) ] .
(8.40)

Now we may define a state y ( t ) R 2 p by y = ( ξ ξ ˙ ) and write the manipulator dynamics as

y ˙ = 0 I p 0 0 y + 0 I p u .
(8.41)

This is a linear state-space system of the form

y ˙ = A y + B u ,
(8.42)

driven by the control input u. Due to the special form of A and B, this system is called the Brunovsky canonical form and it is always controllable from u ( t ) .

Since (8.40 ) is said to be a linearizing transformation for the manipulator dynamic equation, one may invert this transformation to obtain the joint torque

τ = H ( q ) T + ( q ) ( u - r ¨ - T ˙ q ˙ ) + n ( q , q ˙ ) ,
(8.43)

where T + denotes the Moore–Penrose inverse of the transformation matrix T ( q ) .

In the special case ξ = e q ( t ) , and if we select u ( t ) so that (8.41) is stable by the PD feedback u = - K P ξ - K V ξ ˙ , then T = - I n and the control input torque τ ( t ) defined by (8.43) makes the manipulator move in such a way that y ( t ) goes to zero. In this case, the feedback linearizing control and the inverse dynamics control become the same.

5.3 Passivity-Based Control

This method explicitly uses the passivity properties of the Lagrangian system [8.31, 8.32]. In comparison with the inverse dynamics method, passivity-based controllers are expected to have better robust properties because they do not rely on the exact cancellation of the manipulator nonlinearities. The passivity-based control input is given by

q ˙ r = q ˙ d + α e q , α > 0 , τ = H ( q ) q ¨ r + C ( q , q ˙ ) q ˙ r + τ g ( q ) + K V e ˙ q + K P e q .
(8.44)

With (8.44), we obtain the following closed-loop system

H ( q ) s ˙ q + C ( q , q ˙ ) s q + K V e ˙ q + K P e q = 0 ,
(8.45)

where s q = e ˙ q + α e q . Let us choose a Lyapunov function V ( y , t ) as follows

V = 1 2 y T α K V + K P + α 2 H α H α H H y = 1 2 y T P y .
(8.46)

Since the above equation is positive definite, it has a unique equilibrium at the origin, i. e., y = ( e q T , e ˙ q T ) T = 0 . Moreover, V can be bounded by

σ m y 2 y T P y σ M y 2 , σ M σ m > 0 .
(8.47)

The time derivative of V gives

V ˙ = - e ˙ q T K V e ˙ q - α e q K P e q = - y T Q y < 0 ,
(8.48)

where Q = diag [ α K P , K V ] . Since Q is positive definite and quadratic in y, it can be also bounded by

κ m y 2 y T Q y κ M y 2 , κ M κ m > 0 .
(8.49)

Then, from the bound of the Lyapunov function V, we get

V ˙ - κ m y 2 = - 2 η V , η = κ m σ M ,
(8.50)

which finally yields

V ( t ) V ( 0 ) e - 2 η t .
(8.51)

It has been shown that the value of α affects the tracking result dramatically [8.33]. The manipulator tends to vibrate for small values of α. Larger values of α allow better tracking performance and protect sq from being spoiled by the velocity measurement noise when the position error is small. In [8.34], it was suggested that

K P = α K V
(8.52)

be used for quadratic optimization.

5.4 Summary

In this section, we have reviewed some of the model-based motion control methods proposed to date. Under some control approaches, the closed-loop system has either asymptotic stability or globally exponential stability. However, such ideal performance cannot be obtained in practical implementation because factors such as sampling rate, measurement noise, disturbances, and unmodeled dynamics will limit the achievable gain and the performance of the control algorithms [8.33, 8.35, 8.36].

6 Computed-Torque Control

Through the years many kinds of robot control schemes have been proposed. Most of these can be considered as special cases of the class of computed-torque control (Fig. 8.5) which is the technique of applying feedback linearization to nonlinear systems in general [8.37, 8.38]. In the section, computed-torque control will be first introduced, and its variant, so-called computed-torque-like control, will be introduced later.

Fig. 8.5
figure 5

Computed-torque control

6.1 Computed-Torque Control

Consider the control input (8.29)

τ = H ( q ) v + C ( q , q ˙ ) q ˙ + τ g ( q ) ,

which is also known as computed-torque control; it consists of an inner nonlinear compensation loop and an outer loop with an exogenous control signal v. Substituting this control law into the dynamical model of the robot manipulator, it follows that

q ¨ = v .
(8.53)

It is important to note that this control input converts a complicated nonlinear controller design problem into a simple design problem for a linear system consisting of n decoupled subsystems. One approach to the outer-loop control v is propositional–derivative (PD) feedback, as in (8.30)

v = q ¨ d + K V e ˙ q + K P e q ,

in which case the overall control input becomes

τ = H ( q ) ( q ¨ d + K V e ˙ q + K P e q ) + C ( q , q ˙ ) q ˙ + τ g ( q ) ,

and the resulting linear error dynamics are

e ¨ q + K V e ˙ q + K P e q = 0 .
(8.54)

According to linear system theory, convergence of the tracking error to zero is guaranteed [8.29, 8.39].

Remark 8.2

One usually lets KV and KP be ( n × n ) diagonal positive-definite gain matrices (i. e., K V = diag ( k V , 1 , , k V , n ) > 0 , K P = diag ( k P , 1 , , k P , n ) > 0 ) to guarantee the stability of the error system. However, the format of the foregoing control never leads to independent joint control because the outer-loop multiplier H ( q ) and the full nonlinear compensation term C ( q , q ˙ ) q ˙ + τ g ( q ) in the inner loop scramble all joint signals among different control channels.

6.2 Computed-Torque-Like Control

It is worth noting that the implementation of computed-torque control requires that parameters of the dynamical model are accurately known and the control input is computed in real time. In order to avoid those problems, several variations of this control scheme have been proposed, for example, computed-torque-like control. An entire class of computed-torque-like controllers can be obtained by modifying the computed-torque control as

τ = H ^ ( q ) v + C ^ ( q , q ˙ ) q ˙ + τ ^ ( q ) ,
(8.55)

where ^ represents the computed or nominal value and indicates that the theoretically exact feedback linearization cannot be achieved in practice due to the uncertainty in the systems. The overall control scheme is depicted in Fig. 8.6.

Fig. 8.6
figure 6

Computed-torque-like control

6.2.1 Computed-Torque-Like Control with Variable-Structure Compensation

Since there is parametric uncertainty, compensation is required in the outer-loop design to achieve trajectory tracking. The following shows a computed-torque-like control with variable-structure compensation

v = q ¨ d + K V e ˙ q + K P e q + Δ v ,
(8.56)

where the variable-structure compensation Δ v is devised as

Δ v = - ρ ( x , t ) B T P x B T P x if B T P x 0 , 0 if B T P x = 0 ,
(8.57)

where x = ( e q T , e ˙ q T ) T , B = ( 0 , I n ) T , P is a  ( 2 n × 2 n ) symmetric positive-definite matrix satisfying

PA + A T P = - Q ,
(8.58)

with A being defined as

A = 0 I n - K P - K V ,
(8.59)

Q being any appropriate ( 2 n × 2 n ) symmetric positive-definite matrix,

ρ ( x , t ) = 1 1 - α [ α β + K x + H ¯ ϕ ( x , t ) ] ,
(8.60)

where α and β are positive constants such that H - 1 ( q ) H ^ ( q ) - I n α < 1 for all q R n and sup t [ 0 , ) q ¨ d ( t ) < β , respectively, K is the ( n × 2 n ) matrix defined as K = [ K P K V ] , λ ¯ H being a positive constant such that H - 1 ( q ) λ ¯ H for all q R n , and the function ϕ being defined as

[ C ^ ( q , q ˙ ) - C ( q , q ˙ ) ] q ˙ + [ τ ^ g ( q ) - τ g ( q ) ] ϕ ( x , t ) .
(8.61)

Convergence of the tracking error to zero can be shown using the Lyapunov function

V = x T P x ,
(8.62)

following the stability analysis in [8.40, 8.5].

Remarks 8.3

  • By Property 8.1 in Sect. 8.1, there exist positive constants λ ¯ H and λ ¯ h such that λ ¯ h H - 1 ( q ) λ ¯ H for all q R n . If we choose

    H ^ = 1 c I n , where c = λ ¯ H + λ ¯ h 2 ,
    (8.63)

    it can be shown that

    H - 1 ( q ) H ^ ( q ) - I n λ ¯ H - λ ¯ h λ H + λ ¯ h α < 1 ,
    (8.64)

    which indicates that there is always at least one choice of H ^ for some α < 1.

  • Due to the discontinuity in Δ v , chattering phenomenon may occur when the control scheme is applied. It is worth noting that chattering is often undesirable since the high-frequency component in the control can excite unmodeled dynamic effect (such as joint flexibility) [8.29, 8.38, 8.6]. In order to avoid chattering, the variable-structure compensation can be modified to become smooth, i. e.,

    Δ v = - ρ ( x , t ) B T P x B T P x if B T P x > ε , - ρ ( x , t ) ε B T P x if B T P x ε ,
    (8.65)

    where ε is a positive constant and is used as the boundary layer. Following this modification, convergence of tracking errors to a residual set can be ensured, and the size of this residual set can be made smaller by use of a smaller value of ε.

6.2.2 Computed-Torque-Like Control with Independent-Joint Compensation

Obviously, the previous compensation scheme is centralized, which implies that the online computation load is heavy and high-cost hardware is required for practical implementation. In order to solve this problem, a scheme with independent-joint compensation is introduced below. In this scheme, a computed-torque-like control is designed with estimates as

H ^ ( q ) = I , C ^ ( q , q ˙ ) = 0 , τ ^ ( q ) = 0 .
(8.66)

Then, we use the outer-loop v as

v = K V e ˙ q + K P e q + Δ v ,
(8.67)

where the positive constants KP and KV are selected to be sufficiently large, and the i-th component Δ v i of Δ v = ( v 1 , , v n ) T is

Δ v i = - [ β T w ( q d , q ˙ d ) ] 2 s i ε i if s i ε i β T w ( q d , q ˙ d ) , - β T w ( q d , q ˙ d ) s i | s i | if s i > ε i β T w ( q d , q ˙ d ) .
(8.68)

In this compensation, s i = e ˙ q , i + λ i e q , i , i { 1 , , n } , and λ i , i { 1 , , n } are positive constants. Furthermore, following the properties of robot manipulators, we have

H ( q ) q ¨ d + C ( q , q ˙ ) q ˙ d + τ g ( q ) β 1 + β 2 q + q ˙ = β T w ( q , q ˙ )

for some suitable positive constants β1, β2, and β3, where β = ( β 1 , β 2 , β 3 ) T and

w ( q , q ˙ ) = [ 1 , q , q ˙ ] T .
(8.69)

Finally, εi, i { 1 , , n } , is the variable length of the boundary layer, satisfying

ε ˙ i = - g i ε i , ε ( 0 ) > 0 , g i > 0 .
(8.70)

It is worth pointing out that the term w in this control scheme is devised as the desired compensation rather than feedback. Furthermore, this scheme is in a form of independent-joint control and hence has the advantages introduced before. The convergence of the tracking error to zero can be shown using the Lyapunov function

V = 1 2 ( e q T e ˙ q T ) λ K P H H λ H e q e ˙ q + i = 1 n g i - 1 ε i ,
(8.71)

whose time derivative along the trajectory of the closed-loop systems follows

V ˙ = - α e q e ˙ q 2 ,
(8.72)

with α being some positive constant, if sufficiently large KP and γ are used. The detailed analysis of stability, which requires Properties 8.3 and 8.4, can be found in [8.13].

Remark 8.3

Similar to computed-torque-like control with variable-structure compensation, we can consider the nonzero boundary layer as

ε ˙ i = - g i ε i , ε ( 0 ) > 0 , g i , α i > 0 .
(8.73)

Following this modification, tracking errors converge to a residual set. The size of this residual set can be made smaller by the use of a smaller value of ε (i. e., smaller αi).

For the task of point-to-point control, one PD controller with gravity compensation is designed with the estimates

H ^ ( q ) = I , C ^ ( q , q ˙ ) = 0 , τ ^ g ( q ) = τ g ( q ) ,
(8.74)

with τ g ( q ) being the gravity term of the dynamical model of the robot manipulators. Then, we use the outer-loop v as

v = K V e ˙ q + K P e q ,
(8.75)

such that the control input becomes

τ = K V e ˙ q + K P e q + τ g ( q ) .
(8.76)

This scheme is much simpler to implement than the exact computed-torque controller. The convergence of the tracking error to zero can be shown using the Lyapunov function

V = 1 2 e ˙ q T H ( q ) e ˙ q + 1 2 e q T K P e q ,
(8.77)

whose time derivative along the solution trajectories of the closed-loop system is

V ˙ = - e ˙ q T K V e ˙ q .
(8.78)

The detailed analysis of stability is given in [8.12]. It is necessary to note that this result is for the case of regulation, rather than for the case of tracking, since the former theoretical base, which relies on LaSalle’s lemma, requires the system be autonomous (time invariant) [8.38, 8.41, 8.42].

Remark 8.4

If we neglect gravity in the dynamical model of the robot manipulators, then the gravity estimation can be omitted here, i. e., τ ^ g ( q ) = 0 , so that the control law becomes

τ = v = K V e ˙ q + K P e q ,
(8.79)

which leads to pure PD control. The gain matrices, KP and KV, can be selected to be diagonal so that this PD control is in a form of independent-joint control developed based on the multijoint dynamic model.

6.3 Summary

In this section, we have presented two control schemes: the computed-torque and computed-torque-like control. The former transforms a multi-input multi-output (GlossaryTerm

MIMO

) nonlinear robotic system into a very simple decoupled linear closed-loop system whose control design is a well-established problem. Since the practical implementation of the former control requires preknowledge of all the manipulator parameters and its payload, which may not be realistic, the latter was introduced to relax the foregoing requirement and still to achieve the objective of tracking subject to system’s uncertainty.

6.3.1 Further Reading

The PD control with different feedforward compensation for tracking control is investigated in [8.43]. An adaptive control scheme based on PD control is presented in [8.19].

7 Adaptive Control

An adaptive controller differs from an ordinary controller in that the controller parameters are time varying, and there is a mechanism for adjusting these parameters online based on some signals in the closed-loop systems. By the use of such control scheme, the control goal can be achieved even if there is parametric uncertainty in the plant. In this section, we will introduce several adaptive control schemes to deal with the case of imperfect knowledge of dynamical parameters of the robot manipulators. The control performance of those adaptive control schemes, including adaptive computed-torque control, adaptive inertia-related control, adaptive control based on passivity, and adaptive control with desired compensation, are basically derived from Property 8.5. Finally, the condition of persistent excitation, which is important in parameter convergence, will be addressed.

7.1 Adaptive Computed-Torque Control

The computed-torque control scheme is appealing, since it allows the designer to transform a MIMO highly coupled nonlinear system into a very simple decoupled linear system, whose control design is a well-established problem. However, this method of feedback linearization relies on perfect knowledge of the system parameters, and failure to have this will cause erroneous parametric estimates, resulting in a mismatch term in the closed-loop model of the error system. That term can be interpreted as a nonlinear perturbation acting at the input of the closed-loop system. In order to solve the problem due to parametric uncertainty, we instead consider the inverse dynamics method with parameter estimates of

τ = H ^ ( q ) ( q ¨ d + K V e ˙ q + K P e q ) + C ^ ( q , q ˙ ) q ˙ + τ ^ g ( q ) ,
(8.80)

where H ^ , C ^ , τ ^ g have the same functional form as H, C, τ g . From Property 8.5 of the dynamics model, we have

H ^ ( q ) q ¨ + C ^ ( q , q ˙ ) q ˙ + τ ^ g ( q ) = Y ( q , q ˙ , q ¨ ) a ^ ,
(8.81)

where Y ( q , q ˙ , q ¨ ) , called the regressor, is a known ( n × r ) function matrix and a is the ( r × 1 ) vector that summarizes all the estimated parameters. Substituting this control input τ into the manipulator dynamics gives the following closed-loop error model

H ^ ( q ) ( e ¨ q + K V e ˙ q + K P e q ) = Y ( q , q ˙ , q ¨ ) a ̃ ,
(8.82)

where a ̃ = a ^ - a . In order to acquire an appropriate adaptive law, we first assume that the acceleration term q ¨ is measurable, and that the estimated inertia matrix H ^ ( q ) is never singular. Now, for convenience, the error equation is rewritten as

x ˙ = A x + B H ^ - 1 ( q ) Y ( q , q ˙ , q ¨ ) a ̃ ,
(8.83)

with x = e q T , e ˙ q T T ,

A = 0 n I n - K P - K V , B = 0 n I n .
(8.84)

The adaptive law is considered as

a ^ ˙ = - Γ - 1 Y T ( q , q ˙ , q ¨ ) H ^ - 1 ( q ) B T P x ,
(8.85)

where Γ is an ( r × r ) positive-definite constant matrix, and P is a  ( 2 n × 2 n ) symmetric positive-definite constant matrix satisfying

PA + A T P = - Q ,
(8.86)

with Q being a symmetric positive-definite constant matrix with coherent dimension. In this adaptive law, we made two assumptions:

  • The joint acceleration q ¨ is measurable, and

  • The bounded range of the unknown parameter is available.

The first assumption is to ensure that the regressor Y ( q , q ˙ , q ¨ ) is known a priori, whereas the second assumption is to allow one to keep the estimate H ^ ( q ) nonsingular by restricting the estimated parameter a ^ to lie within a range about the true parameter value.

Convergence of the tracking error and maintaining boundedness of all internal signals can actually be guaranteed by Lyapunov stability theory with the Lyapunov function

V ˙ = - x T Q x .
(8.87)

Detailed stability analysis is given in [8.2].

Remark 8.5

For practical and theoretical reasons, the first assumption above is hardly acceptable. In most cases, it is not easy to obtain an accurate measure of acceleration; the robustness of the above adaptive control scheme with respect to such a disturbance has to be established. Moreover, from a pure theoretical viewpoint, measuring q , q ˙ , q ¨ means that not only do we need the whole system state vector, but we also need its derivative.

7.2 Adaptive Inertia-Related Control

Another adaptive control scheme is now introduced. This proposed scheme does not require the measurement of the manipulator’s acceleration nor does it require inversion of the estimated inertia matrix. Hence, the drawbacks of the adaptive computed-torque control scheme are avoided. Let us consider the control input

τ = H ^ ( q ) v ˙ + C ^ ( q , q ˙ ) v + τ ^ g ( q ) + K D s ,
(8.88)

where the auxiliary signals v and s are defined as v = q ˙ d + Λ e q and s = v - q ˙ = e ˙ q + Λ e q , with Λ being an ( n × n ) positive-definite matrix. Following Property 8.5 of the dynamic model, we have

H ( q ) v ˙ + C ( q , q ˙ ) v + τ g ( q ) = Y ¯ ( q , q ˙ , v , v ˙ ) a ,
(8.89)

where Y ¯ ( , , , ) is an ( n × r ) matrix of known time functions. The formulation above is the same type of the parameter separation that was used in the formulation of the adaptive computed-torque control. Note that Y ¯ ( q , q ˙ , v , v ˙ ) is independent of the joint acceleration. Similar to the formulation above, we also have

H ^ ( q ) v ˙ + C ^ ( q , q ˙ ) v + τ ^ g ( q ) = Y ¯ ( q , q ˙ , v , v ˙ ) a ^ .
(8.90)

Substituting the control input into the equation of motion, it follows that

H ( q ) q ¨ + C ( q , q ˙ ) q ˙ + τ g ( p ) = H ^ ( q ) v ˙ + C ^ ( q , q ˙ ) v + τ ^ g ( q ) + K D s .

Since q ¨ = v ˙ - s ˙ , q ˙ = v - s , the previous result can be rewritten as

H ( q ) s ˙ + C ( q , q ˙ ) s + K D s = Y ¯ ( q , q ˙ , v , v ˙ ) a ̃ ,
(8.91)

where a ̃ = a - a ^ . The adaptive law is considered as

a ^ ˙ = Γ Y ¯ T ( q , q ˙ , v , v ˙ ) s .
(8.92)

The convergence of the tracking error to zero with boundedness on all internal signals can be shown through Lyapunov stability theory using the following Lyapunov-like function

V = 1 2 s T H ( q ) s + 1 2 a ̃ T Γ - 1 a ̃ ,
(8.93)

whose time derivative along the trajectories of the closed-loop systems can be found to be

V ˙ = - s T K D s .
(8.94)

The detailed stability analysis is given in [8.32].

Remark 8.6

  • The restrictions for adaptive computed-torque control formerly seen have been removed here.

  • The term K D s introduces a PD-type linear stabilizing control action to the error system model.

  • The estimated parameters converge to the true parameters provided the reference trajectory satisfies the condition of persistency of excitation,

    α 1 I r t 0 t 0 + t Y T ( q d , q ˙ d , v , v ˙ ) Y ( q d , q ˙ d , v , v ˙ ) d t α 2 I r ,

    for all t0, where α1, α2, and t are all positive constants.

7.3 Adaptive Control Based on Passivity

Taking a physics viewpoint of control, we see that the concept of passivity has become popular for the development of adaptive control schemes. Here, we illustrate how the concept of passivity can be used to design a class of adaptive control laws for robot manipulators. First, we define an auxiliary filtered tracking error signal r as

r = F - 1 ( s ) e q ,
(8.95)

where

F - 1 ( s ) = s I n + 1 s K ( s ) ,
(8.96)

and s is the Laplace transform variable. The ( n × n ) matrix K ( s ) is chosen such that F ( s ) is a strictly proper, stable transfer function matrix. As in the preceding schemes, the adaptive control strategies has close ties to the ability to separate the known functions from the unknown constant parameters. We use the expression given above to define

Z φ = H ( q ) [ q ¨ d + K ( s ) e q ] + V ( q , q ˙ ) q ˙ n + 1 s K ( s ) e q + τ g ( q ) ,

where Z is a known ( n × r ) regression matrix and φ is a vector of unknown system parameters in the adaptive context. It is important to note that the above can be arranged such that Z and r do not depend on the measurement of the joint acceleration q ¨ . The adaptive control scheme given here is called the passivity approach because the mapping of - r Z φ ̃ is constructed to be a passive mapping. That is, we develop an adaptive law such that

0 t - r T ( σ ) Z ( σ ) φ ̃ ( σ ) d σ - β
(8.97)

is satisfied for all time and for some positive scalar constant β. For this class of adaptive controllers, the control input is given by

τ = Z φ ^ + K D r ,
(8.98)

Detailed analysis of stability is given in [8.44].

Remarks 8.4

  • If K ( s ) is selected such that H ( s ) has a relative degree of one, Z and r will not depend on q ¨ .

  • Many types of control schemes can be generated from the adaptive passive control approach by selected different transfer function matrices K ( s ) in the definition of r.

  • Note that, by defining K ( s ) = s Λ such that F ( s ) = ( s I n + Λ ) - 1 , we have the control input

    τ = Z φ ^ - K D r ,

    with

    Z φ ^ = H ^ ( q ) ( q ¨ d + Λ e ˙ q ) + C ^ ( q , q ˙ ) ( q ˙ d + Λ e q ) + τ ^ g ( q ) .

    The adaptive law may be chosen as

    φ ^ ˙ = Γ Z T ( e ˙ q + Λ e q )

    to satisfy the condition of passive mapping. This indicates that adaptive inertia-related control can be viewed as a special case of adaptive passive control.

7.4 Adaptive Control with Desired Compensation

In order to implement the adaptive control scheme, one needs to calculate the elements of Y ( q , q ˙ , q ¨ ) in real time. However, this procedure may be excessively time consuming since it involves computations with highly nonlinear functions of joint position and velocity. Consequently, the real-time implementation of such a scheme is rather difficult. To overcome this difficulty, the adaptive control with desired compensation was proposed and is discussed here. In other words, the variables q, q ˙ , and q ¨ are replaced with the desired ones, namely, qd, q ˙ d , and q ¨ d . Since the desired quantities are known in advance, all their corresponding calculations can be performed offline, which renders real-time implementation more plausible. Let us consider the control input

τ = Y ( q d , q ˙ d , q ¨ d ) a ^ + k a s + k p e q + k n e q 2 s ,
(8.99)

where the positive constants ka, kp, and kn are sufficiently large, and the auxiliary signal s is defined as s = e ˙ q + e q . The adaptive law is considered as

a ^ ˙ = - Γ Y T ( q d , q ˙ d , q ¨ d ) s .
(8.100)

It is worth noting that the desired compensation is adopted in both the control and adaptive laws such that the computational load can be drastically reduced. For the sake of this analysis, we note that

Y ( q , q ˙ , q ¨ ) a - Y ( q d , q ˙ d , q ¨ d ) a ^ ζ 1 e q + ζ 2 e q 2 + ζ 3 s + ζ 4 s e q ,

where ζ1, ζ2, ζ3, and ζ4 are positive constants. In order to achieve trajectory tracking, it is required that

k a > ζ 2 + ζ 4 , k p > ζ 1 2 + ζ 2 4 , k v > ζ 1 2 + ζ 3 + ζ 2 4 ,

(i. e., the gains ka, kp, and kv must be sufficiently large). The convergence of the tracking error to zero with boundedness on all internal signals can be proved through application of Lyapunov stability theory with the following Lyapunov-like function

V = 1 2 s T H ( q ) s + 1 2 k p e q T e q + 1 2 a ̃ T Γ - 1 a ̃ ,
(8.101)

whose time derivative along the trajectories of the closed-loop system can be derived as

V ˙ - x T Q x ,
(8.102)

where

x = e q s , Q = k p - ζ 2 4 - ζ 1 2 - ζ 1 2 k v - ζ 3 - ζ 4 4 .

Detailed stability analysis can be found in [8.45].

7.5 Summary

Since the computed-torque control suffers from parametric uncertainty, a variety of adaptive control schemes have been proposed. Firstly, we have presented an adaptive control scheme based on computed-torque control. Then, in order to overcome the mentioned drawbacks such as the measurability of the joint acceleration and the invertibility of the estimated inertia matrix, we presented an alternative adaptive control scheme that is free of these drawbacks. Recently, to incorporate a physics viewpoint into control, adaptive passivity-based control has become popular, and hence is introduced and discussed here. Finally, to reduce the computational load of the adaptive schemes, we presented an adaptive control with desired compensation.

7.5.1 Further Reading

A computationally very fast scheme dealing with adaptive control of rigid manipulators was presented in [8.46]. The stability analysis was completed by assuming that the joint dynamics are decoupled, i. e., that each joint is considered as an independent second-order linear system. A decentralized high-order adaptive variable-structure control is discussed in [8.47], the proposed scheme makes both position and velocity tracking errors of robot manipulators globally converge to zero asymptotically while allowing all signals in closed-loop systems to be bounded without the information of manipulator parameters. Other pioneering works in the field can be found, for example, in [8.48, 8.49]; although none of the fundamental dynamic model properties are used, the complete dynamics are taken into account, but the control input is discontinuous and may lead to chattering. Positive definiteness of the inertia matrix is explicitly used in [8.50], although it was assumed that some time-varying quantities remain constant during the adaptation. It is interesting to note that all of these schemes were based on the concept of model reference adaptive control (GlossaryTerm

MRAC

) developed in [8.51] for linear systems. Therefore, they are conceptually very different from the truly nonlinear schemes presented in this section.

A passive-based modified version of the least-squares estimation scheme has been proposed in [8.52] and [8.53], which guaranteed closed-loop stability of the scheme. Other schemes can be found in [8.54], where no use is made of the skew-symmetry property, and in [8.55], where the recursive Newton–Euler formulations is used instead of the Lagrange formulation to derive the manipulator dynamics, and thus computation is simplified to facilitate practical implementation.

Even though adaptive control provides a solution to the problem of parametric uncertainty, the robustness of adaptive controllers remains a topic of great interest in the field. Indeed, measurement noise or unmodeled dynamics (e. g., flexibility) may result in unbounded closed-loop signals. In particular, the estimated parameters may diverge; this is a well-known phenomenon in adaptive control and is called parameter drift. Solutions inspired from the adaptive control of linear systems have been studied [8.56, 8.57], where a modified estimation ensures boundedness of the estimates. In [8.58], the controller in [8.32] is modified to enhance robustness.

8 Optimal and Robust Control

Given a nonlinear system, such as robotic manipulators, one can develop many stabilizing controls [8.29, 8.41]. In other words, the stability of the control system cannot determine a unique controller. It is natural that one seeks an optimal controller among the many stable ones. However, the design of an optimal controller is possible provided that a rather exact information on the target system is available, such as an exact system model [8.34, 8.59]. In the presence of discrepancy between the real system and its mathematical model, a designed optimal controller is no longer optimal, and may even end up being instable in the actual system. Generally speaking, the optimal control design framework is not the best one to deal with system uncertainty. To handle system uncertainty from the control design stage, a robust control design framework is necessary [8.60]. One of main objectives of robust control is to keep the controlled system stable even in presence of uncertainties in the mathematical model, unmodeled dynamics, and the like.

Let us consider an affine nonlinear system described by nonlinear time-varying differential equation in the state x = ( x 1 , x 2 , , x n ) T R n

x ˙ ( t ) = f ( x , t ) + G ( x , t ) u + P ( x , t ) w ,
(8.103)

where u R m is the control input, and w R w is the disturbance. Without disturbances or unmodeled dynamics, the system simplifies to

x ˙ ( t ) = f ( x , t ) + G ( x , t ) u .
(8.104)

Actually, there are many kinds of methods describing the nonlinear system according to the objective of control [8.1, 8.16, 8.21, 8.23, 8.34, 8.54].

8.1 Quadratic Optimal Control

Every optimal controller is based on its own cost function [8.61, 8.62]. One can define a cost function as [8.63, 8.64]

z = H ( x , t ) x + K ( x , t ) u ,

such that H T ( x , t ) K ( x , t ) = 0 , K T ( x , t ) K ( x , t ) = R ( x , t ) > 0 , and H T ( x , t ) H ( x , t ) = Q ( x , t ) > 0 . Then, we have

1 2 z T z = 1 2 x T Q ( x , t ) x + 1 2 u T R ( x , t ) u .

The quadratic optimal control for the system (8.104) is found by solving, for a first order differentiable positive-definite function V ( x , t ) , the Hamilton–Jacobi–Bellman (GlossaryTerm

HJB

) equation [8.34, 8.59]

0 = HJB ( x , t ; V ) = V t ( x , t ) + V x ( x , t ) f ( x , t ) - 1 2 V x ( x , t ) G ( x , t ) R - 1 ( x , t ) G T ( x , t ) V x T ( x , t ) + 1 2 Q ( x , t ) ,

where V t = V t and V x = V x T . Then the quadratic optimal control is defined by

u = - R - 1 ( x , t ) G T ( x , t ) V x T ( x , t ) .
(8.105)

Note that the HJB equation is a nonlinear second-order partial differential equation in V ( x , t ) .

Unlike the aforementioned optimal control problem, the so-called inverse quadratic optimal control problem is to find a set of Q ( x , t ) and R ( x , t ) for which the HJB equation has a solution V ( x , t ) . Then the inverse quadratic optimal control is defined by (8.105).

8.2 Nonlinear H Control

When disturbances are not negligible, one can deal with their effect such that

0 t z T ( x , τ ) z ( x , τ ) d τ γ 2 0 t w T w d τ ,
(8.106)

where γ > 0 specifies the L2-gain of the closed-loop system from the disturbance input w to the cost variable z. This is called the L2-gain attenuation requirement [8.63, 8.64, 8.65]. One systematic way to design an optimal and robust control is given by the nonlinear H optimal control. Let γ > 0 be given, by solving the following equation

HJI γ ( x , t ; V ) = V t ( x , t ) + V x ( x , t ) f ( x , t ) - 1 2 V x ( x , t ) { G ( x , t ) R - 1 ( x , t ) G T ( x , t ) - γ - 2 P ( x , t ) P T ( x , t ) } V x T ( x , t ) + 1 2 Q ( x , t ) 0 ,
(8.107)

then the control is defined by

u = - R - 1 ( x , t ) G T ( x , t ) V x T ( x , t ) .
(8.108)

The partial differential inequality (8.107) is called the Hamilton–Jacobi–Isaac (GlossaryTerm

HJI

) inequality. Then one can define the inverse nonlinear H optimal control problem that finds a set of Q ( x , t ) and R ( x , t ) such that the L2-gain requirement is achieved for a prescribed L2-gain γ [8.66].

Two things deserve further comment. The first is that the L2-gain requirement is only valid for disturbance signals w whose L2-norm is bounded. The second is that H optimal control is not uniquely defined. Hence, one can choose a quadratic optimal among many H optimal controllers. Precisely speaking, the control (8.108) should be called H suboptimal control, since the desired L2-gain is prescribed a priori. A true H optimal control is to find a minimal value of γ, such that the L2-gain requirement is achieved.

8.3 Passivity-Based Design of Nonlinear  H  Control

There are many methodologies for the design of optimal and/or robust controls. Among these, passivity-based controls can take full advantage of the properties described above [8.31]. They consist of two parts: one coming from the reference motion compensation while preserving the passivity of the system, and the other to achieve stability, robustness, and/or optimality [8.66, 8.67].

Let us suppose that the dynamic parameters are identified as H ^ ( q ) , C ^ ( q , q ˙ ) , and τ ^ g ( q ) , whose counterparts are H ( q ) , C ( q , q ˙ ) , and τ g ( q ) , respectively. Then, passivity-based control generates the following tracking control laws

τ = H ^ ( q ) q ¨ ref + C ^ ( q , q ˙ ) q ˙ ref + τ ^ g ( q ) - u ,
(8.109)

where q ¨ ref is the reference acceleration defined by

q ¨ ref = q ¨ d + K V e ˙ q + K P e q ,
(8.110)

where K V = diag { k V , i } > 0 and K P = diag { k P , i } > 0 . Two parameters are involved in generating the reference acceleration. Sometimes the following alternative method can be adopted

q ¨ ref = q ¨ d + K V e ˙ q .

This reduces the order of the closed-loop system because the state x = ( e q T , e ˙ q T ) T is sufficient for the system description, while the definition of (8.110) requires the state x = ( e q T , e q T , e ˙ q T ) T .

In Fig. 8.7, the closed-loop dynamics under the control is given by

H ( q ) e ¨ ref + C ( q , q ˙ ) e ˙ ref = u + w ,
(8.111)

where

e ¨ ref = e ¨ q + K V e ˙ q + K P e q , e ˙ ref = e ˙ q + K V e q + K P e q .

If d ( t ) = 0 and H ^ = H , C ^ = C , τ ^ g = τ g , then w = 0 . Otherwise, the disturbance is defined as

w = H ̃ ( q ) q ¨ ref + C ̃ ( q , q ˙ ) q ˙ ref + τ ̃ g ( q ) + d ( t ) ,
(8.112)

where H ̃ = H - H ^ , C ̃ = C - C ^ , and τ ̃ g = τ ^ g - τ g . It is of particular interest that the system (8.111) defines a passive mapping between u + w and e ˙ ref .

Fig. 8.7
figure 7

The closed-loop system according to (8.111)

According to the manner in which the auxiliary control input u is specified, passivity-based control can achieve stability, robustness, and/or optimality (Fig. 8.7).

8.4 A Solution to Inverse Nonlinear  H  Control

Let us define the auxiliary control input by the reference-error feedback

u = - α R - 1 ( x , t ) e ˙ ref ,
(8.113)

where α > 1 is arbitrary. Then, the control provides the inverse nonlinear H optimality.

Theorem 8.1 Inverse Nonlinear H Optimality [8.66]

Let the reference acceleration generation gain matrices KV and KP satisfy

K V 2 > 2 K P .
(8.114)

Then for a given γ > 0, the reference error feedback

u = - K e ˙ ref = - K e ˙ q + K V e q + K P e q
(8.115)

satisfies the L2-gain attenuation requirement for

Q = K P 2 K γ 0 0 0 ( K V 2 - 2 K P ) K γ 0 0 0 K γ ,
(8.116)
R = K - 1 ,
(8.117)

provided that

K γ = K - 1 γ 2 I > 0 .
(8.118)

Given γ, one can set K = α 1 γ 2 I for α > 1. This yields K γ = ( α - 1 ) 1 γ 2 I .

When the inertia matrix is identified as a diagonal constant matrix such as H ^ = diag { m ^ i } , one should set C ^ = 0 . In addition, one can set τ ^ g = 0 . Then this results in a decoupled PID control of the form

τ i = m ^ i q ¨ d , i + k V , i e ˙ q , i + k P , i e q , i + α 1 γ 2 e ˙ q , i + k V , i e q , i + k P , i e q , i

for α > 1, which can be rewritten as

τ i = m ^ i q ¨ d , i + m ^ i k V , i + α 1 γ 2 e ˙ q , i + m ^ i k P , i + α k V , i γ 2 e q , i + α k P , i γ 2 e q , i .
(8.119)

This leads to a PID control with the desired acceleration feedforward [8.68] given by

τ i = m ^ i q ¨ d , i + k V , i * e ˙ q , i + k P , i * e q , i + k I , i * e q , i ,
(8.120a)

where

k V , i * = m ^ i k V , i + α 1 γ 2 ,
(8.120b)
k P , i * = m ^ i k P , i + α k V , i γ 2 ,
(8.120c)
k I , i * = α k P , i γ 2 .
(8.120d)

9 Trajectory Generation and Planning

This section deals with the problem of reference trajectory generation, that is, the computation of desired position, velocity, acceleration and/or force/torque signals that are used as input values for the robot motion controllers introduced in Sects 8.38.8.

9.1 Geometric Paths and Trajectories

9.1.1 Path Planning

A path is a geometric representation of a plan to move from a start to a target pose. The task of planning is to find a collision-free path among a collection of static and dynamic obstacles. Path planning can also include the consideration of dynamic constraints such as workspace boundaries, maximum velocities, maximum accelerations, and maximum jerks. We distinguish between online and offline path planning algorithms. Offline planned paths are static and calculated prior to execution. Online methods require algorithms that meet real-time constraints (i. e., algorithms that do not exceed a determinable worst-case computation time) to enable path (re-)calculations and/or adaptations during the robot motions in order to react to and interact with dynamic environments. This means that a robot moves along a path that has not necessarily been computed completely, and which may change during the movement. Details about path planning concepts are described in Chap. 7, in Parts D and E, and specifically in Chap. 47.

9.1.2 Trajectory Planning

A trajectory is more than a path: It also includes velocities, accelerations, and/or jerks along a path ( ). A common method is computing trajectories for a priori specified paths, which fulfill a certain criterion (e. g., minimum execution time). We distinguish between online and offline trajectory planning methods. An offline calculated trajectory cannot be influenced during its execution, while online trajectory planning methods can (re-)calculate and/or adapt robot motions behavior during the movement. The reasons for this (re-)calculation and/or adaptation can vary: improvement of accuracy, better utilization of currently available dynamics, reaction to and interaction with a dynamic environment, or reaction to (sensor) events. Besides the distinction between online and offline methods, we can further distinguish between (1) one-dimensional (GlossaryTerm

1-D

) and multi-dimensional trajectories and (2) single-point and multi-point trajectories. Multi-point trajectories typically relate to a path.

9.2 Joint Space and Operational Space Trajectories

Depending on the control state space, trajectory generators provide set points for tracking controllers in joint space or in operational space. In either space, a trajectory can be represented in several different ways: cubic splines, quintic splines, higher-order splines, harmonics (sinusoidal functions), exponential functions, Fourier series, and more.

9.2.1 Joint Space Trajectories

Consider the torque control input (8.29)

τ = H ( q ) v + C ( q , q ˙ ) q ˙ + τ g ( q ) ,

and the PD controller (8.30)

v = q ¨ d + K V ( q ˙ d - q ˙ ) + K P ( q d - q ) ,
(8.121)

or PID controller (8.31), respectively, the task of a trajectory generator in joint space coordinates is computing the signals q d ( t ) , q ˙ d ( t ) , and q ¨ d ( t ) . These three signals contain the reference trajectory and are used as input values for the tracking controller.

During nominal operation the joint torques required to execute a trajectory should not exceed joint force/torque limits τ min ( t ) and τ max ( t ) ,

τ min ( t ) τ ( t ) τ max ( t ) t R .
(8.122)

9.2.2 Operational Space Trajectories

Similarly to (8.29), we can also consider trajectories represented by xd, x ˙ d , and x ¨ d for an operational space controller (8.9)

f c = Λ ( q ) μ + Γ ( q , q ˙ ) x ˙ + η ( q ) ,

with a PD control law of

μ = x ¨ d + K V ( x ˙ d - x ˙ ) + K P ( x d - x ) .
(8.123)

With the transformation into joint space using the inverse of (8.8), the operational space trajectory generator must assure that the limits given in (8.122) are not violated. It is the responsibility of the path planner (Chap. 7) that all points along the trajectory are in the robot workspace and that start and goal poses can be reached in the same joint configuration. It is the responsibility of the trajectory planner that joint torque and velocity constraints are not violated even in the presence of kinematic singularities.

9.3 Trajectory Representations

9.3.1 Mathematical Representations

Functions for q ¨ d ( t )  (8.121) and x ¨ d  (8.123) can be represented in several ways that are described here.

9.3.1.1 Polynomial Trajectories

One of the simplest ways to represent a robot trajectory is a polynomial function of degree m for each joint i { 1 , , n }

q i ( t ) = a i , 0 + a i , 1 t + a i , 2 t 2 + + a i , m t m ,
(8.124)

so that q ( t ) can be composed (or x ( t ) in operational space, respectively). In the simplest case, cubic polynomials are used, which, however, leads to non-steady acceleration signals with infinite jerks. Quintic and higher-order polynomials allow for steady acceleration signals as well as arbitrary position, velocity, and acceleration vectors and the beginning and at the end of the trajectory. To determine the coefficients a i , j ( i , j ) { 1 , , n } × { 0 , , m } of (8.124), the execution time ttrgt, at which the target state will be reached needs to be known. The left part of Fig. 8.8a shows a quintic trajectory for three DOFs starting at t 0 = 0 s with an execution time of t trgt = 2.5 s . To connect a trajectory segment to preceding and succeeding segments, the following six constraints need to be satisfied for all n joints

q i ( t 0 ) = q i , start = a i , 0 q i ( t trgt ) = q i , trgt = a i , 0 + a i , 1 t trgt + a i , 2 t trgt 2 + a i , 3 t trgt 3 + a i , 4 t trgt 4 + a i , 5 t trgt 5 q ˙ i ( t 0 ) = q ˙ i , 0 = a i , 1 q ˙ i ( t trgt ) = q ˙ i , trgt = a i , 1 + 2 a i , 2 t trgt + 3 a i , 3 t trgt 2 + 4 a i , 4 t trgt 3 + 5 a i , 5 t trgt 4 q ¨ i ( t 0 ) = q ¨ i , 0 = 2 a i , 2 q ¨ i ( t trgt ) = q ¨ i , trgt = 2 a i , 2 + 6 a i , 3 t trgt + 12 a i , 4 t trgt 2 + 20 a i , 5 t trgt 3 .

A unique closed-form solution can be computed, so that all polynomial coefficients a i , j ( i , j ) { 1 , , n } × { 0 , ,  5 } can be determined for one trajectory segment.

Fig. 8.8a,b
figure 8

Two sample trajectories for a three-DOF robot (n = 3). The trajectory in (a) is represented by quintic splines, and the trajectory in (b) by piecewise polynomials

9.3.1.2 Piecewise Polynomials

Polynomials of different degrees can be concatenated to represent a trajectory between an initial state ( q 0 , q ˙ 0 , q ¨ 0 ) and a target state ( q trgt , q ˙ trgt , q ¨ trgt ) . For instance, the classical double-S velocity profile [8.69] with trapezoidal acceleration and deceleration profiles and a cruise-velocity segment in the middle consists of seven polynomials of degrees 3-2-3-1-3-2-3 (m in (8.124)). The right part of Fig. 8.8 shows a trajectory represented by piecewise polynomials. To compute time-optimal trajectories under purely kinematic constraints (e. g., q ˙ max , q ¨ max , q ˙˙˙ max , etc.), piecewise polynomials are used, because they allow always using one signal at its kinematic limit (Fig. 8.8b and [8.70]).

9.3.1.3 Trigonometric Trajectories

Similarly to (8.124), trigonometric functions can be used to represent harmonic, cycloidal, and elliptic trajectories [8.71, 8.72]. A simple example for a harmonic trajectory for one joint i is

q i ( t ) = q i , trgt - q i , 0 2 1 - cos π t - t 0 t trgt - t 0 + q i , 0 .
(8.125)

While any order of derivatives of trigonometric functions is continuous, they might be discontinuous at t0 and ttrgt.

9.3.1.4 Other Representations

Exponential Trajectories and Fourier Series Expansions [8.72] are particularly suited to minimize natural vibrations on robot mechanisms introduced by reference trajectories.

9.3.2 Trajectories and Paths

To draw the connection to Chap. 7 and Parts D and E, trajectories and paths are often tightly coupled.

9.3.2.1 Trajectories Along Predefined Paths

A path in joint space can be described by a function q ( s ( t ) ) with s [ t 0 , t trgt ] , where the start configuration of the path is q ( t 0 ) and the target configuration is q ( t trgt ) . To move a robot along the path, an appropriate function s(t) needs to be computed that does not violate any of the kinematic and dynamic constraints [8.73, 8.74, 8.75]. If a path is given in operational space, x ( s ( t ) ) can be mapped to q ( t ) (Sect. 8.2).

9.3.2.2 Multi-Dimensional Trajectories

Instead of using a one-dimensional function s(t) to parameterize a path segment, trajectories can also be described by individual functions for each DOF i to represent q ( s ( t ) ) or x ( s ( t ) ) , respectively. To connect two arbitrary states, the signals for each individual degree of freedom need to be time-synchronized [8.70], so that all DOFs reach their target state of motion at the very same instant. Those trajectories may also be phase-synchronized [8.76], so that the trajectories of all DOFs are derived from a one master DOF and only scaled by a factor to achieve homothety [8.77]. The two trajectories in Fig. 8.8 are time-synchronized but not phase-synchronized.

9.3.2.3 Multi-Point Trajectories

If instead of an entirely defined geometric path or a motion to a single way point, an entire series of geometric way points is given, the trajectory that connects all way points in a given state space needs to be computed. Trajectory segments between two way points can be represented with any of the above mentioned representations as long as the position signal and its derivatives up an appropriate order are continuous (at least C1 continuous). Splines, B-splines, or Bezier splines are used to generate either a reference trajectory or a geometric path, which then can be parameterized with a function s(t).

9.4 Trajectory Planning Algorithms

The following part provides an overview of online and offline trajectory planning concepts.

9.4.1 Constraints

Constraints for trajectory planners can manifold:

  • Kinematic: maximum velocities, accelerations, jerks, etc. and workspace space limits

  • Dynamic: maximum joint or actuator forces and/or torques

  • Geometric: no collisions with static and dynamic objects in the workspace

  • Temporal: reaching a state within a given time interval or at a given time.

These and other constraints may have to be taken into account at the same time. Depending on the robot and the task, additional optimization criteria may be considered (e. g., time-optimality, minimum-jerk, maximum distance to workspace boundaries, minimum energy).

9.4.2 Offline Trajectory Planning

Kahn and Roth [8.78] showed results using optimal, linear control theory to achieve a near-time-optimal solution for linearized manipulators. The resulting trajectories are jerk-limited and lead to smaller trajectory-following errors and to less excitation of structural natural frequencies in the system.

The work of Brady [8.79] introduced several techniques of trajectory planning in joint space and Paul [8.80] and Taylor [8.81] published works about the planning of trajectories in Cartesian space in parallel to Brady. Lin et al. [8.82] published another purely kinematic approach as did Castain and Paul [8.69].

Hollerbach [8.83] first introduced the consideration of the nonlinear inverse robot dynamics for the generation of manipulator trajectories.

During the middle of the 1980s, three groups developed techniques for time-optimal trajectory planning for arbitrarily specified paths: Bobrow [8.73], Shin and McKay [8.74], and Pfeiffer and Johanni [8.75]. Trajectories are composed of three curves: the maximum acceleration curve, the maximum velocity curve, and the maximum deceleration curve. The proposed algorithms find the intersection points of these three curves.

These algorithms have become the fundament for many follow-up works: Kyriakopoulos and Sridis [8.84] added minimum-jerk criteria; Slotine and Yang abandoned the computationally expensive calculation of the maximum velocity curve [8.85]; Shiller and Lu added methods for handling dynamic singularities [8.86]; Fiorini and Shiller extended the algorithm for known dynamic environments with moving obstacles [8.87].

9.4.3 Online Trajectory Planning

An online modification of a planned trajectory may have several reasons: (i) The trajectory becomes adapted in order to improve the accuracy with a path specified beforehand; (ii) The robotic system reacts on sensor signals and/or events that cannot be predicted beforehand, because the robot acts in a (partly) unknown and dynamic environment.

9.4.3.1 Improving Path Accuracy

All previously described off-line trajectory planning methods assume a dynamic model that describes the behavior of the real robot exactly. In practice, this is often not the case, and some robot parameters are only estimated, some dynamic effects remain unmodeled, and system parameters may change during operation. If this is the case, the resulting robot motion is not time-optimal anymore and/or the maximum actuator forces and/or torques are exceeded, which leads to an undesired difference between the specified and the executed path.

Dahl and Nielsen [8.88] extended [8.73, 8.74, 8.75] by adapting the acceleration along the path, so that the underlying trajectory-following controller becomes adapted depending on the current state of motion. The approaches of Cao et al. [8.89, 8.90] use cubic splines to generate smooth paths in joint space with time-optimal trajectories. Constantinescu and Croft [8.91] suggest a further improvement to the approach of [8.86] with objective to limit the derivative of actuator forces/torques. Macfarlane and Croft extended this approach further by adding jerk limitations to quintic splines (Fig. 8.8) [8.92].

9.4.4 Sensor-Based Trajectory Adaptation

The last paragraph presented an overview of online trajectory generation methods for improving the path accuracy, while this one focuses on the online consideration of sensor signals, for instance, for the purpose of collision avoidance ( , ) or switching between controllers or control gains ( , ).

In 1988, Andersson presented an online trajectory planning for a Ping-Pong-playing PUMA 260 manipulator that computes parameterized quintic polynomials [8.93, 8.94]. Based on [8.73, 8.74, 8.75], Lloyd and Hayward proposed a technique to transition between two different trajectory segments [8.95] using a transition window [8.81]. Ahn et al. introduced a method to connect two arbitrary motion states online, which does not take into account kinematic or dynamic constraints [8.96]. Broquère et al., Haschke et al., and Kröger extended this approach for multi-dimensional trajectories, so that kinematic constraints are taken into account [8.70, 8.97, 8.98].

9.4.5 Further Reading

Overviews of the domain of robot reference trajectory generation can found in the textbooks of Biagiotti and Melchiorri [8.72], Craig [8.99], Fu et al. [8.100], and Spong et al. [8.101].

10 Digital Implementation

Most controllers introduced in the previous sections are digitally implemented on microprocessors. In this section basic but essential practical issues related to their computer implementation are discussed. When the controller is implemented on a computer control system, the analog inputs are read and the outputs are set with a certain sampling period. This is a drawback compared to analog implementations, since sampling introduces time delays into the control loop. Figure 8.9 shows the overall block diagram of control system with a boxed digital implementation part. When a digital computer is used to implement a control law, it is convenient to divide coding sequence in the interrupt routine into four process routines, as shown in Fig. 8.10. Reading the input signal from sensors and writing the control signal to digital-to-analog (GlossaryTerm

D/A

) converters synchronized at the correct frequency is very important. Therefore, these processes are located in the first routine. After saving counter values and extracting D/A values, which are already calculated one step before, the next routine produces reference values. Control routines with filters follow and produce scalar or vector control outputs. Finally, the user interface for checking parameter values is made and will be used for tuning and debugging.

Fig. 8.9
figure 9

Digital implementation of system control

Fig. 8.10
figure 10

The sequence in the interrupt routine for digital control

10.1 Z-Transform for Motion Control Implementation

Continuous-time systems are transformed into discrete-time systems by using the Z-transform. A discrete-time system is used to obtain a mathematical model that gives the behavior of a physical process at the sampling points, although the physical process is still a continuous-time system. A Laplace transform is used for the analysis of control system in the s-domain. In most cases, the design of controllers and filters are done using tools in the s-domain. In order to realize those results in program code, understanding the Z-transform is essential. All controllers and filters designed in the s-domain can be easily translated to a program code through a Z-transform because it has the form of digitized difference sequences.

A PID controller is used as an example. In transfer function form, this controller has the basic structure

Y ( s ) E ( s ) = K P + K I s + s K V .
(8.126)

There are several methods for transformation from the frequency domain to the discrete domain. For stability conservation, backward Euler and Tustin algorithms are often used. Though the Tustin algorithm is known as the more exact one, the backward Euler algorithm is utilized in the following procedure.

After substituting the backward Euler equation into (8.126),

s 1 - z - 1 T ,

the following discrete form is produced

Y ( z ) E ( z ) = α + β z - 1 + γ z - 2 T ( 1 - z - 1 ) ,
(8.127)

where

α = K I T 2 + K P T + K V , β = - K P T - 2 K V , γ = K V .

Sometimes a differentiator s in the PID controller makes the implementation infeasible when the measurement noise is severe. One can remedy the controller (8.126) by attaching a lowpass filter with filter time constant σ

Y ( s ) E ( s ) = K P + K I s + s σ s + 1 K V .
(8.128)

Again, substituting the backward Euler equation into (8.128) produces

Y ( z ) E ( z ) = α + β z - 1 + γ z - 2 1 - δ z - 1 - ψ z - 2 ,
(8.129)

where

α = K P + K I T + K V σ + T , β = - ( 2 σ + T ) K P + σ T K I + 2 K V σ + T , γ = σ K P + K V σ + T , δ = 2 σ + T σ + T , ψ = - σ σ + T ,

in which the filter time constant σ is determined from a cutoff frequency fc[Hz] for removing noises such as σ = 1 2 π f c .

10.2 Digital Control for Coding

Inverse Z-transform produces a difference equation for digital control. Furthermore the difference equation can be directly converted into the control program code. Since the inverse Z-transform of Y(z) is yk and z−1 implies the previous sample time, z - 1 Y ( z ) = y k - 1 and z - 2 Y ( z ) = y k - 2 .

Now, the PID controller expressed by (8.127) is rearranged using the difference equation

T ( y k - y k - 1 ) = α e k + β e k - 1 + γ e k - 2 , y k - y k - 1 = 1 T ( α e k + β e k - 1 + γ e k - 2 ) .
(8.130)

For pratical use, the PID controller can be directly coded in the program as follows

y k = K P , c e k + K V , c e k v + K I , c e k i ,

where

e k = p k , desired - p k , e k v = v k , desired - v k = ( p k , desired - p k - 1 , desired ) - ( p k - p k - 1 ) = e k - e k - 1 , e k i = e k - 1 i + e k = j = 0 k e k ,

in which pk is the present position, vk is the present velocity, desired means reference to be followed, and c means coded form for digitial control. Now let us obtain the difference between the present control output and the previous one

y k - y k - 1 = [ K P , c e k - K P , c e k - 1 ] + [ K V , c ( e k - e k - 1 ) - K V , c ( e k - 1 - e k - 2 ) ] + [ K I , c e k i - K I , c e k - 1 i ] = ( K P , c + K V , c + K I , c ) e k - ( K P , c + 2 K V , c ) e k - 1 + K V , c e k - 2 .
(8.131)

Comparing the parameters in (8.130) and (8.131), one obtains

α T = K P + K V T + K I T = ( K P , c + K V , c + K I , c ) , β T = - K P - 2 K V T = - ( K P , c + 2 K V , c ) , γ T = K V T = K V , c ,

which shows that there is a relation between the designed and coded forms of the gains

K P , c = K P , K V , c = K V T , K I , c = K I T .
(8.132)

As the sampling frequency is increased in the same system, the coded KV gain should be increased and the coded KI gain should be decreased. Using this method, the designed controller can be coded in a digital signal processor (GlossaryTerm

DSP

) or microprocessor. However, sufficient analysis and simulation for control algorithms should be performed beforehand to obtain successful control system performance.

In addition, the PID controller with lowpass filter (8.129) can be implemented as

y k - δ y k - 1 - ψ y k - 2 = α e k + β e k - 1 + γ e k - 2 , y k = δ y k - 1 + ψ y k - 2 + α e k + β e k - 1 + γ e k - 2 .
(8.133)

Using the same procedures, one can arrive at the similar control program code for digital control.

10.2.1 PID Control Experiment (Multimedia)

According as the gains change, the performance variations of PID controller implemented in the digital control system are shown in the multimedia source to help readers’ understanding .

11 Learning Control

Since many robotic applications, such as pick-and-place operations, paintings, and circuit-board assembly, involve repetitive motions, it is natural to consider the use of data gathered in previous cycles to try to improve the performance of the manipulator in subsequent cycles. This is the basic idea of repetitive control or learning control. Consider the robot model given in Sect. 8.1 and suppose that one is given a desired joint trajectory q d ( t ) on a finite time interval 0 t T . The reference trajectory qd is used in repeated trails of the manipulator, assuming either that the trajectory is periodic, q d ( T ) = q d ( 0 ) , (repetitive control) or that the robot is reinitialized to lie on the desired trajectory at the beginning of each trail (learning control). Hereafter, we use the term learning control to mean either repetitive or learning control.

11.1 Pure P-Type Learning Control

Let τ k be the input torque during the k-th cycle, which produces an output q k ( t ) , 0 t T bnd . Now, let us consider the following set of assumptions:

  • Assumption 1: Every trial ends at a fixed time of duration T bnd > 0 .

  • Assumption 2: Repetition of the initial setting is satisfied.

  • Assumption 3: Invariance of the system dynamics is ensured throughout these repeated trails.

  • Assumption 4: Every output qk can be measured and thus the error signal Δ q k = q k - q d can be utilized in the construction of the next input τ k + 1 .

  • Assumption 5: The dynamics of the robot manipulators is invertible.

The learning control problem is to determine a recursive learning law L

τ k + 1 = L [ τ k ( t ) , Δ q k ( t ) ] , 0 t T bnd ,
(8.134)

where Δ q k ( t ) = q k ( t ) - q d ( t ) , such that Δ q k 0 as k in some suitably defined function norm, . The initial control input can be any control input that produces a stable output, such as PD control. Such learning control schemes are attractive because accurate models of the dynamics need not be known a priori.

Several approaches have been used to generate a suitable learning law L and to prove convergence of the output error. A pure P-type learning law is one of the form

τ k + 1 ( t ) = τ k ( t ) - Φ Δ q k ( t ) ,
(8.135)

and is given this name because the correction term for the input torque at each iteration is proportional to the error Δ q k . Now let τ d be defined by the computed-torque control, i. e.,

τ d ( t ) = H [ q d ( t ) ] q ¨ d ( t ) + C [ q d ( t ) , q ˙ d ( t ) ] q ˙ d ( t ) + τ g [ q d ( t ) ] .
(8.136)

One should recall that the function τ k actually does not need to be computed; it is sufficient to know that it exists. Considering the P-type learning control law, we have

Δ τ k + 1 ( t ) = Δ τ k ( t ) - Φ Δ q k ( t ) ,
(8.137)

where Δ τ k ( t ) = τ k ( t ) - τ d ( t ) , so that

Δ τ k + 1 ( t ) 2 Δ τ k ( t ) 2 - β Φ Δ q k ( t ) 2
(8.138)

provided there exist positive constant λ and β such that

0 T bnd e - λ t Δ q k T Δ τ k ( t ) d t 1 + β 2 Φ Δ q k ( t ) 2
(8.139)

for all k. It then follows from the inequality above that Δ q k 0 in the norm sense as k . Detailed stability analysis of this control scheme is given in [8.102, 8.103].

11.2 P-Type Learning Control with a Forgetting Factor

Although pure P-type learning control achieves the desired goal, several strict assumptions may be not valid in actual implementations, for example, there may be an initial setting error. Furthermore, there may be small but nonrepeatable fluctuations of dynamics. Finally, there may exit a (bounded) measurement noise ξ k such that

Δ q k ( t ) + ξ k ( t ) = [ q k ( t ) + ξ k ( t ) ] - q d ( t ) .
(8.140)

Thus the learning control scheme may fail. In order to enhance the robustness of P-type learning control, a forgetting factor is introduced in the form

τ k + 1 ( t ) = ( 1 - α ) τ k ( t ) + α τ 0 ( t ) - Φ [ Δ q k ( t ) + ξ k ( t ) ] .
(8.141)

The original idea of using a forgetting factor in learning control originated with [8.104].

It has been rigorously proven that P-type learning control with a forgetting factor guarantees convergence to a neighborhood of the desired one of size O ( α ) . Moreover, if the content of a long-term memory is refreshed after every k trials, where k is of O ( 1 / α ) , then the trajectories converge to an ε-neighborhood of the desired control goal. The size of ε is dependent on the magnitude of the initial setting error, the nonrepeatable fluctuations of the dynamics, and the measurement noise. For a detailed stability investigation, please refer to [8.105, 8.106].

11.3 Summary

By applying learning control, the performance of repetitive tasks (such as painting or pick-and-place operation) is improved by utilizing data gathered in the previous cycles. In this section, two learning control schemes were introduced. First, pure P-type learning control and its robustness problem were described. Then P-type learning control with a forgetting factor was presented, enhancing the robustness of learning control.

11.3.1 Further Reading

Rigorous and refined exploration of learning control is first discussed independently in [8.12, 8.2].