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.

Introduction

Robotic manipulation has shown to be a key technology in factory automation. In order for a robot to perform some specific tasks, the robot is required to move according to the commands from a motion controller. Most motion control applications of robot manipulators can be categorized into two main classes. The first is the point-to-point motion control or set-point regulation where the robot is required to move from an initial position to a final desired position in the workspace. Pick-and-place operations are typical examples of the point-to-point motion control applications. Other examples that require set-point control are spot welding and hole drilling. The second type is trajectory tracking applications, such as arc welding, machining, and painting, where the robot has to follow a desired trajectory.

Robot manipulator Robot manipulator consists of rigid links connected by joints. One end of the manipulator is fixed to a base and an end effector or tool is connected to the other end. The vector space in which the joint displacements are defined is often referred to as the joint space, and the coordinates in which the manipulator task of the end effector is specified is referred to as the task space, which can be a Cartesian space or an image space depending on the task requirements. The motion control problem of a robot can be formulated either in the joint space (Kelly et al. 2005) or in the task space (Spong et al. 2006). In the joint-space control methodology, the desired position of the end effector is converted to a corresponding desired joint configuration by solving an inverse kinematic problem, and a feedback control law is designed so that the robot joints follow the desired joint position. To eliminate the problem of solving the inverse kinematics, the robot motion control problem can be directly formulated and designed in task space. A transformation matrix Transformation matrix or Jacobian matrix Jacobian matrix is used to transform the task-space feedback error to joint control inputs.

The most commonly used controllers in industrial applications are PD and PID controllers (Ziegler and Nichols 1942). The main advantages of such controllers are the simplicity and ease of implementation. However, the kinematics and dynamics of a robot manipulator are highly nonlinear with coupling between joints, and hence, the linear control theory cannot be applied directly to design PD or PID controllers for a robot manipulator. By exploring physical properties of the robot dynamics, Takegaki and Arimoto (Takegaki and Arimoto 1981) first showed using Lyapunov method (Slotine and Li 1991) that a simple PD controller with gravity compensation is effective for set-point control of a robot manipulator Robot manipulator. The result was an important landmark in robot control theory. Inspired by the original work (Takegaki and Arimoto 1981), much progress has been made in understanding the robot motion control problem, and various control methods have been developed for a robot manipulator (Arimoto and Miyazaki 1984, 1985; Arimoto et al. 1994; Ortega et al. 1995; Arimoto 1994; Wen and Bayard 1988; Niemeyer and Slotine 1991; Berghuis et al. 1993; Cheah et al. 1998, 2004, 2007, 2010; Cheah 2003; Dixon 2007; Liang et al. 2010; Braganza et al. 2005; Wang and Xie 2009; Garcia-Rodriguez and Parra-Vega 2012; Cheah and Liaw 2005; Kelly 1997; Wang et al. 2007).

This chapter focuses on motion control methods of robot manipulators that were developed based on the Lyapunov method. In particular, several set-point and adaptive tracking controllers are presented in both the joint space and task space, for a robot manipulator with uncertainty. The robot kinematics and dynamics are nonlinear with coupling between joints, and a good understanding of the structure and properties of the models is essential for the design of simple and effective controllers. The dynamics and kinematics of robot manipulators and their basic properties are first introduced in section “Dynamics and Kinematics of Robot Manipulators” and several examples are given to illustrate the properties. The next two sections of this chapter present the standard motion controllers in robotics, which serve as foundation works for the design of most robot controllers based on the Lyapunov method. Section “Set-Point Control by PD Plus Gravity Controller” introduces the set-point controllers based on the PD plus gravity control strategy. Section “Adaptive Control of Robot Manipulators” presents adaptive control methodology for tracking control of robot manipulators. Recent advances in sensing technology has led to the research and development of sensory task-space feedback control laws for robot manipulators. The use of task-space sensory feedback information such as visual information improves the endpoint accuracy in the presence of uncertainty. Section “Approximate Jacobian Set-Point Control” presents the basic task-space sensory feedback control problem of a robot manipulator with kinematic and dynamic uncertainty for set-point control applications. Moreover, the results are extended to deal with uncertain gravitational force. Section “Adaptive Jacobian Tracking Control” presents the adaptive Jacobian controller for task-space sensory feedback tracking control applications. Simulation results are presented in section “Simulation Results.” A brief review of the basic concepts and theories for stability analysis of nonlinear systems is also provided in the Appendix.

Dynamics and Kinematics of Robot Manipulators

In this section, the dynamic and kinematic equations of robot manipulators Robot manipulator are introduced and the properties which constitute the basis of controller design in this chapter are presented.

Dynamic Equation of Robots

For a robot manipulator of n DOF with the joint coordinate q = [q 1,…, q n ]T, the equation of motion using Lagrange approach takes the following form:

$$ {\displaystyle \sum_{j=1}^n{M}_{ij}{\ddot{q}}_j}+{\displaystyle \sum_{j=1}^n{\displaystyle \sum_{k=1}^n{\varGamma}_{ijk}{\dot{q}}_j{\dot{q}}_k+{D}_{ii}(q){\dot{q}}_i+{g}_i(q)}}={u}_i,\kern1em i=1,\dots, n $$
(1)

such that \( {\mathbf{\mathcal{\boldsymbol{\Gamma}}}}_{kji} \) is called the Christoffel symbols and it is defined as

$$ {\mathbf{\mathcal{\boldsymbol{\Gamma}}}}_{ijk}=\frac{1}{2}\left\{\frac{\partial {M}_{ij}(q)}{\partial {q}_k}+\frac{\partial {M}_{ik}(q)}{\partial {q}_j}-\frac{\partial {M}_{kj}(q)}{\partial {q}_i}\right\}. $$
(2)

Equation 1 can be expressed in the following compact form:

$$ M(q)\ddot{q}+C\left(q,\dot{q}\right)\dot{q}+D(q)\dot{q}+g(q)=u $$
(3)

where M(q) ∈ R n×n is the inertia matrix, \( C\left(q,\dot{q}\right) \) is the matrix of Coriolis and centripetal terms, D(q) ∈ R n×n is the matrix of damping coefficients, g(q) ∈ R n denotes the gravitational force, and uR n is the vector of control input. The following example is presented for better understanding of the dynamic equation expressed in Eq. 3.

Example 1

Consider a two-link planar robot manipulator as depicted in Fig. 1.

Fig. 1
figure 1

A two-link robot manipulator

The dynamic equation of the robot is expressed as follows:

$$ \left[\begin{array}{cc}\hfill {M}_{11}\hfill & \hfill {M}_{12}\hfill \\ {}\hfill {M}_{21}\hfill & \hfill {M}_{22}\hfill \end{array}\right]\left[\begin{array}{c}\hfill {\ddot{q}}_1\hfill \\ {}\hfill {\ddot{q}}_2\hfill \end{array}\right]+\left[\begin{array}{cc}\hfill {C}_{11}\hfill & \hfill {C}_{12}\hfill \\ {}\hfill {C}_{21}\hfill & \hfill {C}_{22}\hfill \end{array}\right]\left[\begin{array}{c}\hfill {\dot{q}}_1\hfill \\ {}\hfill {\dot{q}}_2\hfill \end{array}\right]+\left[\begin{array}{cc}\hfill {D}_{11}\hfill & \hfill 0\hfill \\ {}\hfill 0\hfill & \hfill {D}_{22}\hfill \end{array}\right]\left[\begin{array}{c}\hfill {\dot{q}}_1\hfill \\ {}\hfill {\dot{q}}_2\hfill \end{array}\right]+\left[\begin{array}{c}\hfill {g}_1\hfill \\ {}\hfill {g}_2\hfill \end{array}\right]=u $$
(4)

where parameters M ij , C ij , and g i for i, j = 1, 2 are expressed in Appendix 2. Parameters D 11 and D 22 are positive constants that represent damping coefficients for each joint.

Some properties of dynamic equation of robot manipulators expressed by Eq. 3 are as follows:

Property 1

The inertia matrix M(q) is symmetric and positive definite for all qR n.

Property 2

The matrix \( \dot{M}(q)-2C\left(q,\dot{q}\right) \) is skew symmetric so that

$$ {y}^T\left\{\dot{M}(q)-2C\left(q,\dot{q}\right)\right\}y=0\kern1em for\; all\;y\in {R}^n. $$
(5)

To show property 2, the elements of matrix \( C\left(q,\dot{q}\right) \) are obtained by using Eqs. 1 and 2:

$$ {C}_{ij}\left(q,\dot{q}\right)={\displaystyle \sum_{k=1}^n\frac{1}{2}\left\{\frac{\partial {M}_{ij}(q)}{\partial {q}_k}+\frac{\partial {M}_{ik}(q)}{\partial {q}_j}-\frac{\partial {M}_{kj}(q)}{\partial {q}_i}\right\}}{\dot{q}}_k $$
(6)

Therefore, the elements of matrix \( \dot{M}(q)-2C\left(q,\dot{q}\right) \) can be expressed as

$$ \begin{array}{l}{\left(\dot{M}(q)-2C\left(q,\dot{q}\right)\right)}_{ij}={\displaystyle \sum_{k=1}^n\frac{\partial {M}_{ij}(q)}{\partial {q}_k}{\dot{q}}_k-\left\{\frac{\partial {M}_{ij}(q)}{\partial {q}_k}+\frac{\partial {M}_{ik}(q)}{\partial {q}_j}-\frac{\partial {M}_{kj}(q)}{\partial {q}_i}\right\}}{\dot{q}}_k\\ {}={\displaystyle \sum_{k=1}^n\left\{-\frac{\partial {M}_{ik}(q)}{\partial {q}_j}+\frac{\partial {M}_{kj}(q)}{\partial {q}_i}\right\}}{\dot{q}}_k.\end{array} $$

Switching i and j and considering the symmetricity of matrix M(q) yield

$$ \begin{array}{l}{\left(\dot{M}(q)-2C\left(q,\dot{q}\right)\right)}_{ij}=-{\displaystyle \sum_{k=1}^n\left\{-\frac{\partial {M}_{jk}(q)}{\partial {q}_i}+\frac{\partial {M}_{ki}(q)}{\partial {q}_j}\right\}}{\dot{q}}_k\\ {}=-{\left(\dot{M}(q)-2C\left(q,\dot{q}\right)\right)}_{ji},\end{array} $$

which shows that the matrix \( \left(\dot{M}(q)-2C\left(q,\dot{q}\right)\right) \) is skew symmetric.

Property 3

The dynamic equation Eq. 3 can be linearly parameterized with respect to the constant parameters, as follows:

$$ M(q)\ddot{q}+C\left(q,\dot{q}\right)\dot{q}+D(q)\dot{q}+g(q)=Y\left(q,\dot{q},\dot{q},\ddot{q}\right){\theta}_d $$
(7)

where Y(⋅) ∈ R n×p is the known regressor matrix and θ d is the unknown parameter vector.

The following example is presented to illustrate properties 1–3:

Example 2

Consider the two-link robot manipulator depicted in Fig. 1. The inertia matrix is expressed by Eq. 113 in the Appendix. To show the positive definiteness of the inertia matrix, it is sufficient to show that all leading principal minors of the matrix are positive. Hence, the following inequalities must hold:

$$ \left\{\begin{array}{l}I:\kern1em \frac{4}{3}{M}_1{L}_{c1}^2+\frac{4}{3}{M}_2{L}_{c2}^2+{M}_2{L}_1^2+2{M}_2{L}_1{L}_{c2} \cos \left({q}_2\right)>0\hfill \\ {}II:\kern1em \det (M)>0\hfill \end{array}\right.. $$
(8)

For inequality I, the worst case is cos (q 2) = −1; then it gives

$$ \frac{4}{3}{M}_1{L}_{c1}^2+\frac{1}{3}{M}_2{L}_{c2}^2+{M}_2{\left({L}_1-{L}_{c2}\right)}^2>0. $$
(9)

For the second inequality, the determinant of M(q) is computed as follows:

$$ \frac{16}{9}{M}_1{M}_2{L}_{c1}^2{L}_{c2}^2+{M}_2^2{L}_1^2{L}_{c2}^2\left(\frac{4}{3}-{ \cos}^2\left({q}_2\right)\right)>0 $$
(10)

which yields the positive definiteness of the inertia matrix.

To show the skew-symmetric property of the matrix \( \dot{M}(q)-2C\left(q,\dot{q}\right) \), let us form the matrix \( \dot{M}(q) \):

$$ \dot{M}(q)=\left[\begin{array}{cc}\hfill -2{M}_2{L}_1{L}_{c2}{\dot{q}}_2 \sin \left({q}_2\right)\hfill & \hfill -{M}_2{L}_1{L}_{c2}{\dot{q}}_2 \sin \left({q}_2\right)\hfill \\ {}\hfill -{M}_2{L}_1{L}_{c2}{\dot{q}}_2 \sin \left({q}_2\right)\hfill & \kern5em 0\hfill \end{array}\right] $$
(11)

Hence, the matrix \( \dot{M}(q)-2C\left(q,\dot{q}\right) \) can be expressed as

$$ \dot{M}(q)-2C\left(q,\dot{q}\right)=\left[\begin{array}{cc}\hfill 0\hfill & \hfill \varPsi \hfill \\ {}\hfill -\varPsi \hfill & \hfill 0\hfill \end{array}\right] $$
(12)

where \( \varPsi =2{M}_2{L}_1{L}_{c2}{\dot{q}}_1 \sin \left({q}_2\right)+{M}_2{L}_1{L}_{c2}{\dot{q}}_2 \sin \left({q}_2\right) \). It can be seen from Eq. 12 that the matrix \( \dot{M}(q)-2C\left(q,\dot{q}\right) \) is skew symmetric.

To show the property Eq. 3, the elements of known regressor matrix YR (2×7) are given as

$$ \begin{array}{l}{Y}_{11}={\ddot{q}}_1,\kern1em {Y}_{12}={\ddot{q}}_2\\ {}{Y}_{13}=\left(2{\ddot{q}}_1+{\ddot{q}}_2\right) \cos \left({q}_2\right)-\left(2{\dot{q}}_1{\dot{q}}_2+{\dot{q}}_2^2\right) \sin \left({q}_2\right)\\ {}{Y}_{14}={\dot{q}}_1,\kern1em {Y}_{15}=0,\kern1em {Y}_{16}= \cos \left({q}_1\right),\kern1em {Y}_{17}= \cos \left({q}_1+{q}_2\right)\\ {}{Y}_{21}=0,\kern1em {Y}_{22}={\ddot{q}}_1+{\ddot{q}}_2\\ {}{Y}_{23}={\ddot{q}}_1 \cos \left({q}_2\right)+{\dot{q}}_1^2 \sin \left({q}_2\right)\\ {}{Y}_{24}=0,\kern1em {Y}_{25}={\dot{q}}_2,\kern1em {Y}_{26}=0,\kern1em {Y}_{27}= \cos \left({q}_1+{q}_2\right),\end{array} $$

and the unknown parameter vector is expressed as follows:

$$ {\theta}_d=\left[\begin{array}{c}\hfill \frac{4}{3}{M}_1{L}_{c1}^2+\frac{4}{3}{M}_2{L}_{c2}^2+{M}_2{L}_1^2\hfill \\ {}\hfill \frac{4}{3}{M}_2{L}_{c2}^2\hfill \\ {}\hfill {M}_2{L}_1{L}_{c2}\hfill \\ {}\hfill {D}_{11}\hfill \\ {}\hfill {D}_{22}\hfill \\ {}\hfill \left({M}_1{L}_{c1}+{M}_2{L}_1\right)g\hfill \\ {}\hfill {M}_2{L}_{c2}g\hfill \end{array}\right]. $$

Kinematic Equation Kinematic equation of Robots

The kinematic model represents the relationship between the joint angles and the end-effector position. Hence, the kinematic model connects the task space to joint space as follows:

$$ x=h(q) $$
(13)

where xR m is the task-space vector and h(⋅) ∈ R nR m is a transformation describing the relation between the joint space and the task space. The relationship between task-space and joint-space velocities is given as

$$ \dot{x}=J(q)\dot{q} $$
(14)

where J(q) ∈ R m×n is the which provides a transformation from the joint space to the task space.

Remark 1

The task-space vector can either be defined in a Cartesian space or an image space. If cameras are used to measure the end-effector position, the task space is defined as an image space. Let x denote the vector of image feature parameters; the image velocity vector \( \dot{x} \) is related to the joint velocity vector \( \dot{q} \) as

$$ \dot{x}={J}_I(q){J}_e(q)\dot{q} $$
(15)

where J I (q) is the image Jacobian matrix from the Cartesian space to the image space (Hutchinson et al. 1996) and J e (q) is the manipulator Jacobian matrix from the joint space to the Cartesian space. Therefore, the overall Jacobian from joint space to task space is J(q) = J I (q)J e (q). If a position sensor is used to measure the end-effector position directly, the task-space vector x is defined as a Cartesian space and hence J(q) = J e (q).

A property of the kinematic equation Kinematic equation described by Eq. 14 is stated as follows:

Property 4

The right-hand side of Eq. 14 is linear in a set of constant kinematic parameters θ k = (θ k1, ⋯, θ kq )T, such as link lengths and joint offsets. Hence, Eq. 14 can be expressed as

$$ \dot{x}=J(q)\dot{q}={Y}_k\left(q,\dot{q}\right){\theta}_k, $$
(16)

where \( {Y}_k\left(q,\dot{q}\right)\in {R}^{n\times q} \) is called the kinematic regressor matrix.

Example 3

Consider the two-link robot manipulator as depicted in Fig. 1. The kinematics of the robot can be expressed as follows:

$$ x=\left[\begin{array}{c}\hfill {L}_1 \cos \left({q}_1\right)+{L}_2 \cos \left({q}_1+{q}_2\right)\hfill \\ {}\hfill {L}_1 \sin \left({q}_1\right)+{L}_2 \sin \left({q}_1+{q}_2\right)\hfill \end{array}\right]. $$
(17)

The task-space velocity can be obtained by differentiation Eq. 17 with respect to time, as

$$ \dot{x}=\underset{J(q)}{\underbrace{\left[\begin{array}{ll}-{L}_1 \sin \left({q}_1\right)-{L}_2 \sin \left({q}_1+{q}_2\right)\hfill & -{L}_2 \sin \left({q}_1+{q}_2\right)\hfill \\ {}{L}_1 \cos \left({q}_1\right)+{L}_2 \cos \left({q}_1+{q}_2\right)\hfill & {L}_2 \cos \left({q}_1+{q}_2\right)\hfill \end{array}\right]}}\left[\begin{array}{l}{\dot{q}}_1\hfill \\ {}{\dot{q}}_2\hfill \end{array}\right]. $$
(18)

Equation 18 can be written as follows:

$$ \dot{x}=\underset{Y_k\left(q,\dot{q}\right)}{\underbrace{\left[\begin{array}{ll}- \sin \left({q}_1\right){\dot{q}}_1\hfill & - \sin \left({q}_1+{q}_2\right)\left({\dot{q}}_1+{\dot{q}}_2\right)\hfill \\ {} \cos \left({q}_1\right){\dot{q}}_1\hfill & \cos \left({q}_1+{q}_2\right)\left({\dot{q}}_1+{\dot{q}}_2\right)\hfill \end{array}\right]}}\underset{\theta_k}{\underbrace{\left[\begin{array}{l}{L}_1\hfill \\ {}{L}_2\hfill \end{array}\right]}}. $$
(19)

Set-Point Control by PD Plus Gravity Controller

This section considers the set-point control problems or point-to-point control problems in which the robot is required to move from one point to another point without controlling the path taken by the robot between the two points. A simple and useful set-point controller for motion control is the PD plus gravity controller . This control strategy employs feedback of joint angles, velocity, and compensation of gravitational force as depicted in Fig. 2.

Fig. 2
figure 2

A block diagram of the PD plus gravity controller

The feedback control law is expressed in the following form:

$$ u=-{K}_v\dot{q}-{K}_p\tilde{q}+g(q) $$
(20)

where K p is the proportional gain matrix, K v is the derivative gain matrix, and \( \tilde{q}=q-{q}_d \) such that q d represents a constant desired position. Both K p and K v are positive diagonal matrices. The closed-loop system can be obtained by substituting Eq. 20 into the dynamic Eq. 3:

$$ M(q)\ddot{q}+C\left(q,\dot{q}\right)\dot{q}+D(q)\dot{q}+{K}_v\dot{q}+{K}_p\tilde{q}=0. $$
(21)

The stability of the closed-loop system is examined by using the Lyapunov-based stability analysis. Consider the following Lyapunov function candidate as

$$ V=\frac{1}{2}{\dot{q}}^TM(q)\dot{q}+\frac{1}{2}{\tilde{q}}^T{K}_p\tilde{q}. $$
(22)

Differentiating the Lyapunov-like candidate with respect to time gives

$$ \dot{V}={\dot{q}}^TM(q)\ddot{q}+\frac{1}{2}{\dot{q}}^T\dot{M}(q)\dot{q}+{\dot{q}}^T{K}_p\tilde{q}. $$
(23)

Substituting \( M(q)\ddot{q} \) from the closed-loop Eq. 21 yields

$$ \begin{array}{c}\dot{V}=\frac{1}{2}{\dot{q}}^T\left(\dot{M}(q)-2C\left(q,\dot{q}\right)\right)\dot{q}-{\dot{q}}^TD(q)\dot{q}\\ {}\kern-1.2em -{\dot{q}}^T{K}_v\dot{q}-{\dot{q}}^T{K}_p\tilde{q}+{\dot{q}}^T{K}_p\tilde{q}.\end{array} $$
(24)

Considering the skew-symmetric property of the matrix \( \dot{M}(q)-2C\left(q,\dot{q}\right), \) \( \dot{V} \) is simplified as follows:

$$ \dot{V}=-{\dot{q}}^TD(q)\dot{q}-{\dot{q}}^T{K}_v\dot{q}\le 0. $$
(25)

Using LaSalle’s invariance principle (see lemma A1 in the Appendix) yields

$$ \dot{V}=0\Rightarrow {\dot{q}}^T\left\{D(q)+{K}_v\right\}\dot{q}=0\iff \dot{q}=0. $$
(26)

From the closed-loop Eq. 21, one can conclude that

$$ {K}_p\tilde{q}=0\Rightarrow \tilde{q}=0 $$
(27)

yields qq d as t → ∞.

In most robotic applications, the end effector of a robot manipulator is required to move to a desired position in the task space. This can be obtained by either solving the inverse kinematic problem to find the corresponding desired joint angles or developing task-space control methodology directly by using the task-space error. For task-space control, the Jacobian matrix is used to transform the task-space errors to joint control inputs. In the following, a task-space set-point control approach is presented. Consider the following feedback control law for the task-space regulation:

$$ u=-{J}^T(q)\left({K}_v\dot{x}-{K}_p\tilde{x}\right)+g(q) $$
(28)

where \( \tilde{x}=x-{x}_d \) such that x d is the desired position of the end effector. A block diagram of the task-space regulator described by Eq. 28 is illustrated in Fig. 3.

Fig. 3
figure 3

A block diagram of the task-space PD plus gravity control system

Substituting the feedback law Eq. 28 into the dynamic Eq. 3 yields the following closed-loop system:

$$ M(q)\ddot{q}+C\left(q,\dot{q}\right)\dot{q}+D(q)\dot{q}+{J}^T(q)\left({K}_v\dot{x}-{K}_p\tilde{x}\right)=0. $$
(29)

The following Lyapunov-like candidate can be considered for the stability analysis of the task-space regulation problem:

$$ V=\frac{1}{2}{\dot{q}}^TM(q)\dot{q}+\frac{1}{2}{\tilde{x}}^T{K}_p\tilde{x}. $$
(30)

Differentiating Eq. 30 with respect to time and substituting Eq. 29 into it yield

$$ \dot{V}=-{\dot{q}}^TD(q)\dot{q}-{\dot{q}}^T{J}^T(q){K}_v\dot{q}-{\dot{q}}^T{J}^T(q){K}_p\tilde{x}+{\dot{x}}^T{K}_p\tilde{x}-{\dot{q}}^TD(q)\dot{q}-{\dot{x}}^T{K}_v\dot{x}\le 0. $$
(31)

If the Jacobian matrix is of full rank, by using LaSalle’s invariance principle (see lemma A1 in the Appendix), it is obtained

$$ \dot{V}=0\Rightarrow {\dot{q}}^TD(q)\dot{q}+{\dot{x}}^T{K}_v\dot{x}\iff \Big\{\begin{array}{c}\hfill \dot{q}=0\hfill \\ {}\hfill \dot{x}=0\hfill \end{array}. $$
(32)

From the closed-loop Eq. 29, one can conclude that

$$ {J}^T(q){K}_p\tilde{x}=0\Rightarrow \tilde{x}=0. $$
(33)

Hence, the position of the end effector converges to the desired position such as xx d as t → ∞.

Remark 2

It was first shown in (Takegaki and Arimoto 1981) using the Lyapunov method that the simple PD controller with gravity compensation Eq. 20 is effective for set-point control of a robot manipulator Robot manipulator. The gravity compensation term can also be computed off-line by using the desired position (Tomei 1991; Kelly 1993; Arimoto 1996):

$$ u=-{K}_v\dot{q}-{K}_p\tilde{q}+g\left({q}_d\right). $$
(34)

A main drawback of the PD plus gravity controller is that an exact knowledge of the gravity force of the robot manipulator is required. The existence of uncertainty in modeling the gravitational term results in steady-state position error. One way to alleviate the problem is to increase the P control gain which may lead to saturation of the control torques. A common practice to remove the steady-state error is to add an integral term (Arimoto and Miyazaki 1984; Arimoto 1996).

$$ u=-{K}_v\dot{q}-{K}_p\tilde{q}-{K}_I{\displaystyle \int \tilde{q}dt} $$
(35)

where K I is a symmetric positive definite matrix. The closed-loop system of the linear PID robot control system is asymptotically stable in a local sense. To achieve global asymptotic stability, a saturated or bounded nonlinear function of the position error can be used (Arimoto et al. 1994):

$$ u=-{K}_v\dot{q}-{K}_p\tilde{q}-{K}_I{\displaystyle \int s\left(\tilde{q}\right)dt} $$
(36)

where s(.) is the saturation function. Other regulators for robot manipulators without using the gravitational term can be found in (Ortega et al. 1995; Kelly 1998). If the structure of the gravity force is known, adaptive PD controller with gravity regressor can also be used to eliminate the steady-state position error in the presence of uncertain parameters (Tomei 1991; Arimoto 1996):

$$ u=-{K}_v\dot{q}-{K}_p\tilde{q}+Z(q)\widehat{\varphi} $$
(37)

with the parameter update law

$$ \dot{\widehat{\varphi}}=-L{Z}^T(q)\left(\dot{q}+\alpha s\left(\tilde{q}\right)\right) $$
(38)

where α is a positive constant. The gravity regressor matrix can be computed off-line by using the desired position (Kelly 1993).

Adaptive Control of Robot Manipulators

For tracking control applications, the manipulator is required to follow a desired time-varying trajectory. The simple PD controllers in the previous section are usually not effective for tracking control, especially for high-speed manipulation tasks. In this section, adaptive control method of robot manipulators is presented for tracking control applications.

To design the adaptive control , a reference vector is defined as follows:

$$ {\dot{q}}_r={\dot{q}}_d-\lambda \tilde{q} $$
(39)

where λ is a positive constant. Using the reference vector Eq. 39, a sliding vector is defined as follows:

$$ \mathfrak{s}=\dot{q}-{\dot{q}}_r=\dot{\tilde{q}}+\lambda \tilde{q}. $$
(40)

In fact, Eq. 40 represents a low-pass filter which is also depicted in Fig. 4. Hence, \( \tilde{q} \) can be obtained as

Fig. 4
figure 4

Filter-like representation of Eq. 40 (p = (d/dt) is the Laplace operator)

$$ \tilde{q}(t)={\displaystyle \underset{0}{\overset{t}{\int }}{e}^{-\lambda \left(t-\tau \right)}}\mathfrak{s}\left(\tau \right)d\tau . $$
(41)

For a bounded sliding vector, i.e., \( \left|\right|\mathfrak{s}\left|\right|\le \Phi, \) then it yields

$$ \left|\right|\tilde{q}(t)\left|\right|\le \Phi {\displaystyle \underset{0}{\overset{t}{\int }}{e}^{-\lambda \left(t-\tau \right)}}\mathfrak{s}\left(\tau \right)d\tau \le \frac{\Phi}{\lambda }. $$
(42)

Therefore, inequality Eq. 42 shows that increasing λ leads to smaller tracking error.

By differentiating Eq. 40 with respect to time, \( \dot{\mathfrak{s}} \) is obtained as follows:

$$ \dot{\mathfrak{s}}=\ddot{q}-{\ddot{q}}_r=\ddot{\tilde{q}}+\lambda \dot{\tilde{q}}. $$
(43)

Substituting Eqs. 40 and 43 into Eq. 3 and using property 3, the following equation is obtained:

$$ M(q)\dot{\mathfrak{s}}+C\left(q,\dot{q}\right)\mathfrak{s}+D(q)\mathfrak{s}+\mathrm{Y}\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right){\theta}_d=u $$
(44)

where \( \mathrm{Y}\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right) \) is a known regressor matrix and θ d is an unknown parameter vector, which are defined as follows:

$$ \mathrm{Y}\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right){\theta}_d=M(q){\ddot{q}}_r+C\left(q,\dot{q}\right){\dot{q}}_r+D(q){\dot{q}}_r+g(q). $$
(45)

In fact, adaptive control strategies for a nonlinear system are mainly based on the property of linear parameterization of the nonlinear dynamics with respect to unknown parameters.

The adaptive law is expressed as follows:

$$ u=-{K}_{\mathfrak{s}}\mathfrak{s}+\mathrm{Y}\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right){\widehat{\theta}}_d $$
(46)

where \( {K}_{\mathfrak{s}} \) is a positive definite matrix and \( {\widehat{\theta}}_d \) is the vector of estimated parameters, which is updated based on the following update law:

$$ {\widehat{\theta}}_d=-L{\mathrm{Y}}^T\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right)\mathfrak{s} $$
(47)

such that L is a symmetric positive definite matrix. A block diagram of the adaptive law Eq. 46 is illustrated in Fig. 5.

Fig. 5
figure 5

A block diagram of the adaptive feedback law (46)

The closed-loop equation for the robot manipulator is obtained by substituting the adaptive feedback law Eq. 46 into the dynamic Eq. 3, as follows:

$$ M(q)\dot{\mathfrak{s}}+C\left(q,\dot{q}\right)\mathfrak{s}+D(q)\mathfrak{s}+{K}_{\mathfrak{s}}\mathfrak{s}+\mathrm{Y}\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right)\Delta {\theta}_d=0 $$
(48)

where \( \Delta {\theta}_d={\theta}_d-{\widehat{\theta}}_d. \) To examine the stability of the closed-loop system described by the Eq. 48, the following Lyapunov-like candidate is proposed:

$$ V=\frac{1}{2}{\mathfrak{s}}^TM(q)\mathfrak{s}+\frac{1}{2}\Delta {\theta}_d^T{L}^{-1}\Delta {\theta}_d. $$
(49)

By differentiating the Lyapunov-like candidate with respect to time, substituting the closed-loop Eq. 48 into it yields

$$ \begin{array}{c}\kern-0.3em \dot{V}={\mathfrak{s}}^TM(q)\dot{\mathfrak{s}}+\frac{1}{2}{\mathfrak{s}}^T\dot{M}(q)\mathfrak{s}+{\dot{\widehat{\theta}}}_d{L}^{-1}\Delta {\theta}_d\\ {}=-{\mathfrak{s}}^TD(q)\mathfrak{s}-{\mathfrak{s}}^T{K}_{\mathfrak{s}}\mathfrak{s}-{\mathfrak{s}}^T\mathrm{Y}\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right)\Delta {\theta}_d\\ {}+\frac{1}{2}{\mathfrak{s}}^T\left\{\dot{M}(q)-2C\left(q,\dot{q}\right)\right\}\mathfrak{s}+{\dot{\widehat{\theta}}}_d^T{L}^{-1}\Delta {\theta}_d.\end{array} $$
(50)

Considering the skew symmetricity of the matrix \( \dot{M}(q)-2C\left(q,\dot{q}\right) \) and substituting Eq. 47 into Eq. 50, \( \dot{V} \) is simplified as

$$ \dot{V}=-{\mathfrak{s}}^TD(q)\mathfrak{s}-{\mathfrak{s}}^T{K}_{\mathfrak{s}}\mathfrak{s}\le 0. $$
(51)

Since M(q) and L are positive definite, V is positive definite in \( \mathfrak{s} \) and Δθ d . Therefore, \( \mathfrak{s} \) and Δθ d are bounded. Hence, from closed-loop Eq. 48, one can conclude the boundedness of \( \dot{\mathfrak{s}} \), and this leads to the boundedness of \( \ddot{V} \), which means that \( \dot{V} \) is uniformly continuous. By Barbalat’s lemma (see lemma A2), it then follows \( \dot{V} \) goes to zero as t → ∞, so it can be concluded that s converges to zero. The convergence of \( \mathfrak{s} \) yields the convergence of \( \tilde{q} \) and \( \dot{\tilde{q}} \) to zero.

Remark 3

The globally tracking convergent adaptive controller Eq. 46 was derived in (Slotine and Li 1987) for a robot with dynamic uncertainty. The dynamic regressor matrix can also be computed off-line by using the desired trajectory (Arimoto 1996; Sadegh and Horowitz 1990). An adaptive controller with off-line computed dynamic regressor is as follows (Arimoto 1996):

$$ u=-{k}_p\tilde{q}-{K}_v\dot{\tilde{q}}+{Y}_d\left({q}_d,{\dot{q}}_d,{\dot{q}}_d,{\ddot{q}}_d\right){\widehat{\theta}}_d $$
(52)

with the parameter update law as

$$ {\dot{\widehat{\theta}}}_d=-L{Y}_d^T\left({q}_d,{\dot{q}}_d,{\dot{q}}_d,{\ddot{q}}_d\right)\left\{\dot{\tilde{q}}+\alpha s\left(\tilde{q}\right)\right\} $$
(53)

where α is a positive constant and s(.) is the saturation function. Many other robot adaptive controllers have also been proposed for a robot with dynamic uncertainty (Wen and Bayard 1988; Niemeyer and Slotine 1991; Berghuis et al. 1993; Paden and Panja 1988; Ortega and Spong 1989; Craig et al. 1987; Middleton and Goodwin 1988; Koditschek 1987; Lee and Khalil 1997).

This section focuses only on adaptive control of robot manipulators. Other tracking control methods for robot manipulators with dynamic uncertainty include robust control (Slotine 1985; Spong 1992; Abdallah et al. 1991), learning control (Arimoto 1996; Arimoto et al. 1984), and neural network control (Lewis 1996).

Remark 4

Since the closed-loop system Eq. 48 is directly dependant on time due to the presence of the time-varying trajectory q d (t), LaSalle’s invariance principle cannot be utilized to show the stability of the system.

Remark 5

A key point in adaptive control is that the tracking error will converge regardless of parameter convergence. That is, one does not need parameter convergence for tracking error convergence. However, parameter convergence can be obtained if the persistence of excitation condition is satisfied.

Remark 6

In many practical applications, the physical parameters are bounded by prescribed upper and lower limits. Using these bounds as a priori information, the parameter update law can be modified in a way that the estimates are constrained to a specified region. In this regard, a commonly used method is the standard projection algorithm (Ioannou and Sun 1996).

Approximate Jacobian Set-Point Control

In many modern control applications of robot manipulators, task-space sensory feedback information such as visual information is used to monitor the position of the end effector. By using sensory feedback, the control systems are robust to various modeling uncertainties. This gives the robot a high degree of flexibility in dealing with unforeseen changes and uncertainties. When a robot picks up several tools of different dimensions, unknown orientations, or gripping points, the kinematics changes and is difficult to derive exactly. In the presence of kinematic uncertainty, inverse kinematic algorithms cannot be used to derive the desired position in the joint space. This section presents a simple approximate Jacobian set-point controller for a robot manipulator with uncertain kinematics by using task-space sensory feedback of the position of the end effector. Though the position of the end effector can be measured by task-space sensors, the uncertainty of the Jacobian matrix poses a challenging robot control problem.

First the quasi-natural potential function S i (ϕ) is defined which will be used in developing the feedback law.

Definition 1

Consider the scalar function S i (ϕ) and its derivative s i (ϕ) as depicted in Fig. 6, with the following properties:

Fig. 6
figure 6

(a) Quasi-natural potential S i (ϕ), (b) derivative of S i (ϕ)

  1. 1.

    S i (ϕ) > 0 for ϕ ∈ R − {0} and S i (0) = 0.

  2. 2.

    S i (ϕ) is twice continuously differentiable, and the derivative \( {s}_i\left(\phi \right)=\frac{d{S}_i\left(\phi \right)}{d\phi } \) is strictly increasing in ϕ for |ϕ| < γ i with some γ i and saturated for |ϕ|γ i , i.e., s i (ϕ) = ±s i for ϕ ≥ +γ i and ϕ−γ , respectively, where s i is a positive constant.

  3. 3.

    There are constants \( {\overline{c}}_i>0,{d}_i>0,{\overline{d}}_i\left(>{d}_i\right)>0 \) such that

$$ {\overline{d}}_i{s}_i^2\left(\phi \right)\ge \phi {s}_i\left(\phi \right)\ge {d}_i{s}_i^2\left(\phi \right)>0,\kern0.96em {S}_i\left(\phi \right)\ge {\overline{c}}_i{s}_i^2\left(\phi \right), $$
(54)

for ϕ ≠ 0

The approximate Jacobian set-point controller is expressed as follows:

$$ u=-{\widehat{J}}^T(q)\left({K}_ps\left(\tilde{x}\right)+{K}_v\dot{x}\right)+g(q) $$
(55)

where \( \widehat{J}(q)\in {R}^{m\times n} \) is the estimation of the Jacobian matrix; J(q), K p , K v are positive definite diagonal feedback gains for the position and velocity, respectively; and s i (·), i = 1, · · ·, m are saturated functions defined in definition 1. Here, it is assumed that \( {\widehat{J}}^T(q) \) is chosen so that

$$ \left|\right|{J}^T(q)-{\widehat{J}}^T(q)\left|\right|\le \gamma, $$
(56)

where γ is a positive constant to be defined later. Substituting the feedback law Eq. 55 into the dynamic Eq. 3 gives the closed-loop equation as

$$ M(q)\ddot{q}+C\left(q,\dot{q}\right)\dot{q}+D(q)\dot{q}+{\widehat{J}}^T(q)\left({K}_ps\left(\tilde{x}\right)+{K}_v\dot{x}\right)=\kern0.36em 0. $$
(57)

To examine the stability of the closed-loop system, consider the following Lyapunov-like candidate:

$$ \begin{array}{l}V=\frac{1}{2}{\dot{q}}^TM(q)\dot{q}+\alpha {\dot{q}}^TM(q){\widehat{J}}^{\dagger }(q)s\left(\tilde{x}\right)\\ {}+{\displaystyle \sum_{i=1}^m\left({k}_{pi}+\alpha {k}_{vi}\right){S}_i\left({\tilde{x}}_i\right)},\end{array} $$
(58)

where α is a positive constant and Ĵ (q) denotes the pseudo-inverse of Ĵ(q) such that Ĵ(q)Ĵ T (q) is non-singular and Ĵ(q)Ĵ (q) = I. The parameters k pi , k vi denote the ith diagonal elements of K p and K v , respectively. Consider the following inequality:

$$ \begin{array}{c}\frac{1}{4}{\dot{q}}^TM(q)\dot{q}+\alpha {\dot{q}}^TM(q){\widehat{J}}^{\dagger }(q)s\left(\tilde{x}\right)+{\sum}_{i=1}^m\left({k}_{pi}+\alpha {k}_{vi}\right){S}_i\left({\tilde{x}}_i\right)\\ {}\kern1.2em =\frac{1}{4}{\left(\dot{q}+2\alpha {\widehat{J}}^{\dagger }(q)s\left(\tilde{x}\right)\right)}^TM(q)\left(\dot{q}+2\alpha {\widehat{J}}^{\dagger }(q)s\left(\tilde{x}\right)\right)-\\ {}{\alpha}^2s{\left(\tilde{x}\right)}^T{\left({\widehat{J}}^{\dagger }(q)\right)}^TM(q){\widehat{J}}^{\dagger }(q)s\left(\tilde{x}\right)+{\sum}_{i=1}^m\left({k}_{pi}+\alpha {k}_{vi}\right){S}_i\left({\tilde{x}}_i\right)\\ {}\kern2.4em \ge {\sum}_{i=1}^m\left\{{k}_{pi}{\overline{c}}_i+\alpha \left({k}_{vi}{\overline{c}}_i-\alpha {\lambda}_m\right)\right\}{s_i}^2\left({\tilde{x}}_i\right)\end{array} $$
(59)

where \( {\lambda}_m\kern0.24em \underset{\bar{\mkern6mu}}{\underset{\bar{\mkern6mu}}{\Delta}}\kern0.24em {\lambda}_{max}\left[{\left({\widehat{J}}^{\dagger }(q)\right)}^TM(q){\widehat{J}}^{\dagger }(q)\right] \). Substituting the inequality Eq. 59 into Eq. 58 yields

$$ V\ge \kern-0.1em \frac{1}{4}{\dot{q}}^TM(q)\dot{q}+{\displaystyle \sum_{i=1}^m\left\{{k}_{pi}{\overline{c}}_i+\alpha \left({k}_{vi}{\overline{c}}_i-\alpha {\lambda}_m\right)\right\}}{s_i}^2\left({\tilde{x}}_i\right)\ge 0 $$

where K v and α can be chosen so that

$$ {k}_{vi}{\overline{c}}_i-\alpha\;{\lambda}_m>0. $$
(60)

Hence, V is positive definite and represents a Lyapunov function candidate for the set-point control of the robot with uncertain Jacobian matrix. Differentiating the Lyapunov function candidate V with respect to time, it can be shown that (refer to Appendix for details)

$$ \begin{array}{c}\dot{V}\le -\left\{{\lambda}_{\max}\left({K}_v\right)\left({\delta}_1-\frac{\gamma }{2}\left({\delta}_2+2{b}_J\right)\right)-\alpha {c}_0\right\}{\left\Vert \dot{q}\right\Vert}^2\\ {}\kern1.92em -\left({\lambda}_{\max}\left({K}_p\right)\left(\alpha {\delta}_3-\frac{\gamma }{2}\right)-\alpha {c}_1\right){\left\Vert s\left(\tilde{x}\right)\right\Vert}^2\end{array} $$
(61)

such that c 0, c 1 are positive constants, b J is the upper bound of ||J(q)||, and

$$ \begin{array}{l}{\delta}_1\kern0.36em =\kern0.6em \frac{\lambda_{\min}\left[{J}^T(q){K}_vJ(q)+D(q)\right]}{\lambda_{\max}\left({K}_v\right)}\\ {}{\delta}_2\kern0.36em =\kern0.6em \frac{\lambda_{\max}\left({K}_p\right)}{\lambda_{\max}\left({K}_v\right)}\ \\ {}{\delta}_3\kern0.36em =\kern0.48em \frac{\lambda_{\min}\left({K}_p\right)}{\lambda_{\max}\left({K}_p\right)}.\end{array} $$
(62)

If the following inequality holds

$$ \min \left\{\frac{2{\delta}_1}{\delta_2+2{b}_J},2\alpha {\delta}_3\right\}>\gamma, $$
(63)

then by proper selection of parameters α, K p , and K v , such that

$$ \begin{array}{l}\ \left({\delta}_1-\frac{\gamma }{2}\left({\delta}_2+2{b}_J\right)\right)-\frac{\alpha {c}_0}{\lambda_{\max}\left({K}_v\right)}>0\\ {}\ \left(\alpha {\delta}_3-\frac{\gamma }{2}\right)-\frac{\alpha {c}_1}{\lambda_{\max}\left({K}_p\right)}>0,\kern0.75em \end{array} $$
(64)

it can be guaranteed that \( \dot{V}<0 \). This implies the convergence of the task-space error and joint-space velocity such that \( \tilde{x}\to 0 \), \( \dot{q}\to 0 \), as t → ∞.

Remark 7

For redundant robots, the dimension of x is different with the dimension of q, but the LaSalle’s invariance theorem can be used to deduce the convergence of \( \tilde{x} \), \( \dot{q} \) to zero.

An alternate condition for the bound γ can be derived by substituting \( {J}^T(q)={\widehat{J}}^T(q)+\tilde{J}(q) \) into Eq. 120 so that

$$ \begin{array}{c}\dot{V}\le -{\dot{q}}^T\left\{{\widehat{J}}^T(q){K}_v\widehat{J}(q)+D(q)-\alpha {c}_0I\right\}\dot{q}-\alpha s{\left(\tilde{x}\right)}^T\left({K}_p-{c}_1I\right)s\left(\tilde{x}\right)\\ {}-{\dot{q}}^T{\tilde{J}}^T(q){K}_v\widehat{J}(q)\dot{q}+{\dot{q}}^T{\tilde{J}}^T(q){K}_ps\left(\tilde{x}\right).\end{array} $$
(65)

Therefore, condition Eq. 63 is written as follows:

$$ \min \left\{\frac{2{\widehat{\delta}}_1}{\delta_2+2{b}_{\widehat{J}}},2\alpha {\delta}_3\right\}>\gamma, $$
(66)

where \( {\widehat{\delta}}_1=\frac{\lambda_{\min}\left[{\widehat{J}}^T(q){K}_v\widehat{J}(q)+D(q)\right]}{\lambda_{\max}\left({K}_v\right)} \) and b Ĵ is the upper norm bound of Ĵ(q). This implies that the bound γ can be represented by the actual or estimated Jacobian matrix whichever is larger.

In order to further explore the condition Eq. 63, let K v = k v I, K p = ak v I. Hence, condition Eq. 63 is simplified as

$$ \min \left\{\frac{2{\lambda}_{\min}\left[{\widehat{J}}^T(q)\widehat{J}(q)+\raisebox{1ex}{$D(q)$}\!\left/ \!\raisebox{-1ex}{${k}_v$}\right.\right]}{a+2{b}_{\widehat{J}}},2\alpha \right\}\kern0.37em >\gamma . $$
(67)

For a sufficiently large α \( \left(\mathrm{i.e.,},\kern0.36em ,\alpha \kern0.36em >\frac{\lambda_{\min}\left[{\widehat{J}}^T(q)\widehat{J}(q)+\raisebox{1ex}{$D(q)$}\!\left/ \!\raisebox{-1ex}{${k}_v$}\right.\right]}{2{b}_{\widehat{J}}}\right) \), condition Eq. 67 is written as

$$ \frac{2{\lambda}_{\min}\left[{\widehat{J}}^T(q)\widehat{J}(q)+\raisebox{1ex}{$D(q)$}\!\left/ \!\raisebox{-1ex}{${k}_v$}\right.\right]}{a+2{b}_{\widehat{J}}}\kern0.36em >\gamma . $$
(68)

The condition Eq. 63 is illustrated in Fig. 7. In order to guarantee the stability of the system with approximate Jacobian matrix, the allowable bound of the Jacobian uncertainty γ must be smaller than the curve as shown in the figure.

The following conditions can be obtained from Fig. 7:

Fig. 7
figure 7

An illustration of condition Eq. 63 where the vertical axis represents the bound of the Jacobian uncertainty and the horizontal axis represents the feedback-gains ratio

  1. (i)

    If γ is small, α can be chosen small and therefore from Eq. 60 it can be deduced that a smaller controller gain is required.

  2. (ii)

    If γ is small, a wider range of the feedback-gains ratio a can be chosen. In fact, in the extreme case where γ = 0, a could be chosen as any value.

  3. (iii)

    If γ is large, a larger controller gain is required and a narrower range of the feedback-gains ratio a is allowed.

Moreover, if a is increased, then the allowable bound γ of the Jacobian uncertainty \( \tilde{J}(q)={\widehat{J}}^T(q)-{J}^T(q) \) is reduced. Therefore, the feedback-gains ratio a should be kept smaller so that the allowable bound of the Jacobian uncertainty is larger. This can be easily done by either reducing K p or increasing K v . Though the condition is a sufficient condition, it is reasonable because increasing K p amplifies the estimated Jacobian \( \widehat{J}(q) \) and hence more accuracy on the estimation or more damping is required. An important and piratical conclusion of the result is that when the system is unstable, redesign of \( \widehat{J}(q) \) may not be necessary as the instability may be due to the reason that the feedback-gains ratio a is not tuned properly. In practice, we should therefore try to stabilize the system or increase the margin of stability first by reducing the feedback-gains ratio a (Fig. 7).

Fig. 8
figure 8

A block diagram of the task-space approximate Jacobian regulator with adaptive gravity compensation

In the presence of uncertainties in gravitational force and Jacobian matrix, the task-space control of robot manipulators can be obtained by using the concept of regressor for the robot dynamics (see Eq. 7) such that a gravity regressor is introduced to compensate for the gravity force.

The gravity term can be characterized by a set of parameters φ = (φ 1, · · ·, φ p )T as

$$ g(q)=Z(q)\varphi, $$
(69)

where Z(q) ∈ R n×p is the gravity regressor.

Example 4

For the two-link robot manipulator depicted in Fig. 1, Z(q) can be expressed as follows:

$$ Z(q)=\kern0.61em \left[\begin{array}{cc}\hfill \cos \left({q}_1\right)\hfill & \hfill \cos \left({q}_1+{q}_2\right)\hfill \\ {}\hfill 0\hfill & \hfill \cos \left({q}_1+{q}_2\right)\hfill \end{array}\right]\kern0.5em , $$

and the unknown parameter vector φ is expressed as

$$ \varphi =\left[\begin{array}{c}\hfill \left({M}_1{L}_{c1}+{M}_2{L}_1\right)g\hfill \\ {}\hfill {M}_2{L}_{c2g}\hfill \end{array}\right]. $$

The feedback control law is obtained as

$$ u=-{\widehat{J}}^T(q)\left({K}_ps\left(\tilde{x}\right)+{K}_v\dot{x}\right)+Z(q)\widehat{\varphi}, $$
(70)

such that the estimated parameter vector \( \widehat{\varphi} \) is updated as

$$ \dot{\widehat{\varphi}}(t)=-L{Z}^T(q)\ \left(\dot{q}+\alpha {\widehat{J}}^{\dagger }(q)s\left(\tilde{x}\right)\right), $$
(71)

where LR p×p is a positive definite matrix. A block diagram of the task-space approximate Jacobian regulator Task-space approximate Jacobian regulator with adaptive gravity compensation described by Eqs. 70 and 71 is illustrated in Fig. 8.

Substituting Eqs. 69 and 70 into the dynamic Eq. 3 gives

$$ M(q)\ddot{q}+C\left(q,\dot{q}\right)\dot{q}+D(q)\dot{q}{\widehat{J}}^T(q)\left({K}_ps\left(\tilde{x}\right)+{K}_v\dot{x}\right)+Z(q)\Delta \varphi =0, $$
(72)

where \( \Delta \varphi =\varphi -\widehat{\varphi} \). To examine the stability of the closed-loop system Eq. 72, the following Lyapunov function candidate is considered:

$$ \begin{array}{l}V=\frac{1}{2}{\dot{q}}^TM(q)\dot{q}+\alpha {\dot{q}}^TM(q){\widehat{J}}^{\dagger }(q)s\left(\tilde{x}\right)\\ {}+\frac{1}{2}\Delta {\varphi}^T{L^{-}}^1\Delta \varphi +{\displaystyle \sum_{i=1}^m\left({k}_{pi}+\alpha {k}_{vi}\right){S}_i\left({\tilde{x}}_i\right).}\end{array} $$
(73)

The convergence of the task-space error and joint-space velocity can be shown by differentiating the Lyapunov function candidate with respect to time (similar to previous section), and using LaSalle’s invariance principle.

Remark 8

The approximate Jacobian set-point controller Eq. 55 with task-space damping was proposed in (Cheah et al. 1998, 1999). The controller requires the measurement of a task-space position by using a sensor such as vision systems. The task-space velocity is obtained by numerical differentiation of the position. In (Cheah et al. 2003), an approximate Jacobian feedback controller using only joint-space damping was developed as

$$ u=-{\widehat{J}}^T(q){K}_ps\left(\tilde{x}\right)-{K}_v\dot{q}+g(q). $$
(74)

The joint-space velocity is obtained by numerical differentiation of the joint position, which is usually less noisy than in the task space. In the presence of uncertainty in the gravitational force, the update law Eq. 71 or the integration control term (Cheah et al. 1999) also requires the use of the inverse Jacobian matrix. An approximate Jacobian controller with adaptive gravity compensation was developed as (Cheah et al. 2003)

$$ u=-{\widehat{J}}^T(q)\left({K}_p,s,\left(\tilde{x}\right),+,{K}_v,\dot{x}\right)+Z(q)\widehat{\varphi}, $$
(75)

such that the estimated parameter vector \( \widehat{\varphi} \) is updated as

$$ \dot{\widehat{\varphi}}(t)=-L{Z}^T(q)\left(\dot{q}+\alpha {\widehat{J}}^T(q)s\left(\tilde{x}\right)\right), $$
(76)

where α is positive constant and s(.) is the saturation function. The main advantages of the controller are that the task-space velocity and the inverse of the approximate Jacobian matrix are not required. An update law can also be used to update the kinematic parameters of the estimated Jacobian matrix online (Cheah 2003; Dixon 2007), and the simpler stability conditions can be obtained as compared to using a fixed approximate Jacobian matrix.

Adaptive Jacobian Tracking Control

The approximate Jacobian controller in the previous section is only effective for point-to-point control problem. This section presents an adaptive Jacobian controller for tracking control of a robot manipulator with uncertain kinematics and dynamics. The concurrent adaptation to both kinematic and dynamic uncertainties is something “humanlike” as in tool manipulation. The key idea is to introduce a task-space adaptive sliding vector based on estimated task-space velocity and a dynamic regressor matrix based on the estimated kinematic parameters.

In the presence of kinematic uncertainty, the parameters of the Jacobian matrix are uncertain and an estimated velocity is defined using Eq. 16 as

$$ \widehat{\dot{x}}=\widehat{J}\left(q,,,{\widehat{\theta}}_k\right)\dot{q}={Y}_k\left(q,\dot{q}\right){\widehat{\theta}}_k $$
(77)

where \( \widehat{\dot{x}}\in {R}^n \) denotes the estimated task-space velocity, \( \widehat{J}\left(q,,,{\widehat{\theta}}_k\right)\in {R}^{n\times n} \) is an estimated or adaptive Jacobian matrix, and \( {\widehat{\theta}}_k\in {R}^q \) denotes a set of estimated kinematic parameters. Figure 9 illustrates the difference between the estimated task-space velocity and the actual task-space velocity.

Fig. 9
figure 9

The estimated task-space velocity and the actual task-space velocity

A reference vector \( {\dot{x}}_r\in {R}^n \) is defined as follows:

$$ {\dot{x}}_r={\dot{x}}_d-\alpha \left(x-{x}_d\right) $$
(78)

where x d (t) ∈ R n is the desired trajectory in the task space. Differentiating Eq. 78 with respect to time yields

$$ {\ddot{x}}_r={\ddot{x}}_d-\alpha \left(\dot{x}-{\dot{x}}_d\right) $$
(79)

where \( {\ddot{x}}_d=\frac{d{\dot{x}}_d}{dt}\in {R}^n \) is the desired acceleration in the task space. Using the reference vector, an adaptive task-space sliding vector is defined as

$$ {\widehat{\mathfrak{s}}}_x\kern0.48em =\kern0.48em \widehat{\dot{x}}-{\dot{x}}_r=\widehat{J}\left(q,,,{\widehat{\theta}}_k\right)\dot{q}-{\dot{x}}_r $$
(80)

where \( \widehat{J}\left(q,,,{\widehat{\theta}}_k\right)\dot{q}={Y}_k\left(q,\dot{q}\right){\widehat{\theta}}_k \) as indicated in Eq. 77. The above vector is adaptive in the sense that the parameters of the estimated Jacobian matrix are updated by a parameter update law which will be introduced in the later development. The adaptive task-space sliding vector can also be written as follows:

$$ \begin{array}{c}{\widehat{\mathfrak{s}}}_x\kern0.36em =\kern0.48em \widehat{J}\left(q,,,{\widehat{\theta}}_k\right)\dot{q}-{\dot{x}}_d+\alpha \tilde{x}+\dot{x}-\dot{x}\\ {}=\dot{\tilde{x}}+\alpha \tilde{x}-\left(\underset{Y_k\left(q,,,\dot{q}\right){\theta}_k}{\underbrace{J\left(q,{\theta}_k\right)\dot{q}}}-\underset{Y_k\left(q,,,\dot{q}\right){\widehat{\theta}}_k}{\underbrace{\widehat{J}\left(q,,{\widehat{\theta}}_k\right)\dot{q}}}\right)\\ {}=\dot{\tilde{x}}+\alpha \tilde{x}-{Y}_k\left(q,\dot{q}\right)\Delta {\theta}_k.\end{array} $$
(81)

Equation 81 shows that \( {\widehat{\mathfrak{s}}}_x \) converges to the sliding vector \( \left(\dot{\tilde{x}}+\alpha \tilde{x}\right) \), as Δθ k goes to zero.

Differentiating Eq. 80 with respect to time yields

$$ {\dot{\widehat{\mathfrak{s}}}}_x=\widehat{\ddot{x}}-{\ddot{x}}_r=\widehat{J}\left(q,,,{\widehat{\theta}}_k\right)\ddot{q}+\dot{\widehat{J}}\left(q,,,{\widehat{\theta}}_k\right)\dot{q}-{\ddot{x}}_r $$
(82)

where \( \widehat{\ddot{x}} \) denotes the derivative of \( \widehat{\dot{x}} \).

Now, a reference vector is defined in the joint space as

$$ {\dot{q}}_r={\widehat{J}}^{-1}\left(q,,,{\widehat{\theta}}_k\right){\dot{x}}_r $$
(83)

where \( {\widehat{J}}^{-1}\left(q,{\widehat{\theta}}_k\right) \) is the inverse of the approximate Jacobian matrix \( \widehat{J}\left(q,{\widehat{\theta}}_k\right) \). Here, it is assumed that the robot is operating in a finite task space such that the approximate Jacobian matrix is of full rank. From Eq. 83, it is obtained:

$$ {\ddot{q}}_r={\widehat{J}}^{-1}\left(q,,,{\widehat{\theta}}_k\right){\ddot{x}}_r+{\dot{\widehat{J}}}^{-1}\left(q,,,{\widehat{\theta}}_k\right){\dot{x}}_r $$
(84)

Hence, an adaptive sliding vector in joint space can be defined as

$$ \mathfrak{s}\kern0.48em =\kern0.36em \dot{q}-{\dot{q}}_r=\dot{q}-{\widehat{J}}^{-1}\left(q,,,{\widehat{\theta}}_k\right){\dot{x}}_r $$
(85)

and

$$ \dot{\mathfrak{s}}=\ddot{q}-{\ddot{q}}_r. $$
(86)

To obtain the relationship between the adaptive sliding vectors in the joint space and task space, multiply both sides of Eq. 85 by \( \widehat{J}\left(q,,,{\widehat{\theta}}_k\right) \) and using Eq. 80 as follows:

$$ \widehat{J}\left(q,,,{\widehat{\theta}}_k\right)\mathfrak{s}\kern0.36em =\widehat{J}\left(q,,,{\widehat{\theta}}_k\right)\dot{q}-{\dot{x}}_r={\widehat{\mathfrak{s}}}_x. $$
(87)

Substituting Eqs. 85 and 86 into Eq. 3 and using property 3, the equations of motion can be expressed as

$$ M(q)\dot{\mathfrak{s}}+C\left(q,\dot{q}\right)\mathfrak{s}+D(q)\mathfrak{s}+\mathrm{Y}\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right){\theta}_d=u $$
(88)

such that

$$ \mathrm{Y}\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right){\theta}_d=M(q){\ddot{q}}_r+C\left(q,\dot{q}\right){\dot{q}}_r+D(q){\dot{q}}_r+g(q). $$
(89)

The adaptive Jacobian tracking controller is presented as follows:

$$ u=-{\widehat{J}}^T\left(q,{\widehat{\theta}}_k\right)\left({K}_v\dot{\tilde{x}}+{K}_p\tilde{x}\right)+Y\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right){\widehat{\theta}}_d $$
(90)

where \( \tilde{x}=x-{x}_d \), \( \dot{\tilde{x}}=\dot{x}-{\dot{x}}_d \), and K v R n×n and K p R n×n are symmetric positive definite gain matrices. The kinematic and dynamic adaptation laws are introduced as follows:

$$ {\dot{\widehat{\theta}}}_k={L}_k{Y}_k^T\left(q,\dot{q}\right)\left({k}_v\dot{\tilde{x}}+{K}_p\tilde{x}\right) $$
(91)
$$ {\dot{\widehat{\theta}}}_d=-{L}_d{Y}^T\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right)\mathfrak{s}. $$
(92)

A block diagram and an illustration of the adaptive Jacobian tracking controller Eq. 90 are depicted in Figs. 10 and 11, respectively.

Fig. 10
figure 10

A block diagram of the adaptive Jacobian tracking controller Eq. 90

Fig. 11
figure 11

A schematic diagram of the adaptive Jacobian tracking controller (Eq. 90) together with parameter update laws (91) and (92)

Substituting Eq. 90 into Eq. 88, the closed-loop equation can be expressed as

$$ M(q)\dot{\mathfrak{s}}+C\left(q,\dot{q}\right)\mathfrak{s}+D(q)\mathfrak{s}+{\widehat{J}}^T\left(q,{\widehat{\theta}}_k\right)\left({K}_v\dot{\tilde{x}}+{K}_p\tilde{x}\right)+\mathrm{Y}\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right)\Delta {\theta}_d=0 $$
(93)

where \( \Delta {\theta}_d={\theta}_d-{\widehat{\theta}}_d \). For stability analysis, a Lyapunov-like function candidate is defined as

$$ V=\frac{1}{2}{\mathfrak{s}}^TM(q)\mathfrak{s}+\frac{1}{2}\Delta {\theta}_d^T{L}_d^{-1}\Delta {\theta}_d+\frac{1}{2}\Delta {\theta}_k^T{L}_k^{-1}\Delta {\theta}_k+\frac{1}{2}{\tilde{x}}^T\left({K}_p+\alpha {K}_v\right)\tilde{x} $$
(94)

where \( \Delta {\theta}_k={\theta}_k-{\widehat{\theta}}_k \). Differentiating V with respect to time; substituting the closed-loop Eq. 93, \( {\dot{\widehat{\theta}}}_k \) from Eq. 91, and \( {\dot{\widehat{\theta}}}_d \) from Eq. 92 into it; and using property 2 yield

$$ \begin{array}{l}\dot{V}=-{\mathfrak{s}}^TD(q)\mathfrak{s}-{\widehat{\mathfrak{s}}}_x^T\left({K}_v\dot{\tilde{x}}+{K}_p\tilde{x}\right)+{\tilde{x}}^T\left({K}_p+\alpha {K}_v\right)\dot{\tilde{x}}\\ {}-\Delta {\theta}_k^T{Y}_k^T\left(q,\dot{q}\right)\left({K}_v\dot{\tilde{x}}+{K}_p\tilde{x}\right).\end{array} $$
(95)

Substituting Eq. 81 into Eq. 95 yields

$$ \dot{V}=-{\mathfrak{s}}^TD(q)\mathfrak{s}-{\dot{\tilde{x}}}^T{K}_v\dot{\tilde{x}}-\alpha {\tilde{x}}^T{K}_p\tilde{x}\le 0. $$
(96)

Since M(q) is positive definite, V in Eq. 94 is positive definite in \( \mathfrak{s} \), Δx, Δθ k , and Δθ d . Therefore, Eq. 96 leads to boundedness of V, and consequently \( \mathfrak{s} \), Δx, Δθ k , and Δθ d are bounded, which implies that \( {\widehat{\theta}}_k \) and \( {\widehat{\theta}}_d \) are bounded and \( {\widehat{\mathfrak{s}}}_x=\widehat{J}\left(q,{\widehat{\theta}}_k\right)\mathfrak{s} \) is bounded as seen from Eq. 87. If x d and its derivatives are bounded, then x and \( {\dot{x}}_r \) (see Eq. 78) are bounded. Therefore, \( {\dot{q}}_r \) in Eq. 83 is also bounded if the approximate Jacobian matrix is non-singular. From Eq. 85, \( \dot{q} \) is bounded and the boundedness of \( \dot{q} \) means that \( \dot{x} \) is bounded since the Jacobian matrix is bounded. Hence, \( \Delta \dot{x} \) is bounded and \( {\ddot{x}}_r \) in Eq. 79 is also bounded if \( {\ddot{x}}_d \) is bounded. From Eq. 91, \( {\dot{\widehat{\theta}}}_k \) is therefore bounded since Δx, \( \Delta \dot{x} \), \( \dot{q} \) are bounded and Y k (·) is a trigonometric function of q. Therefore, \( {\ddot{q}}_r \) in Eq. 84 is bounded. From the closed-loop Eq. 93, one can conclude that \( \dot{\mathfrak{s}} \) is bounded. The boundedness of \( \dot{\mathfrak{s}} \) implies the boundedness of \( \ddot{q} \) as seen from Eq. 86. From Eq. 82, \( {\dot{\widehat{\mathfrak{s}}}}_x \) is therefore bounded. Finally, differentiating Eq. 81 with respect to time and rearranging yield

$$ \ddot{\tilde{x}}+\alpha \dot{\tilde{x}}={\dot{\widehat{\mathfrak{s}}}}_x+{\dot{Y}}_k\left(q,\dot{q},\ddot{q}\right)\Delta {\theta}_k-{Y}_k\left(q,\dot{q}\right){\dot{\widehat{\theta}}}_k $$

which means that \( \ddot{\tilde{x}}=\ddot{x}-{\ddot{x}}_d \) is also bounded. Therefore, \( \ddot{V} \), which is shown as follows:

$$ \ddot{V}=-2{\mathfrak{s}}^TB\dot{\mathfrak{s}}-2\Delta {\dot{x}}^T{K}_v\ddot{\tilde{x}}-2\alpha {\tilde{x}}^T{K}_p\dot{\tilde{x}}, $$

is bounded. Hence, \( \dot{V} \) is uniformly continuous. Using Barbalat’s lemma, it gives \( \tilde{x}=x-{x}_d\to 0 \), \( \dot{\tilde{x}}=\dot{x}-{\dot{x}}_d\to 0 \), and \( \mathfrak{s}\to 0 \) as t → ∞.

Remark 9

The adaptive Jacobian tracking controller Eq. 90 for robots with uncertainties in kinematics and dynamics was developed in (Cheah et al. 2004). The proposed controller requires the differentiation of the task-space position which is noisy. An adaptive Jacobian tracking control law based on filtered differentiation of the measured task-space position was developed in (Cheah et al. 2006a). Observer design techniques can also be used to estimate the velocities (Liang et al. 2010). To avoid singularities associated with Euler angle representation, adaptive Jacobian tracking controller based on unit quaternion was developed (Braganza et al. 2005). An adaptive Jacobian controller based on prediction error was proposed in (Wang and Xie 2009). Sliding PID tracking control schemes with uncertain Jacobian were proposed in (Garcia-Rodriguez and Parra-Vega 2012).

When cameras are used to measure the position of the end effector, the vector of image feature parameter rates of change x is related to joint variables by the following equation (Cheah et al. 2007):

$$ \dot{x}=\overset{J(q)}{\overbrace{\underset{J_I}{\underbrace{Z^{-1}(q)L(x)}}{J}_m(q)}}\dot{q} $$
(97)

where \( \mathbf{\mathcal{Z}} \) (q) is a diagonal matrix, which contains the depth information of the feature points with respect to the camera image frame, and L(x) is a Jacobian matrix. Since the overall Jacobian matrix J(q) is inversely proportional to the depths, it is not linearly parameterizable. Therefore, the kinematic parameters in the image Jacobian cannot be extracted to form a lumped kinematic parameter vector that includes the unknown depth parameters, i.e.,

$$ J(q)\dot{q}\ne Y\left(q,\dot{q}\right)\boldsymbol{\theta} . $$
(98)

Thus, these abovementioned adaptive Jacobian controllers are effective only in cases where the depth information is constant or slowly time varying. Vision-based tracking controllers with uncertain depth were proposed in (Wang et al. 2007), but the uncertainty of robot kinematics and dynamics was not considered and the depth information was not updated online. However, the following linear parameterizations hold

$$ \mathbf{\mathcal{Z}}(q)\dot{x}={Y}_z\left(q,\dot{x}\right){\boldsymbol{\theta}}_z $$
(99)
$$ {J}_e(q)\dot{q}={Y}_k\left(q,\dot{q}\right){\boldsymbol{\theta}}_k $$
(100)

where\( {Y}_z\left(q,\dot{x}\right) \) is called the depth regressor matrix and \( {Y}_k\left(q,\dot{q}\right) \) is called the kinematic regressor matrix. Therefore, an adaptive Jacobian tracking control with uncertain depth information can be proposed as (Cheah et al. 2007)

$$ u=-{\widehat{J}}^T\left(q,{\widehat{\theta}}_k\right){\widehat{\mathbf{\mathcal{Z}}}}^{-1}\left(q,{\widehat{\theta}}_z\right)\left({K}_p\tilde{x}+{K}_v\dot{\tilde{x}}\right)+{Y}_d\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right){\widehat{\theta}}_d $$
(101)

where\( {\widehat{J}}^T\left(q,{\widehat{\theta}}_k\right){\widehat{\mathbf{\mathcal{Z}}}}^{-1}\left(q,{\widehat{\theta}}_z\right) \)is the adaptive Jacobian matrix and K p and K v are symmetric positive definite matrices. The uncertain dynamic, kinematic, and depth parameters are updated by the following update laws:

$$ {\dot{\widehat{\theta}}}_d=-{L}_d{Y}_d^T\left(q,\dot{q},{\dot{q}}_r,{\ddot{q}}_r\right)s $$
(102)
$$ {\dot{\widehat{\theta}}}_k={L}_k{Y}_k^T\left(q,\dot{q}\right){\widehat{Z}}^{-1}\left(q,{\widehat{\theta}}_z\right)\left({K}_p\tilde{x}+{K}_v\dot{\tilde{x}}\right) $$
(103)
$$ {\dot{\widehat{\theta}}}_z=-{L}_z{Y}_z^T\left(q,\dot{x}\right){\widehat{Z}}^{-1}\left(q,{\widehat{\theta}}_z\right)\left({K}_p\tilde{x}+{K}_v\dot{\tilde{x}}\right). $$
(104)

Remark 10

In the redundant case (Cheah et al. 2006a, b), the null space of the approximate Jacobian matrix can be used to minimize a performance index. Hence, the reference vector in the joint space can be defined as

$$ {\dot{q}}_r={\widehat{J}}^{\dagger}\left(q,{\widehat{\theta}}_k\right){\dot{x}}_r+\left({I}_n-{\widehat{J}}^{\dagger}\left(q,{\widehat{\theta}}_k\right)\widehat{J}\left(q,{\widehat{\theta}}_k\right)\right)\psi $$
(105)

where \( {\widehat{J}}^{\dagger}\left(q,{\widehat{\theta}}_k\right) \)is the pseudo-inverse of the approximate Jacobian matrix and ψR n is minus the gradient of the convex function to be optimized.

Simulation Results

In this section, various feedback laws presented in the previous sections are applied on the two-link robot manipulator (depicted in Fig. 1). The parameters of the robot are shown in Table 1. The simulation was carried out in MATLAB/SIMULINK .

Table 1 Parameters of the two link robot manipulator

PD Plus Gravity Control Law

For the set-point regulation, PD plus gravity control law Eq. 20 is applied on two-link robot manipulator. The control gains were chosen as K p = diag{10, 10} and K v = diag{5, 5}. The initial values of joint angles were chosen as q 1(0) = π/4 and q 2(0) = π/6, and the initial values of joint velocities were chosen as \( {\dot{q}}_1(0),{\dot{q}}_2(0)=0 \). The desired joint angles were chosen as q d1 = π/2 and q d2 = π/3. The simulation results are depicted in Figs. 12 and 13 which show error of joints angles and joint velocities. The actuator torques are shown in Fig. 14.

Fig. 12
figure 12

Error of joints angles \( {\tilde{q}}_1,{\tilde{q}}_2 \)

Fig. 13
figure 13

Joints velocities \( {\dot{q}}_1,{\dot{q}}_2 \)

Fig. 14
figure 14

Actuator torques u 1, u 2

Now assume there is 10 % mismatch in measurement of physical parameters, i.e.,

$$ \begin{array}{l}{\overline{M}}_1={M}_1+0.1{M}_1\kern0.2em {\overline{M}}_2={M}_2+0.1{M}_2\\ {}\kern0.84em {\overline{L}}_1={L}_1+0.1{L}_1\kern0.48em {\overline{L}}_2={L}_2+0.1{L}_2.\end{array} $$

The error of joints angles is depicted in Fig. 15. Figure 15 shows that there is an offset between the final values of joints angles and their desired values. To alleviate this steady-state error, let the controller gains increase such that K p = diag{60, 60} and K v = diag{25, 25}. Figure 16 shows that the steady-state errors improved considerably. However, if one plots the actuator toques as depicted in Fig. 17, it shows that the actuator torques are also increased which might lead to saturation. Hence, there is a trade-off between the accuracy and the control torque.

Fig. 15
figure 15

\( {\tilde{q}}_1,{\tilde{q}}_2 \) in the presence of 10 % mismatch in measurement of physical parameters

Fig. 16
figure 16

\( {\tilde{q}}_1,{\tilde{q}}_2 \) for high control gains

Fig. 17
figure 17

Actuator torques u 1, u 2

Another method to improve the steady-state error in the presence of inaccurate measurements is to utilize an integral term to the PD plus gravity control law . Therefore, the feedback law for PID plus gravity law can be expressed as follows:

$$ u=-{K}_v\dot{q}-{K}_p\tilde{q}-{K}_i{\displaystyle \int \tilde{q}dt+g(q)}. $$
(106)

The simulation results for PID plus estimated gravity in the presence of 10% mismatch in measurement of physical parameters are depicted in Figs. 18 and 19. The control gains were chosen as K p = diag{10, 10}, K i = diag{2, 2}, and K v = diag{5, 5}. It is shown that both accuracy and control torques are improved significantly.

Fig. 18
figure 18

\( {\tilde{q}}_1,{\tilde{q}}_2 \) for PID plus gravity feedback control

Fig. 19
figure 19

Actuator torques u 1, u 2 for PID plus gravity feedback control

Task-Space PD Plus Gravity

The task-space PD plus gravity control law Eq. 28 is applied for two-link robot manipulator to control its end-effector position to reach the desired position. The controller gains were chosen as K p = diag{200, 200} and K v = diag{50, 50}. The initial position of robot was x = [0.4, 0], and the desired end-effector position was considered as x = [0.1, 0.3]. The end-effector position is depicted in Fig. 20. The robot arms are depicted for different snapshots. The actuator toques are depicted in Fig. 21.

Fig. 20
figure 20

The end-effector position for the task-space PD plus gravity regulator

Fig. 21
figure 21

Actuator torques u 1, u 2 for the task-space PD plus gravity regulator

Adaptive Control

The adaptive feedback law Eq. 46 together with the parameter update law Eq. 47 is applied to the two-link robot manipulator for trajectory tracking. The controller gains were chosen as K s = diag{15, 15} and λ = 10. The gain for update law was chosen as L = 50. The initial position and velocity of the robot’s joints were q = [0, 0] and \( \dot{q}=\left[0,0\right] \), respectively. The desired trajectory was set as

$$ {q}_d(t)=\left[\begin{array}{c}\hfill 0.1+0.1t+0.2 \sin (t)\hfill \\ {}\hfill 0.1+0.1t+0.2 \cos (t)\hfill \end{array}\right]. $$
(107)

The initial values of the unknown parameters were chosen as \( {\widehat{\theta}}_d(0)={\left[0,0,0,0,0,0,0\right]}^T \). The position and the desired reference of joint one and two are depicted in Figs. 22 and 23. The velocity and the desired velocity of joint one and two are depicted in Figs. 24 and 25. The actuator toques are depicted in Fig. 26.

Fig. 22
figure 22

The position and the desired reference of joint one for the adaptive trajectory tracking

Fig. 23
figure 23

The position and the desired reference of joint two for the adaptive trajectory tracking

Fig. 24
figure 24

The velocity and the desired velocity of joint one for the adaptive trajectory tracking

Fig. 25
figure 25

The velocity and the desired velocity of joint two for the adaptive trajectory tracking

Fig. 26
figure 26

Actuator torques u 1, u 2 for the adaptive trajectory tracking

Approximate Jacobian Set-Point Control with Uncertain Gravitational Force

For this part, the approximate Jacobian set-point control in the presence of uncertainties in gravitational force was considered for the simulation. The approximate Jacobian regulator together with adaptive gravity compensation (Eqs. 75 and 76) was applied for the two-link robot manipulator to control its end-effector position to reach the desired position. The controller gains were chosen as K p = diag{1000, 1000} and K v = diag{100, 100}. The adaptive gains were chosen as L = 500 and α = 50. The initial values of the unknown parameters were chosen as \( \widehat{\varphi}(0)={\left[0,0\right]}^T \). The initial position of the robot’s end effector was x = [0.4, 0], and the desired end-effector position was set as x = [0.1,.3]. The end-effector position is depicted in Fig. 27. The robot arms are depicted for different snapshots. The actuator toques are depicted in Fig. 28.

Fig. 27
figure 27

The end-effector position for the task-space approximate Jacobian regulator with adaptive gravity compensation

Fig. 28
figure 28

Actuator torques u 1, u 2 for the task-space approximate Jacobian regulator with adaptive gravity compensation

Adaptive Jacobian Tracking Control

In this case, the adaptive Jacobian tracking control Eq. 90 together with the kinematic parameter update law Eq. 91 and dynamic parameter update law Eq. 92 is applied to the two-link robot manipulator for trajectory tracking in the presence of uncertain kinematics and dynamics. The controller gains were chosen as K p = diag{800, 800} and K v = diag{80, 80}. The adaptive gains were chosen as L k = 5 and L d = 5. The initial values of the unknown parameters were chosen as \( \widehat{\varphi}(0)={\left[0,0\right]}^T \). The initial position and velocity of robot’s end effector were x = [0, 0.15] and x d = [0, 0], respectively. The desired trajectory was set as

$$ {x}_d(t)=\left[\begin{array}{c}\hfill 0.15+0.05 \sin \left(t/2\right)\hfill \\ {}\hfill 0.15+0.05 \cos \left(t/2\right)\hfill \end{array}\right]. $$
(108)

The initial values of the unknown kinematic and dynamic parameters \( \left({\widehat{\theta}}_k(0)\kern0.24em \mathrm{and}\kern0.24em {\widehat{\theta}}_d(0)\right) \) were chosen randomly from the interval [0, 10]. The end-effector position is depicted in Fig. 29. The robot arms are depicted for different snapshots.

Fig. 29
figure 29

The end-effector position for the task-space adaptive Jacobian tracking control

Summary

This chapter introduces robot control design methods using the Lyapunov based method. By utilizing the physical properties of the robot kinematics and dynamics, several set-point and adaptive tracking controllers have been presented in both the joint space and task space. A simple motion controller that is effective for set-point regulation is the PD controller with gravity compensation. For tracking control tasks, the adaptive controller has been presented for a robot manipulator with uncertain dynamics. Using sensory feedback of the robot end-effector position in the task space, approximate Jacobian set-point controllers and adaptive Jacobian tracking controllers have been presented for robot manipulators with uncertainties in both kinematics and dynamics.