1 Introduction

In automated manufacturing processes, robotic manipulators are often equipped with rotary process tools as end effectors, enabling robots to perform certain important tasks, such as drilling, grinding and deburring. When the rotating parts of these rotary process tools have uneven mass distribution relative to their axes of rotation, this rotating unbalance can cause significant disturbances to robotic manipulators, especially to direct-drive robots. These unknown disturbances to robots can deteriorate working precision of corresponding automated manufacturing processes. Such a problem can also arise when a robotic manipulator is fitted with an eccentric mixer, milling tool or rotary table [1].

Disturbance observers (DOBs) are an effective tool to estimate unknown disturbances or physical quantities [2]. There have been many disturbance observers devised for robotic manipulators. It is a well-known fact that robotic manipulators generally have highly nonlinear dynamics. Based on linear models, the studies [3,4,5] employed linear disturbance observers for robotic manipulators, in which unmodeled nonlinearities are considered unknown disturbances. Rather than using linear or linearized models, the study [6] proposed a nonlinear disturbance observer (NDOB) for 2-DoF (degrees of freedom) robotic manipulators. The studies [7, 8] extended the NDOB design to n-DoF robotic manipulators. However, the time derivative of a lumped disturbance in these studies [6,7,8] is assumed to be zero, which implies limited applicability of the NDOB to robotic manipulators subject to unbalanced rotating payloads [9]. Chen [10] released this assumption and considered disturbances generated by a general linear system [11], in which the unknown disturbance is considered a scalar. Nevertheless, the disturbance in a robotic manipulator is often not a scalar. Afterward, the study [12] considered an unknown disturbance of vector form but with an assumption that the second derivative of the disturbance is zero.

Sliding-mode techniques are known for enhancing robustness of uncertain systems subject to modelling uncertainties and external disturbances [13,14,15]. Appealing for robustness, previous studies have integrated sliding-mode techniques into the design of disturbance observers [16]. For robotic manipulators, the study [17] proposed a sliding-mode disturbance observer (SMDOB) with guaranteed stability. However, the first derivatives of disturbances with respect to time are assumed to be bounded. Recently, the study [18] released this assumption and only required continuous differentiability of disturbances relating to state-dependent modeling uncertainties with implementation complexity lower than that in [19]. However, no experimental results were reported in [18, 19]. More importantly, these SMDOBs [17,18,19] are not specifically designed to deal with disturbances due to unbalanced rotating payloads of robotic manipulators. Moreover, switching gains of these SMDOBs [17,18,19] need to be manually determined by trial-and-error. If the switching gains are chosen smaller than required, then a sliding mode cannot be ensured for disturbance estimation. On the contrary, if they are larger than needed, then the undesirable chattering phenomenon can appear. Besides, since the required magnitudes of switching gains can vary due to different operating conditions of a robotic manipulator, it is difficult to have fixed switching gains that are appropriate for all operating conditions. Thus, it is essential to have the switching gains auto-tuned.

This paper presents an SMDOB design for robotic manipulators subject to unbalanced rotating payloads. More specifically, this paper extends the single-input single-output design [20] to robotic manipulators with multiple inputs and outputs. Furthermore, an algorithm is presented to adaptively adjust the switching gains. This algorithm can ensure the existence of a sliding mode in a finite time and is able to decrease the switching gains whenever it can. The experimental results are reported in this paper, and a comparative study is also performed in this paper, in which the DOB presented in [11] are experimentally compared with the scheme proposed in this paper.

2 Background materials

Consider an n-DoF robotic manipulator described in joint space by

$$ {\mathbf{M}}{(}{\mathbf{q}}{)}{\mathbf{\ddot{q}}} + {\mathbf{B}}{(}{\mathbf{q}}{,}{\dot{\mathbf{q}}}{)}{\dot{\mathbf{q}}} + {\mathbf{g}}{(}{\mathbf{q}}{)} = {\mathbf{u}} + {\mathbf{d}}, $$
(1)

where \({\mathbf{q}}\) denotes an n-dimensional vector of generalized joint coordinates, \({\mathbf{u}}\) is an n-dimensional vector of generalized control forces, \({\mathbf{M}}{(}{\mathbf{q}}{)}\) is an \(n \times n\) inertia matrix being symmetric and positive definite, \({\mathbf{B}}{(}{\mathbf{q}}{,}{\dot{\mathbf{q}}}{) }{\dot{\mathbf{q}}}\) corresponds to the Coriolis and centrifugal forces, and \({\mathbf{g}}({\mathbf{q}})\) is the gravity force. Moreover, \({\mathbf{d}}\) denotes an n-dimensional vector of unknown disturbances, including the effects due to modeling uncertainties.

Let the control law for (1) be

$$ {\mathbf{u}} = {\mathbf{u}}_{{{\text{nom}}}} - {\hat{\mathbf{d}}}, $$
(2)

in which \({\mathbf{u}}_{{{\text{nom}}}}\) is determined by a nominal controller, and \({\hat{\mathbf{d}}}\) is a disturbance estimate produced by a DOB. Consider a reference trajectory, \({\mathbf{q}}_{{\text{d}}}\), and define the tracking error as

$$ {\mathbf{e}} = {\mathbf{q}} - {\mathbf{q}}_{{\text{d}}} . $$
(3)

Let the nominal controller be described by

$$ {\mathbf{u}}_{{{\text{nom}}}} = {\mathbf{M\dot{v}}} + {\mathbf{Bv}} + {\mathbf{g}} - {\mathbf{K}}_{1} {\mathbf{s}}, $$
(4)

in which \({\mathbf{K}}_{1} = {\text{diag(}}K_{11} {, }K_{12} {, } \ldots , \, K_{1n} ),\) \({\mathbf{v}} = {\dot{\mathbf{q}}}_{{\text{d}}} - {\mathbf{K}}_{0} {\mathbf{e}},\) \({\mathbf{s}} = {\dot{\mathbf{e}}} + {\mathbf{K}}_{0} {\mathbf{e}},\) and \({\mathbf{K}}_{0} = {\text{diag(}}K_{01} {, }K_{02} {, } \ldots , \, K_{0n} {)}{\text{.}}\) Here, all diagonal elements of \({\mathbf{K}}_{0}\) and \({\mathbf{K}}_{1}\) are positive design parameters. The aim of this paper is to propose a disturbance observer that produces \({\hat{\mathbf{d}}}\) for robotic manipulators. Here the auxiliary nominal control, described by (4), is conventional and popular for the control of robotic manipulators in joint space. From a structural point of view, this nominal control is constructed by combining proportional–derivative (PD) control and several compensation terms. Hence, it is also referred to as PD control with compensation in the literature [21].

In what follows, the DOB presented in [11] will be briefly summarized, and this DOB is referred to as Chen’s DOB. As it is in [6], a two-link robotic manipulator is considered for the sake of simplicity in this section. That is, \({\mathbf{d}} = \left[ {\begin{array}{*{20}c} {d_{1} } & {d_{2} } \\ \end{array} } \right]^{{\text{T}}} ,\) \({\mathbf{q}} = \left[ {\begin{array}{*{20}c} {q_{{1}} } & {q_{{2}} } \\ \end{array} } \right]^{{\text{T}}} ,\) where \(q_{{1}}\) and \(q_{{2}}\) are, respectively, the first and the second joint coordinates, and \(d_{{1}}\) and \(d_{2}\) are unknown disturbances referred to the first and the second joints, respectively.

In [11], the Chen’s DOB is designed for a plant described by

$$ {\dot{\mathbf{x}}}(t) = {\mathbf{f}}({\mathbf{x}}(t)) + {\mathbf{g}}_{1} ({\mathbf{x}}(t)){\mathbf{u}} + {\mathbf{g}}_{2} ({\mathbf{x}}(t))d(t), $$
(5)
$$ {\mathbf{y}}(t) = {\mathbf{h}}({\mathbf{x}}(t)), $$
(6)

in which \({\mathbf{x}} \in R^{2n} ,\) \(d\) is a scalar disturbance, and \({\mathbf{f}}({\mathbf{x}})\), \({\mathbf{g}}_{1} ({\mathbf{x}})\) and \({\mathbf{g}}_{2} ({\mathbf{x}})\) are smooth functions of \({\mathbf{x}}\). It is assumed that the scalar disturbance is produced by an exogenous system given by

$$ {\dot{\mathbf{\zeta }}} = {\mathbf{A}}_{{\text{c}}} {{\varvec{\upzeta}}}, $$
(7)
$$ d = {\mathbf{C}}_{{\text{c}}} {{\varvec{\upzeta}}}, $$
(8)

where \({{\varvec{\upzeta}}} \in R^{m} .\) For a two-link robotic manipulator, the disturbance is assumed to act on the tip of the second link [11]; that is, \(d_{{2}} = d,\) and \({\hat{\mathbf{d}}}{ = }\left[ {\begin{array}{*{20}c} 0 & {\hat{d}} \\ \end{array} } \right]^{{\text{T}}} ,\) in which \(\hat{d}\) denotes an estimate of \(d.\) Furthermore, the functions in (4) are given by

\({\mathbf{f}}({\mathbf{x}}) = \left[ {\begin{array}{*{20}c} {\dot{q}_{1} } \\ {\dot{q}_{2} } \\ { - {\mathbf{M}}^{ - 1} ({\mathbf{B\dot{q}}} + {\mathbf{g}})} \\ \end{array} } \right]\), \({\mathbf{g}}_{1} ({\mathbf{x}}) = \left[ {\begin{array}{*{20}c} {{\mathbf{0}}_{2 \times 2} } \\ {{\mathbf{M}}^{ - 1} } \\ \end{array} } \right]\), \({\mathbf{g}}_{2} ({\mathbf{x}}) = {\mathbf{g}}_{1} \left[ {\begin{array}{*{20}c} 0 \\ 1 \\ \end{array} } \right],\) where \({\mathbf{x}}{ = }\left[ {\begin{array}{*{20}c} {q_{1} } & {q_{{2}} } & {\dot{q}_{1} } & {\dot{q}_{{2}} } \\ \end{array} } \right]^{{\text{T}}} .\) In [11], \(d\) is assumed to be a pure sinusoid. In this paper, \(d\) is considered a sinusoid plus a dc component that commonly appears in a robotic system. Let \({\mathbf{A}}_{{\text{c}}} = \left[ {\begin{array}{*{20}c} 0 & 1 & 0 \\ { - \omega_{0}^{2} } & 0 & 1 \\ 0 & 0 & 0 \\ \end{array} } \right]\) and \({\mathbf{C}}_{{\text{c}}} = \left[ {\begin{array}{*{20}c} {1} & {0} & {0} \\ \end{array} } \right]\), in which \(\omega_{0}\) is the frequency of the major ac disturbance and is set equal to the rotational frequency of the rotary process tool attached to a robotic manipulator. The Chen’s DOB is given by

$$ \begin{gathered} {\dot{\mathbf{\upsilon }}} = \left( {{\mathbf{A}}_{{\text{c}}} - {\mathbf{l}}({\mathbf{x}}){\mathbf{g}}_{2} ({\mathbf{x}}){\mathbf{C}}_{{\text{c}}} } \right){{\varvec{\upupsilon}}} + {\mathbf{A}}_{{\text{c}}} {\mathbf{p}}({\mathbf{x}}) \\ - {\mathbf{l(x)}}\left( {{\mathbf{g}}_{2} ({\mathbf{x}}){\mathbf{C}}_{{\text{c}}} {\mathbf{p}}({\mathbf{x}}) + {\mathbf{f}}({\mathbf{x}}) + {\mathbf{g}}_{1} ({\mathbf{x}}){\mathbf{u}}} \right), \\ \end{gathered} $$
(9)
$$ {\hat{\mathbf{\zeta }}} = {{\varvec{\upupsilon}}} + {\mathbf{p}}({\mathbf{x}}), $$
(10)
$$ \hat{d} = {\mathbf{C}}_{{\text{c}}} {\hat{\mathbf{\zeta }}}, $$
(11)

where \({{\varvec{\upupsilon}}}\) is the observer’s state vector, \({\mathbf{l(x)}} = {{\partial {\mathbf{p(x)}}} \mathord{\left/ {\vphantom {{\partial {\mathbf{p(x)}}} {\partial {\mathbf{x}}}}} \right. \kern-\nulldelimiterspace} {\partial {\mathbf{x}}}}\), and \({\mathbf{p}}({\mathbf{x}}) = {\mathbf{K}}_{{\text{c}}} L_{{\mathbf{f}}}^{{}} {\mathbf{h}}({\mathbf{x}}) = {\mathbf{K}}_{{\text{c}}} \dot{q}_{{2}}\) [11]. Here, \(L\) denotes Lie derivatives, and \({\mathbf{K}}_{{\text{c}}} = [K_{{{\text{c1}}}} \, K_{{{\text{c2}}}} \, K_{{{\text{c3}}}} ]^{{\text{T}}}\) is a gain vector to be designed.

3 Proposed SMDOB for robotic manipulators

For an n-DoF robotic manipulator with an unbalanced rotating process tool, the disturbance is an n-dimensional vector, that is, \({\mathbf{d}} = \left[ {\begin{array}{*{20}c} {d_{1} } & {d_{2} } & \cdots & {d_{n} } \\ \end{array} } \right]^{{\text{T}}}\), in which each element, \(d_{i} , \, i = 1, \cdots ,n,\) is assumed to be produced by an exogenous system described by (7) and (8). Hence, the disturbance can be expressed as

$$ {\dot{\mathbf{\xi }}} = {\mathbf{A}}_{{\text{d}}} {{\varvec{\upxi}}}, $$
(12)
$$ {\mathbf{d}} = {\mathbf{C}}_{{\text{d}}} {{\varvec{\upxi}}}, $$
(13)

in which \({{\varvec{\upxi}}} \in R^{n \times m}\), and \(\left\{ {{\mathbf{A}}_{{\text{d}}} , \, {\mathbf{C}}_{{\text{d}}} } \right\}\) is assumed to be an observable pair.

In the proposed SMDOB, an auxiliary process is introduced, whose state vector is denoted as \({\mathbf{z}} \in R^{n}\) with an initial value of \({\mathbf{z}}({0}) = {\dot{\mathbf{q}}}({0}).\) Let the auxiliary process be described by

$$ {\mathbf{M}}({\mathbf{q}}){\dot{\mathbf{z}}} = - {\mathbf{B}}({\mathbf{q}},{\dot{\mathbf{q}}}) {\dot{\mathbf{q}}} - {\mathbf{g}}({\mathbf{q}}) + {\mathbf{u}} + {\hat{\mathbf{d}}} - {\mathbf{B}}({\mathbf{q}},{\dot{\mathbf{q}}}){{\varvec{\upsigma}}} + {{\varvec{\Phi}}}, $$
(14)

in which the switching function, \({{\varvec{\upsigma}}}\), is defined as \({{\varvec{\upsigma}}} = {\mathbf{z}} - {\dot{\mathbf{q}}},\) the switching signal, \({{\varvec{\Phi}}},\) is defined as \({{\varvec{\Phi}}} = - {\mathbf{K}}_{{\text{s}}} {\text{sgn}} ({{\varvec{\upsigma}}})\), and \({\mathbf{K}}_{{\text{s}}} = {\text{diag(}}K_{{{\text{s1}}}} {, }K_{{{\text{s2}}}} {, } \cdots \, K_{{{\text{s}}n}} {)}\) is the switching-gain matrix to be manually assigned or auto-tuned. It is assumed that \(K_{{{\text{s}}i}} > \left| {d_{i} - \hat{d}_{i} } \right|,\) \(i = 1, \cdots ,n.\) The proposed disturbance estimate, \({\hat{\mathbf{d}}}\), is given by

$$ {\mathbf{\dot{\hat{\xi }}}} = {\mathbf{A}}_{{\text{d}}} {\hat{\mathbf{\xi }}} + {\mathbf{L}}({{\varvec{\Phi}}} - {\mathbf{B\sigma }}) + {\mathbf{P}}^{ - 1} {\mathbf{C}}_{{\text{d}}}^{{\text{T}}} {\mathbf{s}}, $$
(15)
$$ {\hat{\mathbf{d}}} = {\mathbf{C}}_{{\text{d}}} {\hat{\mathbf{\xi }}}, $$
(16)

in which \({\hat{\mathbf{\xi }}}\) is an estimate of \({{\varvec{\upxi}}}\), \({\mathbf{P}}\) is positive definite, and \({\mathbf{L}}\) is a gain matrix to be designed.

To verify if the sliding mode, \({{\varvec{\upsigma}}} = {\mathbf{0}},\) is ensured, consider a Lyapunov candidate

$$ V_{{\text{o}}} = {{\varvec{\upsigma}}}^{{\text{T}}} {\mathbf{M}}({\mathbf{q}}){{\varvec{\upsigma}}}. $$
(17)

Differentiating (17) with respect to time and substituting (1) and (14) into the resultant equation gives

$$ \begin{aligned} \dot{V}_{{\text{o}}} &= {2}{{\varvec{\upsigma}}}^{{\text{T}}} {\mathbf{M\dot{\sigma }}} + {{\varvec{\upsigma}}}^{{\text{T}}} {\mathbf{\dot{M}\sigma }} = {2}{{\varvec{\upsigma}}}^{{\text{T}}} {\mathbf{M}}({\dot{\mathbf{z}}} - {\mathbf{\ddot{q}}}) + {{\varvec{\upsigma}}}^{{\text{T}}} {\mathbf{\dot{M}\sigma }} \\ &= {2}{{\varvec{\upsigma}}}^{{\text{T}}} ({\hat{\mathbf{d}}} - {\mathbf{B}}({\mathbf{q}},{\dot{\mathbf{q}}}){{\varvec{\upsigma}}} + {{\varvec{\Phi}}} - {\mathbf{d}}) + {2}{{\varvec{\upsigma}}}^{{\text{T}}} {\mathbf{B}}({\mathbf{q}},{\dot{\mathbf{q}}}){{\varvec{\upsigma}}} \\ &= {2}{{\varvec{\upsigma}}}^{{\text{T}}} ({\hat{\mathbf{d}}} - {\mathbf{d}} + {{\varvec{\Phi}}}) = {2}{{\varvec{\upsigma}}}^{{\text{T}}} \left( {{\hat{\mathbf{d}}} - {\mathbf{d}} - {\mathbf{K}}_{{\text{s}}} {\text{sgn}} ({{\varvec{\upsigma}}})} \right) \\ & < {\text{0 if }}\left\| {{\varvec{\upsigma}}} \right\| \ne {0,} \\ \end{aligned} $$
(18)

where the property that \({\dot{\mathbf{M}}} - {2}{\mathbf{B}}\) is skew symmetric [22] has been used. Equation (18) implies the satisfaction of the so-called sliding condition. Furthermore, since \({\mathbf{z}}({0}) = {\dot{\mathbf{q}}}({0}),\) one has \({{\varvec{\upsigma}}}({0}) = {\mathbf{0}}.\) These give \({{\varvec{\upsigma}}}(t) = {\mathbf{0}}\) for all \(t \ge {0}\), which further implies \({\dot{\mathbf{\sigma }}}(t) = {\mathbf{0}}\) for all \(t \ge {0}\) in the sense of equivalent control [23]. Therefore, the switching signal, \({{\varvec{\Phi}}},\) equals \({\mathbf{d}} - {\hat{\mathbf{d}}}\) in the sense of equivalent values; that is,

$$ {{\varvec{\Phi}}} = {\mathbf{d}} - {\hat{\mathbf{d}}}, $$
(19)

which is important to the following stability analysis.

To determine \({\mathbf{L}}\) and \({\mathbf{P}}\) for a stable closed-loop system, consider another Lyapunov candidate

$$ V_{{{\text{oc}}}} = {\mathbf{s}}^{{\text{T}}} {\mathbf{Ms}} + ({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}})^{{\text{T}}} {\mathbf{P}}({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}}). $$
(20)

Taking the first derivative of the first term on the right-hand side of (20) with respect to time gives

$$ \begin{aligned} \frac{{\text{d}}}{{{\text{d}}t}}\left( {{\mathbf{s}}^{{\text{T}}} {\mathbf{Ms}}} \right) &= {2}{\mathbf{s}}^{{\text{T}}} {\mathbf{M\dot{s}}} + {\mathbf{s}}^{{\text{T}}} {\dot{\mathbf{M}}\mathbf{s}} = {2}{\mathbf{s}}^{{\text{T}}} {\mathbf{M}}({\mathbf{\ddot{q}}} - {\dot{\mathbf{v}}}) + {2}{\mathbf{s}}^{{\text{T}}} {\mathbf{Bs}} \\ &= {2}{\mathbf{s}}^{{\text{T}}} \left[ { - {\mathbf{B\dot{q}}} - {\mathbf{g}} + {\mathbf{u}}_{{{\text{nom}}}} - {\hat{\mathbf{d}}} + {\mathbf{d}} - {\mathbf{M\dot{v}}}} \right] + {2}{\mathbf{s}}^{{\text{T}}} {\mathbf{Bs}} \\& = {2}{\mathbf{s}}^{{\text{T}}} \left[ { - {\mathbf{B\dot{q}}} - {\mathbf{g}} + {\mathbf{M\dot{v}}} + {\mathbf{Bv}} + {\mathbf{g}} - {\mathbf{K}}_{1} {\mathbf{s}} - {\hat{\mathbf{d}}} + {\mathbf{d}} - {\mathbf{M\dot{v}}}} \right] \\ &\quad+ {2}{\mathbf{s}}^{{\text{T}}} {\mathbf{Bs}} \\ &= - {2}{\mathbf{s}}^{{\text{T}}} {\mathbf{K}}_{1} {\mathbf{s}} + {2}{\mathbf{s}}^{{\text{T}}} ({\mathbf{d}} - {\hat{\mathbf{d}}}). \, \\ \end{aligned} $$
(21)

From (12), (13), (15), (16), and (19), it gives

$$ \begin{aligned} \frac{{\text{d}}}{{{\text{d}}t}}({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}}) & = {\mathbf{A}}_{{\text{d}}} ({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}}) - {\mathbf{L}}({\mathbf{d}} - {\hat{\mathbf{d}}}) - {\mathbf{P}}^{ - 1} {\mathbf{C}}_{{\text{d}}}^{{\text{T}}} {\mathbf{s}} \\ &= ({\mathbf{A}}_{{\text{d}}} - {\mathbf{LC}}_{{\text{d}}} )({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}}) - {\mathbf{P}}^{ - 1} {\mathbf{C}}_{{\text{d}}}^{{\text{T}}} {\mathbf{s}}. \\ \end{aligned} $$
(22)

Since \(\left\{ {{\mathbf{A}}_{{\text{d}}} , \, {\mathbf{C}}_{{\text{d}}} } \right\}\) is an observable pair, the observer gain, \({\mathbf{L}},\) can be decided using the pole assignment approach so that the matrix, \({\mathbf{A}}_{{\text{d}}} - {\mathbf{LC}}_{{\text{d}}}\), is Hurwitz and has desired eigenvalues. Taking the first derivative of the second term on the right-hand side of (20) with respect to time and using the relation (22) gives

$$ \begin{aligned} & \frac{{\text{d}}}{{{\text{d}}t}}\left[ {({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}})^{{\text{T}}} {\mathbf{P}}({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}})} \right] \\ &= \left[ {\frac{{\text{d}}}{{{\text{d}}t}}({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}})} \right]^{{\text{T}}} {\mathbf{P}}({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}}) + ({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}})^{{\text{T}}} {\mathbf{P}}\frac{{\text{d}}}{{{\text{d}}t}}({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}}) \\& = ({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}})^{{\text{T}}} \left[ {({\mathbf{A}}_{{\text{d}}} - {\mathbf{LC}}_{{\text{d}}} )^{{\text{T}}} {\mathbf{P}} + {\mathbf{P}}({\mathbf{A}}_{{\text{d}}} - {\mathbf{LC}}_{{\text{d}}} )} \right]({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}}) \\ & \quad - {\mathbf{s}}^{{\text{T}}} {\mathbf{C}}_{{\text{d}}} ({\mathbf{P}}^{ - 1} )^{{\text{T}}} {\mathbf{P}}({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}}) - ({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}})^{{\text{T}}} {\mathbf{PP}}^{ - 1} {\mathbf{C}}_{{\text{d}}}^{{\text{T}}} {\mathbf{s}} \\ & = ({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}})^{{\text{T}}} \left[ {({\mathbf{A}}_{{\text{d}}} - {\mathbf{LC}}_{{\text{d}}} )^{{\text{T}}} {\mathbf{P}} + {\mathbf{P}}({\mathbf{A}}_{{\text{d}}} - {\mathbf{LC}}_{{\text{d}}} )} \right]({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}}) \\&\quad - 2{\mathbf{s}}^{{\text{T}}} ({\mathbf{d}} - {\hat{\mathbf{d}}}). \\ \end{aligned} $$
(23)

Since \(({\mathbf{A}}_{{\text{d}}} - {\mathbf{LC}}_{{\text{d}}} )\) is Hurwitz, there exists a positive definite solution, \({\mathbf{P}}\), to the Lyapunov equation

$$ ({\mathbf{A}}_{{\text{d}}} - {\mathbf{LC}}_{{\text{d}}} )^{{\text{T}}} {\mathbf{P}} + {\mathbf{P}}({\mathbf{A}}_{{\text{d}}} - {\mathbf{LC}}_{{\text{d}}} ) = - {\mathbf{Q}} $$
(24)

for any given positive definite matrix, \({\mathbf{Q}}\). Combining (21), (23) and (24) gives

$$ \dot{V}_{{{\text{oc}}}} = - 2{\mathbf{s}}^{{\text{T}}} {\mathbf{K}}_{1} {\mathbf{s}} - ({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}})^{{\text{T}}} {\mathbf{Q}}({{\varvec{\upxi}}} - {\hat{\mathbf{\xi }}}) < {0}, $$
(25)

which implies that \({\mathbf{s}} \to {\mathbf{0}}\) and \({\hat{\mathbf{\xi }}} \to {{\varvec{\upxi}}}\) as \(t \to \infty ,\) ensuring the asymptotic stability of the overall system. Figure 1 shows the block diagram of the proposed controller/observer system with constant switching gains.

Fig. 1
figure 1

Block diagram of the proposed SMDOB system

4 Automatic switching-gain adjustment

The validity of (18), which ensures the existence of a sliding mode, relies on the condition that \(K_{{{\text{s}}i}} > \left| {d_{i} - \hat{d}_{i} } \right|,\) \(i = 1, \cdots ,n.\) This condition requires the switching gains to be larger than the absolute errors in disturbance estimation. However, the magnitude of this error is uneasy to be determined since it can vary with different operating conditions of a robotic manipulator. To alleviate this difficulty, an algorithm for automatically adjusting these switching gains is presented in this section.

Define \(\overline{K}_{{{\text{s}}i}} = \left| {d_{i} - \hat{d}_{i} } \right| + \mu_{i} ,\) \(i = 1, \cdots ,n,\) where \(\mu_{i}\) is an arbitrary positive constant. Assume that \(\left| {\dot{\overline{K}}_{si} } \right| + \delta_{i} < \eta_{i} ,\) \(i = 1, \cdots ,n,\) where \(\delta_{i}\) is an arbitrary positive constant, and \(\eta_{i}\) is positive and assumed to be available. The algorithm for switching-gain adaptation is

$$ \dot{K}_{{{\text{s}}i}} = \left\{ \begin{gathered} - \eta_{i} {\text{, if }}\left| {{\mathbf{M\dot{\sigma }}} + {\mathbf{B\sigma }} + {\mathbf{K}}_{{\text{s}}} {\text{sgn}} ({{\varvec{\upsigma}}})} \right|_{i} + \mu_{i} < K_{{{\text{s}}i}} , \hfill \\ \lambda_{i} \left| {\sigma_{i} } \right| + \eta_{i} {\text{, otherwise,}} \hfill \\ \end{gathered} \right. $$
(26)

in which \(\lambda_{i}\), \(i = 1, \cdots ,n,\) are positive constants and \(\left| {{\varvec{\uppsi}}} \right|_{i}\) denotes the absolute value of the ith component of the vector, \({{\varvec{\uppsi}}}\).

To investigate the stability of this adaptation mechanism, consider a Lyapunov candidate

$$ V_{{{\text{oa}}}} = {{\varvec{\upsigma}}}^{{\text{T}}} {\mathbf{M\sigma }} + \sum\limits_{i = 1}^{n} {\frac{1}{{\lambda_{i} }}(K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} )^{2} } . $$
(27)

Taking the first derivative of \(V_{{{\text{oa}}}}\) with respect to time and using (18) gives

$$ \dot{V}_{{{\text{oa}}}} = 2{{\varvec{\upsigma}}}^{T} \left[ { - {\mathbf{K}}_{s} {\text{sgn}} ({{\varvec{\upsigma}}}) + {\hat{\mathbf{d}}} - {\mathbf{d}}} \right] + 2\sum\limits_{i = 1}^{n} {\frac{1}{{\lambda_{i} }}(K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} )(\dot{K}_{{{\text{s}}i}} - \dot{\overline{K}}_{{{\text{s}}i}} )} $$
$$ = 2\sum\limits_{i = 1}^{n} {\left\{ {\sigma_{i} \left[ { - K_{{{\text{s}}i}} {\text{sgn}} (\sigma_{i} ) + \hat{d}_{i} - d_{i} } \right] + \frac{1}{{\lambda_{i} }}(K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} )(\dot{K}_{{{\text{s}}i}} - \dot{\overline{K}}_{{{\text{s}}i}} )} \right\}.} $$
(28)

Consider the following two situations. The first is when \(\left| {{\mathbf{M\dot{\sigma }}} + {\mathbf{B\sigma }} + {\mathbf{K}}_{{\text{s}}} {\text{sgn}} ({{\varvec{\upsigma}}})} \right|_{i} + \mu_{i} < K_{{{\text{s}}i}} ,\) which is equivalent to \(\left| {d_{i} - \hat{d}_{i} } \right| + \mu_{i} < K_{{{\text{s}}i}}\) or \(\overline{K}_{{{\text{s}}i}} < K_{{{\text{s}}i}}\). In this situation, Eq. (26) gives \(\dot{K}_{{{\text{s}}i}} = - \eta_{i} ,\) and the term with an index of i in (28) becomes

$$ \begin{aligned}& \sigma_{i} \left[ { - K_{{{\text{s}}i}} {\text{sgn}} (\sigma_{i} ) + \hat{d}_{i} - d_{i} } \right] + \frac{1}{{\lambda_{i} }}(K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} )(\dot{K}_{{{\text{s}}i}} - \dot{\overline{K}}_{{{\text{s}}i}} ) \hfill \\ &= \sigma_{i} \left[ { - K_{{{\text{s}}i}} {\text{sgn}} (\sigma_{i} ) + \hat{d}_{i} - d_{i} } \right] + \frac{1}{{\lambda_{i} }}(K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} )( - \eta_{i} - \dot{\overline{K}}_{{{\text{s}}i}} ) \hfill \\ & < \sigma_{i} \left[ { - \left| {d_{i} - \hat{d}_{i} } \right|{\text{sgn}} (\sigma_{i} ) - \mu_{i} {\text{sgn}} (\sigma_{i} ) + \hat{d}_{i} - d_{i} } \right] \hfill \\ &\quad+ \frac{1}{{\lambda_{i} }}(K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} )\left[ { - \left| {\dot{\overline{K}}_{{{\text{s}}i}} } \right| - \delta_{i} + \left| {\dot{\overline{K}}_{{{\text{s}}i}} } \right|} \right] \hfill \\ & < - \mu_{i} \left| {\sigma_{i} } \right| - \frac{{\delta_{i} }}{{\lambda_{i} }}\left| {K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} } \right|. \hfill \\ \end{aligned} $$
(29)

The other is when \(\left| {{\mathbf{M\dot{\sigma }}} + {\mathbf{B\sigma }} + {\mathbf{K}}_{{\text{s}}} {\text{sgn}} ({{\varvec{\upsigma}}})} \right|_{i} + \mu_{i} \ge K_{{{\text{s}}i}}\), which implies \(\left| {d_{i} - \hat{d}_{i} } \right| + \mu_{i} \ge K_{{{\text{s}}i}}\) and \(\overline{K}_{{{\text{s}}i}} \ge K_{{{\text{s}}i}}\). In this second situation, \(\dot{K}_{{{\text{s}}i}} = \lambda_{i} \left| {\sigma_{i} } \right| + \eta_{i} ,\) and the term with an index of i in (28) becomes

$$ \begin{aligned} &\sigma_{i} \left[ { - K_{{{\text{s}}i}} {\text{sgn}} (\sigma_{i} ) + \hat{d}_{i} - d_{i} } \right] + \frac{1}{{\lambda_{i} }}(K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} )(\dot{K}_{{{\text{s}}i}} - \dot{\overline{K}}_{{{\text{s}}i}} ) \hfill \\ &= \sigma_{i} \left[ { - K_{{{\text{s}}i}} {\text{sgn}} (\sigma_{i} ) + \hat{d}_{i} - d_{i} } \right] + \frac{1}{{\lambda_{i} }}(K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} )\left( {\lambda_{i} \left| {\sigma_{i} } \right| + \eta_{i} - \dot{\overline{K}}_{{{\text{s}}i}} } \right) \hfill \\ &= \sigma_{i} \left[ { - K_{{{\text{s}}i}} {\text{sgn}} (\sigma_{i} ) + \hat{d}_{i} - d_{i} } \right] + (K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} )\left| {\sigma_{i} } \right| \hfill \\ &\quad + \frac{1}{{\lambda_{i} }}(K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} )\left( {\eta_{i} - \dot{\overline{K}}_{{{\text{s}}i}} } \right) \hfill \\ & { = }\sigma_{i} \left[ { - \overline{K}_{{{\text{s}}i}} {\text{sgn}} (\sigma_{i} ) + \hat{d}_{i} - d_{i} } \right] + \frac{1}{{\lambda_{i} }}(K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} )\left( {\eta_{i} - \dot{\overline{K}}_{{{\text{s}}i}} } \right) \hfill \\ & \le \sigma_{i} \left[ { - \left| {d_{i} - \hat{d}_{i} } \right|{\text{sgn}} (\sigma_{i} ) - \mu_{i} {\text{sgn}} (\sigma_{i} ) + \hat{d}_{i} - d_{i} } \right] \hfill \\ &\quad + \frac{1}{{\lambda_{i} }}(K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} )\left[ {\left| {\dot{\overline{K}}_{{{\text{s}}i}} } \right| + \delta_{i} - \dot{\overline{K}}_{{{\text{s}}i}} } \right] \le - \mu_{i} \left| {\sigma_{i} } \right| - \frac{{\delta_{i} }}{{\lambda_{i} }}\left| {K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} } \right|. \hfill \\ \end{aligned} $$
(30)

Combing the results, (29) and (30), from these two situations, one has

$$ \dot{V}_{{{\text{oa}}}} \le 2\sum\limits_{i = 1}^{n} {\left( { - \mu_{i} \left| {\sigma_{i} } \right| - \frac{{\delta_{i} }}{{\lambda_{i} }}\left| {K_{{{\text{s}}i}} - \overline{K}_{{{\text{s}}i}} } \right|} \right)} , $$
(31)

which implies that \(\sigma_{i} \to 0\) and \(K_{{{\text{s}}i}} \to \overline{K}_{{{\text{s}}i}}\) in a finite time. Hence, the finite-time convergence of the observer with the adaptation mechanism is ensured.

5 Experimental evaluation

5.1 Experimental system

As shown in Fig. 2, the experimental manipulator is planar, has three links and three revolute joints, and is directly driven by three motors. Link 3, together with motor 3, is considered the end effector and used to emulate an unbalanced rotary process tool. Figure 3 shows a photograph of the experimental robotic manipulator with rotating link 3. Motors 1 and 2 are, respectively, SGMAH-04AAA41 and SGMAH-01AAA41 having rated torque of 1.27 and 0.318 Nm from Yaskawa Electric Corporation. Motor 3 is 2342S024CR from Faulhaber with rated power of 16 W. Motor 3 that drives link 3 is velocity-controlled by a linear proportional–integral controller with gravity compensation, and its speed is controlled at 10 rps, which produces disturbances with a major ac component of 10 Hz.

Fig. 2
figure 2

CAD model of the experimental manipulator

Fig. 3
figure 3

Photograph of the experimental manipulator

The controller’s central part is a Texas Instruments TMS320C6713 digital signal processor along with a Xilinx XCV50PQ240-C6 field-programmable gate array. A sampling period of 0.0819 ms is chosen for real-time implementation of digitized controller/observer algorithms. The controller hardware is similar to that in [24]. Please refer to [24] for more details about the controller hardware.

5.2 Controller/observer design

Figure 4 shows a schematic of the robotic manipulator, where all joint angles are defined. Table 1 provides symbols and definitions of physical parameters and their nominal values. Since link 3 along with motor 3 is used as an end effector, the robotic manipulator is considered to have 2 DoFs, i.e., \(n = 2\) for controller/observer designs. The 2-DoF mathematic model of the manipulator used in this paper is the same as that in [24] and is not repeated in this paper.

Fig. 4
figure 4

Schematic of the experimental manipulator

Table 1 Physical parameters for the manipulator

For the nominal controller (4), let \({\mathbf{K}}_{0} {\text{ = diag(}}10, \, 10{)}\) and \({\mathbf{K}}_{1} {\text{ = diag(0}}{.02},{ 0}{\text{.06)}}\). Moreover, velocity signals are low-pass filtered with an edge frequency of 200 rad/s to attenuate high-frequency noise. For the Chen’s DOB, choose \({\mathbf{K}}_{{\text{c}}} { = }K_{{\text{c}}} \left[ {\begin{array}{*{20}c} 1 & 1 & 1 \\ \end{array} } \right]^{{\text{T}}}\) with \(K_{{\text{c}}} { = 0}{\text{.05 or 0}}{.10,}\) and \(\omega_{0} = 20\pi .\) For the SMDOB, let \({\mathbf{K}}_{{\text{s}}} {\text{ = diag(0}}{.24},{ 0}{\text{.18),}}\) \({\mathbf{Q}} = 1000{\mathbf{I}},\) and the observer gain, \({\mathbf{L}},\) is determined so that the matrix, \({\mathbf{A}}_{{\text{d}}} - {\mathbf{LC}}_{{\text{d}}}\), has all eigenvalues equal \(- 30\).

5.3 Experimental results with fixed gains

The first two joints of the manipulator are initially unactuated, but the third joint rotates at approximate 10 rps, i.e., \(q_{{1}} {(}0) \approx {{ - \pi } \mathord{\left/ {\vphantom {{ - \pi } 2}} \right. \kern-\nulldelimiterspace} 2}\) rad, \(q_{2} {(}0) \approx 0\), and \(\dot{q}_{3} {(}0) \approx 20\pi\) rad/s. Let \({\mathbf{q}}_{{\text{d}}} { = }\left[ {\begin{array}{*{20}c} { - {\pi \mathord{\left/ {\vphantom {\pi {2 + 1}}} \right. \kern-\nulldelimiterspace} {2 + 1}}} & 1 \\ \end{array} } \right]^{{\text{T}}}\) rad.

Figure 5 shows step responses using the nominal controller only, demonstrating that the angular position of joint 2 is obviously influenced by the unbalanced rotating payload. Figure 6 shows step responses using the Chen’s DOB with \(K_{{\text{c}}} { = 0}{\text{.05 and 0}}{.10,}\) in which larger \(K_{{\text{c}}}\) produces more oscillatory control efforts but smaller position errors. Comparing the output responses shown in Figs. 5 and 6, it is seen that the Chen’s DOB can diminish the positioning error of joint 2. However, since the Chen’s DOB only tries to compensate for the disturbance to joint 2, the disturbance to joint 1 is not well compensated for by the Chen’s DOB. It is worth noting that although the Chen’s DOB includes the disturbance model for joint 2, the response error of joint 1 deteriorates the performance of joint 2. Figure 7 shows step responses with the SMDOB. Comparing the output responses shown in Figs. 5, 6 and 7, it is seen that the SMDOB augments the nominal controller and that the SMDOB outperforms the Chen’s DOB.

Fig. 5
figure 5

Step responses using the nominal controller only

Fig. 6
figure 6

Step responses with the Chen’s DOB

Fig. 7
figure 7

Step responses with the SMDOB

Consider a task of contour tracking, in which the desired contour, \((x_{{\text{d}}} , \, y_{{\text{d}}} )\), is defined by

$$ x_{{\text{d}}} = x_{0} + \ell \left( {1 - \sin \theta } \right)\cos \theta , $$
(32)
$$ y_{{\text{d}}} = y_{0} + \ell \left( {1 - \sin \theta } \right)\sin \theta , $$
(33)

in which \(\theta = - {1}.{278}t + {{{3}\pi } \mathord{\left/ {\vphantom {{{3}\pi } {2}}} \right. \kern-\nulldelimiterspace} {2}}\) rad, \((x_{0} , \, y_{0} ) = (0.{0}8, - 0.{0}8),\) and \(\ell = 0.05\) m. Figure 8 shows the contour-following results in Cartesian space using the nominal controller with and without the SMDOB. It is seen that the SMDOB greatly enhances the contour-tracing performance of the nominal controller. Figure 9 shows the corresponding tracking responses in joint space, demonstrating that the proposed SMDOB can counteract the disturbances induced by the rotating payload during trajectory tracking.

Fig. 8
figure 8

Contour following with and without the SMDOB

Fig. 9
figure 9

Tracking responses with and without the SMDOB

5.4 Results with automatic switching-gain adjustment

The most popular technique for auto-tuning the switching gains is to increase gains whenever the switching function is nonzero, that is, whenever the sliding mode does not exist [25,26,27]. Using this technique, the adaptation law for switching-gain adjustment would be \(\dot{K}_{{{\text{s}}i}} = \lambda_{i} \left| {\sigma_{i} } \right|,\) \(i = 1,2.\) This technique is straightforward but would cause the switching gains to grow unboundedly. Because the switching functions, \(\sigma_{i}\), \(i = 1,2,\) can never be constrained at zero in practice. On the contrary, the algorithm, described by (26), allows the switching gains to be reduced if the switching gains are large enough.

In the following experiments with gain adaptation, the switching gains are initially set to zero, i.e., \(K_{{{\text{s}}i}} (0) = 0,\) \(i = 1,2.\) Figure 10 shows step responses with and without the adaptation mechanism, in which the parameters are chosen to be \(\lambda_{i} = 10,\) \(\eta_{i} = 0.12,\) \(\mu_{1} = 0.15,\) \(\mu_{2} = 0.05,\) \(i = 1,2.\) It is seen that the output responses with and without gain adaptation are similar. Moreover, the switching gains increase rapidly from zero during an initial period and decrease gradually following this rapid increase. Afterward, the adaptation mechanism can either increase or decrease the switching gains, depending on practical situations. Figure 11 shows tracking responses with and without gain adaptation in joint space during the task of contour tracking. As shown in Fig. 11, the output responses without gain adaptation are comparable to those with fixed gains. The benefits of using the presented adaptation mechanism are that it enables smaller switching gains to be used during the tracking task and that it adapts the switching gains according to variable operating conditions, which is impossible for the one using fixed switching gains.

Fig. 10
figure 10

Step responses with and without gain adaptation

Fig. 11
figure 11

Tracking responses with and without gain adaptation

6 Conclusion

This paper presents an SMDOB for robotic manipulators with unbalanced rotating payloads. Asymptotic stability of the closed-loop system that includes the SMDOB as well as the nominal controller is guaranteed using the Lyapunov stability criterion. Furthermore, this paper presents a switching-gain adaptation law that can ensure the existence of a sliding mode in a finite time and is able to decrease switching gains according to practical situations. The experimental results on a direct-drive robotic manipulator with a rotating arm are reported, practically demonstrating the efficiency of the proposed system.