1 Introduction

Studies on underactuated mechanical systems, which possess fewer actuators than degrees of freedom (DOF), have received considerable interest in the last two decades. In mobile robotic locomotion (legged, wheeled, swimming, flying, etc.), underactuation is an inherent property of the system since the degrees of freedom that describe net body motion are not directly actuated. Moreover, underactuation may alternatively be a consequence of on-purpose “minimalistic” design without using full actuation or that of the failure of one or more actuators. However, it is difficult to control these systems due to their complex nonlinear dynamics and nonholonomic behavior, see pioneer works in [10, 15, 25, 26], and other interesting results in [2,3,4, 7,8,9, 13, 18, 19, 22, 24, 27,28,29].

Many researchers investigated the notion of energy shaping in controlling underactuated mechanical systems since energy is an important variable related to the motion of the systems. For an underactuated mechanical system with generalized coordinate \( {\varvec{\theta }}(t)\), [10] and [15] addressed the simultaneous control of both its total mechanical energy \(E({\varvec{\theta }}(t),\dot{{\varvec{\theta }}}(t))\) and actuated variable(s) \({\varvec{\theta }}_a(t)\); that is, whether one can design a controller to achieve

$$\begin{aligned}&\lim _{t\rightarrow \infty } E({\varvec{\theta }}(t),\dot{{\varvec{\theta }}}(t))=E_r, \end{aligned}$$
(1)
$$\begin{aligned}&\lim _{t\rightarrow \infty } {\varvec{\theta }}_a(t)={\varvec{\theta }}_{ar}, \quad \lim _{t\rightarrow \infty } \dot{{\varvec{\theta }}}_a(t)={\varvec{0}}, \end{aligned}$$
(2)

where \(E_r\) is a given constant, \({\varvec{\theta }}_{ar}\) is a given constant vector, and \({\varvec{0}}\) is zero column vector with a compatible size.

For the Pendubot [11, 15], and the Acrobot [32], objectives (1) and (2) have been shown to be achievable for the swing-up and stabilizing control problem, which is to drive the robot to a small neighborhood of its UEP (upright equilibrium point) and then stabilize it around that point, where all links are in the upright position. The above energy-based control is applied to stabilize an unstable equilibrium point of the butterfly robot in [6]. However, [31] showed that objectives (1) and (2) cannot be achieved simultaneously for the swing-up and stabilizing control problem of a 2-link underactuated robot with a particular counterweight connected to the passive first joint. For a set-point control for a folded configuration of 3-link gymnastic planar robot with the first joint being passive (unactuated) and the second and third joints being active (actuated), we proved in [17] that objectives (1) and (2) can be achieved simultaneously if the mechanical parameters of the robot satisfy certain conditions, and we show via a numerical example that objectives (1) and (2) are not achieved simultaneously when the mechanical parameters of the robot do not satisfy these conditions. Thus, for an underactuated system with particular mechanical parameters, although objective (2) can be achieved for example by the partial feedback linearization in [26], it is not clear whether objectives (1) and (2) can be achieved simultaneously.

Although there are many results for mechanical systems with underactuation degree one [1, 10, 12], that is, the number of control inputs is one less than that of degrees of freedom, designing and analyzing controllers for mechanical systems with underactuation degree greater than one are still a challenging problem. For the double pendulum in a cart, [30] showed that objectives (1) and (2) can be achieved with \(E_r\) being the highest potential energy of the double pendulum for almost all initial conditions of the system. Building on this previous research, for a 3-link planar robot in a vertical plane with its first joint being active and the rest joints being passive, this paper studies a theoretically challenging problem, that is, whether objectives (1) and (2) corresponding to the UEP (all three links are in the upright position), and objective (3)

$$\begin{aligned} \lim _{t\rightarrow \infty } {\varvec{\theta }}(t)={\varvec{0}}_{3}, \quad \lim _{t\rightarrow \infty } \dot{{\varvec{\theta }}}(t)={\varvec{0}}_{3}, \end{aligned}$$
(3)

are achievable for almost every initial condition, where \({\varvec{\theta }}(t)\) is the vector of three link angles of the robot, and \({\varvec{0}}_{3}\) denotes a zero column vector with size 3. This is the ultimate objective of stabilizing the robot at the UEP. We call this robot APP (Active Passive Passive) robot below.

This paper applies the procedure in [10, 15] to derive an energy-based controller for the APP robot. By presenting and using a new property of the motion of the APP robot, without any condition on its mechanical parameters, this paper proves that if the control gains are larger than specific lower bounds, then objectives (1) and (2) corresponding to the UEP are achievable for all initial conditions with the exception of a set of Lebesgue measure zero.

Indeed, first, the new property is that if link 1 of the APP robot does not move under a constant torque on joint 1, then links 2 and 3 do not move. To the best of our knowledge, this property has not yet been proved. We present a strict proof of this property for any mechanical parameters of the APP robot, any constant angle of joint 1, and corresponding constant torque by using some properties of the mechanical parameters of the APP robot. Second, the measure-zero set of initial conditions converges to three strictly unstable equilibrium points: the up–up–down, up–down–up, and up–down–down equilibrium points, where, for example, up–up–down means that links 1, 2, and 3 are in the upright, upright, and downward positions, respectively.

The presented control law achieves objectives (1) and (2) corresponding to the UEP for almost all initial conditions but does not achieve objective (3), since the UEP becomes strictly unstable. This motivates the use of the additional LQR-based linear state feedback law. It is worth pointing out that the linear controller succeeds in achieving only local stabilization, from initial conditions in a close neighborhood of the UEP. The combination of switching between the two control laws is then shown to practically achieve all objectives (1), (2), and (3), but no formal proof is found yet that shows that this ALWAYS works.

The remainder of the paper is organized as follows: Sect. 2 gives some preliminary knowledge and problem formulation. Section 3 presents the main results of this paper. Section 4 makes some discussions. Section 5 gives numerical simulation results for a physical 3-link planar robot in [20]. Section 6 makes some concluding remarks. Certain proofs whose details are not central to the flow of the paper are gathered in the appendices. For brevity, we omit time argument t in the expression of a variable if it is clear from the context.

2 Preliminary knowledge and problem formulation

2.1 Preliminary knowledge

Consider a 3-link planar robot with a single actuator at joint 1 (at the origin) shown in Fig. 1. For link i (\(i=1, 2, 3\)), \(m_i\) is its mass, \(l_i\) is its length, \(l_{ci}\) is the distance from joint i to its center of mass (COM), and \(J_{i}\) is the moment of inertia around its COM, \(\tau _1\) is the torque acting at joint 1, and \(\theta _i\) is the angle measured counterclockwise from the positive Y-axis. In this paper, \(\theta _1\), the angle of active joint 1, is dealt in \({\mathbb {R}}\); \(\theta _2\) and \(\theta _3\), the angles of the passive links, are dealt with in \({\mathbb {S}}^2\) (a torus) and take value in \((-\pi , \pi ]\).

Fig. 1
figure 1

APP robot: 3-link planar robot with a single actuator at the first joint

The motion equation of the APP robot is

$$\begin{aligned} {\varvec{M}}({\varvec{\theta }})\ddot{{\varvec{\theta }}}+ {\varvec{C}}({\varvec{\theta }},\dot{{\varvec{\theta }}})\dot{{\varvec{\theta }}}+ {\varvec{g}}({\varvec{\theta }} )={\varvec{b}}\tau _1, \end{aligned}$$
(4)

where \({\varvec{\theta }}= \left[ \begin{array}{ccc} \theta _1,&\theta _2,&\theta _3 \end{array}\right] ^\mathrm{T}\) and

$$\begin{aligned}&{\varvec{M}}({\varvec{\theta }} )\nonumber \\&\quad = \left[ \begin{array}{l@{\quad }l@{\quad }l} \alpha _{11} &{} \alpha _{12}\cos (\theta _2-\theta _1) &{} \alpha _{13}\cos (\theta _3-\theta _1)\\ \alpha _{12}\cos (\theta _2-\theta _1) &{} \alpha _{22} &{} \alpha _{23}\cos (\theta _3-\theta _2)\\ \alpha _{13}\cos (\theta _3-\theta _1) &{} \alpha _{23}\cos (\theta _3-\theta _2)&{} \alpha _{33} \end{array} \right] , \end{aligned}$$
(5)
$$\begin{aligned}&{\varvec{C}}({\varvec{\theta }},\dot{{\varvec{\theta }}})\nonumber \\&\quad = \left[ \begin{array}{l@{\quad }l@{\quad }l} 0 &{} -\alpha _{12}\dot{\theta }_2\sin (\theta _2-\theta _1) &{} -\alpha _{13}\dot{\theta }_3\sin (\theta _3-\theta _1) \\ \alpha _{12}\dot{\theta }_1\sin (\theta _2-\theta _1) &{} 0 &{} -\alpha _{23}\dot{\theta }_3\sin (\theta _3-\theta _2)\\ \alpha _{13}\dot{\theta }_1\sin (\theta _3-\theta _1) &{} \alpha _{23}\dot{\theta }_2 \sin (\theta _3-\theta _2)&{} 0 \end{array} \right] ,\end{aligned}$$
(6)
$$\begin{aligned}&{\varvec{g}}({\varvec{\theta }} )= \left[ \begin{array}{c} -\beta _1 \sin \theta _1 \\ -\beta _2 \sin \theta _2 \\ -\beta _3 \sin \theta _3 \end{array} \right] ,\quad {\varvec{b}}= \left[ \begin{array}{c} 1\\ 0\\ 0 \end{array} \right] \end{aligned}$$
(7)

with

$$\begin{aligned} \left\{ \begin{array}{l} \alpha _{11}=J_1+m_1l_{c1}^2+(m_2+m_3)l_1^2,\\ \alpha _{22}=J_2+m_2l_{c2}^2+m_3l_2^2, \\ \alpha _{33}=J_3+m_3l_{c3}^2,\\ \alpha _{12}= (m_2l_{c2}+m_3l_2)l_1,\\ \alpha _{13}= m_3l_1l_{c3}, \\ \alpha _{23}= m_3l_2l_{c3},\\ \beta _1=(m_1l_{c1}+m_2l_1+m_3l_1)g,\\ \beta _2=(m_2l_{c2}+m_3l_2)g, \\ \beta _3=m_3l_{c3}g, \end{array} \right. \end{aligned}$$
(8)

where g is the acceleration of gravity.

The total mechanical energy of the APP robot is

$$\begin{aligned} E({\varvec{\theta }},\dot{{\varvec{\theta }}})=\frac{1}{2}\dot{{\varvec{\theta }}}^{\mathrm {T}}{\varvec{M}}({\varvec{\theta }}) \dot{{\varvec{\theta }}} + P({\varvec{\theta }}), \end{aligned}$$
(9)

where \(P({\varvec{\theta }})\) is its potential energy defined by

$$\begin{aligned} P({\varvec{\theta }})=\beta _1 \cos \theta _1 +\beta _2 \cos \theta _2 +\beta _3 \cos \theta _3. \end{aligned}$$
(10)

From (4), we have

$$\begin{aligned} \dot{E}({\varvec{\theta }},\dot{{\varvec{\theta }}})&=\dot{{\varvec{\theta }}}^{\mathrm {T}}{\varvec{M}}({\varvec{\theta }})\ddot{{\varvec{\theta }}}+\frac{1}{2}\dot{{\varvec{\theta }}}^{\mathrm {T}}\dot{{\varvec{M}}}({\varvec{\theta }})\dot{{\varvec{\theta }}}+\dot{{\varvec{\theta }}}^{\mathrm {T}}{\varvec{g}}({\varvec{\theta }})\nonumber \\&=\dot{{\varvec{\theta }}}^{\mathrm {T}}\left( -{\varvec{C}}({\varvec{\theta }},\dot{{\varvec{\theta }}})\dot{{\varvec{\theta }}}-{\varvec{g}}({\varvec{\theta }})+{\varvec{b}} \tau _1\right) \nonumber \\&\quad +\frac{1}{2}\dot{{\varvec{\theta }}}^{\mathrm {T}}\dot{{\varvec{M}}}({\varvec{\theta }})\dot{{\varvec{\theta }}}+\dot{{\varvec{\theta }}}^{\mathrm {T}}{\varvec{g}}({\varvec{\theta }})\nonumber \\&=\dot{{\varvec{\theta }}}^{\mathrm {T}}{\varvec{b}} \tau _1+\frac{1}{2}\dot{{\varvec{\theta }}}^{\mathrm {T}}(\dot{{\varvec{M}}}({\varvec{\theta }})-2 {\varvec{C}}({\varvec{\theta }},\dot{{\varvec{\theta }}})) \dot{{\varvec{\theta }}} \end{aligned}$$
(11)
$$\begin{aligned}&=\dot{\theta }_1\tau _1, \end{aligned}$$
(12)

where the second term in the right-hand side of (11) is 0 since \(\dot{{\varvec{M}}}({\varvec{\theta }})-2 {\varvec{C}}({\varvec{\theta }},\dot{{\varvec{\theta }}})\) is a skew-symmetric matrix which can be verified directly by using (5) and (6).

2.2 Problem formulation

Consider the following UEP:

$$\begin{aligned} {\varvec{{\varvec{\theta }}}}(t)={\varvec{0}}_{3}, \; \; \dot{{\varvec{\theta }}}(t)={\varvec{0}}_{3}. \end{aligned}$$
(13)

For \(E({\varvec{\theta }},\dot{{\varvec{\theta }}})\), \(\theta _1\), and \(\dot{\theta }_1\), we design and analyze a controller to address whether objectives (1) and (2) can be achieved, where \(E_r\) is the highest potential energy of the APP robot expressed as:

$$\begin{aligned} E_{r}={\displaystyle E({\varvec{\theta }}(t),\dot{{\varvec{\theta }}}(t))\left| ^{}_{{\varvec{\theta }}(t)={\varvec{0}}_{3},\;\; \dot{{\varvec{\theta }}}(t)={\varvec{0}}_{3}}\right. }=\beta _1+\beta _2+\beta _3,\nonumber \\ \end{aligned}$$
(14)

\({\varvec{\theta }}_a(t)=\theta _1(t)\), and \({\varvec{\theta }}_{ar}=0\).

3 Main results

Define the following controller:

$$\begin{aligned}&\tau _1(t)\nonumber \\&\quad =\frac{k_DB^{\mathrm {T}}{\varvec{M}}^{-1}({\varvec{\theta }}(t))({\varvec{C}} ({\varvec{\theta }}(t),\dot{{\varvec{\theta }}}(t)) \dot{{\varvec{\theta }}}(t)+{\varvec{g}}({\varvec{\theta }}(t)))-k_V \dot{\theta }_1(t) -k_P {\theta }_1(t)}{\eta ({\varvec{\theta }}(t),\dot{{\varvec{\theta }}}(t))}, \end{aligned}$$
(15)

where

$$\begin{aligned} \eta ({\varvec{\theta }}(t),\dot{{\varvec{\theta }}}(t))= & {} E({\varvec{\theta }}(t),\dot{{\varvec{\theta }}}(t))-E_r + k_D {\varvec{b}}^{{\mathrm {T}}}{\varvec{M}}^{-1}({\varvec{\theta }}(t)) {\varvec{b}}.\nonumber \\ \end{aligned}$$
(16)

Below we present the following five lemmas and one theorem. Lemma 1 is about a condition on gain \(k_D\) to guarantee that controller (15) is well defined, whose proof is given in “Appendix 1.”

Lemma 1

\(\eta ({\varvec{\theta }}(t),\dot{{\varvec{\theta }}}(t))\) in (16) is positive for any \(({\varvec{\theta }}(t),\dot{{\varvec{\theta }}}(t))\) if and only if \(k_D\) satisfies

(17)

Lemma 2 is about the invariant set to which every solution of the closed-loop system converges, whose proof is given in “Appendix 2.”

Lemma 2

Consider the closed-loop system consisting of APP robot (4) and controller (15). If \(k_D\) satisfies (17), and

$$\begin{aligned}&k_V>0, \end{aligned}$$
(18)
$$\begin{aligned}&k_P>0, \end{aligned}$$
(19)

then the closed-loop solution, \(({\varvec{\theta }}(t),~\dot{{\varvec{\theta }}}(t))\), converges to the following invariant set:

$$\begin{aligned} W=&\Bigl \{ ({\varvec{\theta }}(t),\dot{{\varvec{\theta }}}(t) ) \ \Bigl . \Bigr | \ \frac{1}{2}\alpha _{22}\dot{\theta }^{2}_2(t) + \alpha _{23}\dot{\theta }_2(t)\dot{\theta }_3(t)\nonumber \\&\quad \times \cos {(\theta _3(t)-\theta _2(t))}+ \frac{1}{2}\alpha _{33}\dot{\theta }^{2}_3(t)\nonumber \\&\quad + P({\varvec{\theta }}(t) )\equiv E^*, \quad \theta _1(t) \equiv \theta _1^*\Bigr \}, \end{aligned}$$
(20)

where “\(\equiv \)” denotes the equation holds for all t.

Lemma 3 shows a new property of the motion of the APP robot with its proof in “Appendix 3.”

Lemma 3

Consider APP robot (4). Suppose \(\theta _1(t)\equiv \theta _1^*\) and \(\tau _1(t)\equiv \tau _1^*\) with \(\theta _1^*\) and \(\tau _1^*\) being constants; that is, link 1 does not move under a constant torque on joint 1. Then, links 2 and 3 do not move; that is,

$$\begin{aligned} \dot{\theta }_2(t)\equiv 0, \quad \dot{\theta }_3(t)\equiv 0 \end{aligned}$$
(21)

for any mechanical parameters described in (8) for the APP robot, \(\theta _1^*\), and \(\tau _1^*\).

Lemma 4 characterizes the invariant set the W in (20) further under a condition on gain \(k_P\), whose proof is presented in “Appendix 4.”

Lemma 4

Consider the closed-loop system consisting of APP robot (4) and controller (15). Suppose that \(k_D\) satisfies (17), \(k_V\) satisfies (18), and \(k_P\) satisfies

$$\begin{aligned}&k_P> k_{Pm}=\max _{\pi \le w \le 2\pi }\nonumber \\&\quad \times \frac{\displaystyle - \beta _1 \left( \beta _1(1-\cos w)+2\beta _2 + 2\beta _3\right) \sin w}{w}. \end{aligned}$$
(22)

Then, the invariant set W in (20) becomes the union

$$\begin{aligned} W=W_r\cup \Omega _s, \end{aligned}$$
(23)

where

$$\begin{aligned} W_r&=\Bigl \{ ({\varvec{\theta }}(t),\dot{{\varvec{\theta }}}(t) ) \ \Bigl . \Bigr | \ \frac{1}{2}\alpha _{22}\dot{\theta }^{2}_2(t) \nonumber \\&\quad + \alpha _{23}\dot{\theta }_2(t)\dot{\theta }_3(t) \cos {(\theta _3(t)-\theta _2(t))} + \frac{1}{2}\alpha _{33}\dot{\theta }^{2}_3(t) \nonumber \\&\quad + \beta _2 (\cos \theta _2(t)-1) +\beta _3 (\cos \theta _3(t)-1)=0, \; \; \nonumber \\&\qquad \theta _1(t)\equiv 0 \Bigr \} \end{aligned}$$
(24)

and

$$\begin{aligned} \Omega _s= & {} \left\{ ({\varvec{\theta }}^*, {\varvec{0}}_{3}) ~ |~ {\varvec{\theta }}^*\equiv \left[ \begin{array}{ccc} 0, &{} 0, &{} \pi \\ \end{array} \right] ^{\mathrm {T}}, ~ \left[ \begin{array}{ccc} 0, &{} \pi , &{} 0 \\ \end{array} \right] ^{\mathrm {T}},\right. \nonumber \\&\times \left. \left[ \begin{array}{ccc} 0, &{} \pi , &{} \pi \\ \end{array} \right] ^{\mathrm {T}}\right\} . \end{aligned}$$
(25)

Moreover, the UEP is the only equilibrium point in \(W_r\).

Lemma 5 is about the stability of all equilibrium points of the closed-loop system, whose proof is presented in “Appendix 5.”

Lemma 5

Consider the closed-loop system consisting of APP robot (4) and controller (15). Given the bounds on the gains in (17), (18), and (22). The UEP and the equilibrium points in \(\Omega _s\) are all strictly unstable.

We present the following main result of this paper.

Theorem 1

Consider the closed-loop system consisting of APP robot (4) and controller (15). Given the bounds on the gains in (17), (18), and (22). The closed-loop solution, \(({\varvec{\theta }}(t),~\dot{{\varvec{\theta }}}(t))\), converges to the invariant set \(W_r\) in (24), except for the measure-zero set of initial conditions that converge to the strictly unstable equilibrium points in the \(\Omega _s\) in (25). The UEP is the only equilibrium point in \(W_r\) and is strictly unstable. Controller (15) achieves objectives (1) and (2) corresponding to the UEP for almost all initial conditions but does not achieve objective (3).

Proof

From Lemmas 4 and 5, since each equilibrium point of \(\Omega _s\) is strictly unstable; that is, the Jacobian matrix evaluated at each equilibrium point of \(\Omega _s\) has at least one eigenvalue in the open right-half plane, the set of initial conditions from which the closed-loop solution converges to \(\Omega _s\) is of Lebesgue measure zero, see, e.g., [21] (p. 1225). In other words, from all initial conditions with the exception of a set of Lebesgue measure zero, the closed-loop solution \(({\varvec{\theta }}(t), \dot{{\varvec{\theta }}}(t))\) converges to the invariant set \(W_r\). Thus, controller (15) achieves objectives (1) and (2) corresponding to the UEP for almost all initial conditions. From Lemmas 4 and 5, we know that the UEP is the only equilibrium point in \(W_r\) and is strictly unstable. Therefore, controller (15) does not achieve objective (3). \(\square \)

4 Discussion

4.1 On the invariant set \(W_r\)

Theorem 1 shows that objectives (1) and (2) corresponding to the UEP are achieved for almost all initial conditions under the proposed energy-based controller (15), provided that the conditions on control gains are satisfied. Even though the UEP is contained in the invariant set \(W_r\) in (24) in \(t\in (0, ~\infty )\), it is unclear that the solution trajectories will come into a close neighborhood of the UEP. In this sense, this paper does not give a general algorithm to guarantee theoretically for achieving the true practical objective of the APP control: stabilization of the UEP from almost any initial conditions.

From our simulation results for the APP robot with mechanical parameters in [20], under the proposed controller (15) there existed moments in \(t\in (0, ~\infty )\) when the robot came into a close neighborhood of the UEP for several initial conditions we simulated. Please refer two examples in Sects. 5.1 and 5.2. The combination of switching between the two control laws is shown by simulation to practically achieve all objectives (1), (2), and (3), but no formal proof is found yet that shows that this ALWAYS works. We would like to investigate it further in the future.

4.2 On Lemma 3 and its proof

There are various applications of symbolic computation in robot manipulator design and analysis, for example, in kinematics, dynamics, trajectory planning, and control [23]. This paper also shows an application of symbolic computation in the proof of Lemma 3, which is important for proving Theorem 1. Below we discuss Lemma 3 and its proof.

First, Lemma 3 means that for APP robot (4), if link 1 is at rest under a constant torque on joint 1, then the entire system is in an equilibrium point. Lemma 3 seems to be intuitive: As long as links 2 and 3 move, the forces acting at the distal joint of link 1 (joint 2) will change which results in a varying moment at the proximal joint of link 1 (joint 1); thus, a varying torque must be applied at joint 1 to keep link 1 balanced. However, by analyzing all the forces acting at three joints, we cannot find more information than motion equation (4). The details are omitted.

Second, it is very difficult to prove Lemma 3 for any mechanical parameters described in (8) for the APP robot, any constant angle of joint 1, and corresponding constant torque because of the strong nonlinear coupling of two passive joints of the APP robot when link 1 of the robot is at rest under a constant torque. Indeed, in its proof we used the properties of the mechanical parameters shown in Lemmas 6 and 7. If \(\sin \theta ^{*}_1 =0\) (link 1 at the vertical position), then the proof of Lemma 3 can be simplified considerably (without need to use symbolic computation), please refer the result for the double pendulum in a cart in [30]. However, if \(\sin \theta ^{*}_1 \ne 0\) (link 1 not at the vertical position), then the proof is much more involved as shown in “Appendix 3.”

If the mechanical parameters of links 2 and 3 of the robot satisfy \(a^2 - a b -a e+1 \ne 0\), where a, b, and e are defined in (34), then we do not need the analysis of Case 2 (\(a^2 - a b -a e+1 =0\)) in the proof of Lemma 3 which is complicated and involved, please refer “Eq. 37 of Appendix 3.” Note that the physical 3-link robot in [20] which is used in the simulation in Sect. 5 satisfies \(a^2 - a b -a e+1 \ne 0\). Moreover, when link 2 of a 3-link robot has a massless rod with a point mass at its end; that is, \(l_{c2}=l_{2}\) and \(J_2=0\), then from (8) we obtain

$$\begin{aligned} a=\frac{\beta _2}{\beta _3}=\frac{(m_2+m_3)l_2}{m_3l_{c3}}, \quad b=\frac{\alpha _{22}}{\alpha _{23}}=\frac{(m_2+m_3)l_2}{m_3l_{c3}}. \end{aligned}$$

Thus, \(a=b\); together with \(ae>1\) due to Lemma 6, \(a^2 - a b -a e+1 < 0\). Note that the massless rod assumption is often used in pendulum-type systems, see, e.g., [5].

5 Simulation results

We present numerical simulation results for an APP robot with its mechanical parameters being given in Table 1, which are taken from the physical 3-link planar robot in [20]. We took \(g=9.8\,\text {m/s}^2\).

Table 1 Mechanical parameters of the physical 3-link planar robot in [20]

From Theorem 1, under controller (15) with conditions (17) and (22); that is, \(k_D>11.2100 {\,\mathrm J}^2 {\,\mathrm s}^2\) and \(k_P>81.1069 {\,\mathrm J}^2\) for this APP robot, and with condition \(k_V>0\), objectives (1) and (2) corresponding to the UEP are achievable from all initial conditions with the exception of a set of Lebesgue measure zero.

Since the UEP is strictly unstable under the proposed energy-based controller according to Lemma 5, when the APP robot is swung up close to the UEP, to stabilize it around the UEP, we need to switch the energy-based controller to a local stabilizing controller designed by LQR method. Define \({\varvec{x}}(t) = \left[ \begin{array}{cccccc} \theta _1(t), &{} \theta _{2}(t), &{} \theta _{3}(t),&{} \dot{\theta }_1(t),&{} \dot{\theta }_2(t), &{} \dot{\theta }_3(t) \\ \end{array} \right] ^{\mathrm {T}}\). The LQR controller is

$$\begin{aligned} \tau _1(t)=-{\varvec{K}} {\varvec{x}}(t), \end{aligned}$$
(26)

where

$$\begin{aligned} {\varvec{K}}= & {} \left[ \begin{array}{cccccc} 24.8073,&-125.5004,&276.3903,&10.9221,&5.2260,&39.4850 \end{array} \right] , \end{aligned}$$

which was obtained by using the MATLAB function “lqr” for which the weight related to the torque was chosen to be 1, and the weight matrix related to state \({\varvec{x}}(t)\) was chosen to be a diagonal matrix of \(6\times 6\) with the diagonal elements from (1, 1) to (6, 6) being 1, 1, 1, 0.1, 0.1, and 0.1.

The condition for switching controller (15) to controller (26) was set as

$$\begin{aligned} d(t)= & {} |\theta _1(t)|+|\theta _2(t)|+|\theta _3(t)|\nonumber \\&+\, 0.1|\dot{\theta }_1(t)|+0.1|\dot{\theta }_2(t)|+0.1|\dot{\theta }_3(t)|<\epsilon _0\nonumber \\ \end{aligned}$$
(27)

for given \(\epsilon _0>0\). Indeed, small \(\epsilon _0\) is good for achieving a successful switch from controller (15) to controller (26). On the other hand, big \(\epsilon _0\) is good for achieving a quick switch from controller (15) to controller (26). In this paper, we chosen \(\epsilon _0=0.5\) in (27) by trial and error to achieve a successful and quick switch from controller (15) to controller (26).

Since links 2 and 3 may have rotated several times when the LQR controller is switched, \(\theta _i(t)\) \((i=2,3)\) may take value out of \((-\pi , \pi ]\). Therefore, \(\theta _2(t)\) and \(\theta _3(t)\) in (26) and (27) are used under modulo operation with divisor \(2\pi \) and take values in \(( -\pi , \pi ]\). Note that controller (15) needs more knowledge of the system’s parameters and more computation time than controller (26).

Below, we report our simulation results for two initial conditions.

5.1 Initial condition 1

We took an initial condition

$$\begin{aligned}&\left( \theta _1(0),\theta _2(0),\theta _3(0),\dot{\theta }_1(0),\dot{\theta }_2(0),\dot{\theta }_3(0)\right) \nonumber \\&\quad =\left( \frac{5\pi }{6},\frac{6\pi }{7},\frac{7\pi }{8}, 0,0,0\right) , \end{aligned}$$
(28)

which is close to the downward equilibrium point

$$\begin{aligned}&(\theta _1(t),\theta _2(t),\theta _3(t),\dot{\theta }_1(t),\dot{\theta }_2(t),\dot{\theta }_3(t))\\&\quad =( \pi ,\pi ,\pi ,0,0,0). \end{aligned}$$

To swing the APP robot up quickly close to the UEP, we took \(k_D=12.8495 {\,\mathrm J}^2 {\,\mathrm s}^2 \), \(k_P=101.6513 {\,\mathrm J}^2\), and \(k_V= 34.9863 {\,\mathrm J}^2 \mathrm{s}\). Under controller (15), we present the simulation results for \(t\in [0, 200]~\)s to show whether the switching condition in (27) is satisfied. The simulation results under the energy-based controller (15) are shown in Figs. 2, 3 and 4. From Fig. 2, there were many moments when (27) was satisfied.

Fig. 2
figure 2

Time responses of d(t) in (27) under controller (15) with initial condition (28)

Figure 3 shows that V(t) and \(E(t)-E_r\) converged to 0 and \(\tau _1(t)\) was not constant. Figure 4 shows that \(\theta _1(t)\) converged to 0, and \(\theta _2(t)\) and \(\theta _3(t)\) were time varying. Though \(\theta _2(t)\) and \(\theta _3(t)\) are treated in \({\mathbb {S}}^2\), plots of \(\theta _2(t)\) and \(\theta _3(t)\) in Fig. 4 were not plotted modulo \(2\pi \) to avoid confusing artificial points of apparent discontinuity. From Figs. 3 and 4, we validated that objectives (1) and (2) corresponding to the UEP were achieved.

In Fig. 3, the control torque \(\tau _1(t)\) satisfied \(-44.4371 \text {Nm} \le \tau _1(t) \le 30.5831~\text {Nm}\). To see whether these values are small or large, we compare those with the torque where link 1 is horizontal while the two other links are upward vertical. In such a position, we have \(\tau _1(t)=-\beta _1=-12.3835~\text {Nm}\).

Fig. 3
figure 3

Time responses of V(t), \(E(t)-E_r\), and \(\tau _1(t)\) under controller (15) with initial condition (28)

Fig. 4
figure 4

Time responses of \(\theta _1(t)\), \(\theta _2(t)\), and \(\theta _3(t)\) under controller (15) with initial condition (28)

When switching condition (27) was satisfied, we switched controller (15) to controller (26). From Fig. 5, the switch was taken at \(t=4.67\,\)s. Note that the final convergence of \(\theta _3(t)\) is \( -6.2832\text { rad}=-2\pi \text { rad}\) which is \(0\text { rad}\) under modulo operation with divisor \(2\pi \). From Fig. 6, we found that the swing-up control and stabilizing control of the APP robot in Table 1 were achieved under controllers (15) and (26).

Fig. 5
figure 5

Time responses of V(t), \(E(t)-E_r\), and \(\tau _1(t)\) under controllers (15) and (26) with initial condition (28), where the dashed vertical line indicates the switching time

Fig. 6
figure 6

Time responses of \(\theta _1(t)\), \(\theta _2(t)\), and \(\theta _3(t)\) under controllers (15) and (26) with initial condition (28), where the dashed vertical line indicates the switching time

The simulation result under control (26) for \(t\in [0, ~ 0.2]\) s is depicted in Fig. 7, which indicates that controller (26) did not stabilize the APP robot to the UEP from initial condition (28). The maximal value of \(\tau _1(t)\) in \(t\in [0, ~ 0.2]\) s was \(1.0283 \times 10^6\) Nm. This shows that to stabilize the APP robot to the UEP from initial condition (28), the proposed controllers (15) and (26) are better than controller (26) only.

Fig. 7
figure 7

Time responses of \(\theta _1(t)\), \(\theta _2(t)\), and \(\theta _3(t)\) under controller (26) with initial condition (28)

5.2 Initial condition 2

We took an initial condition

$$\begin{aligned}&\left( \theta _1(0),\theta _2(0),\theta _3(0),\dot{\theta }_1(0),\dot{\theta }_2(0),\dot{\theta }_3(0)\right) \nonumber \\&\quad =\left( \frac{\pi }{2},\frac{\pi }{2},\frac{\pi }{2}, 0,0,0\right) , \end{aligned}$$
(29)

where all links are at a stretched horizontal position.

The simulation results under the energy-based controller (15) are shown in Figs. 8, 9 and 10. From Fig. 8, we can see that there were several moments when (27) was satisfied. Figure 9 shows that V(t) and \(E(t)-E_r\) converged to 0 and \(\tau _1(t)\) was not constant. In Fig. 9, the control torque \(\tau _1(t)\) satisfied \(-32.7102~\text {Nm} \le \tau _1(t) \le 30.2021~\text {Nm}\). Figure 10 shows that \(\theta _1(t)\) converged to 0, and \(\theta _2(t)\) and \(\theta _3(t)\) were time varying. From Figs. 9 and 10, we validated that objectives (1) and (2) corresponding to the UEP were achieved.

Fig. 8
figure 8

Time responses of d(t) in (27) with initial condition (29) under controller (15)

Fig. 9
figure 9

Time responses of V(t), \(E(t)-E_r\), and \(\tau _1(t)\) under controller (15) with initial condition (29)

Fig. 10
figure 10

Time responses of \(\theta _1(t)\), \(\theta _2(t)\), and \(\theta _3(t)\) under controller (15) with initial condition (29)

When switching condition (27) was satisfied, we switched controller (15) to controller (26). From Fig. 11, the switch was taken at \(t=107.70\,\)s. From Fig. 12, we found that the swing-up control and stabilizing control of the APP robot in Table 1 were achieved under controllers (15) and (26). We also provide Figs. 13 and 14 only for a short period of the time after switching to the LQR law (26), which will enable zooming into the scale for more effectively displaying the final convergence. Note that the final convergence of \(\theta _3(t)\) is \(408.4070~\text {rad}=2\pi \times 65~\text {rad}\) which is \(0~\text {~rad}\) under modulo operation with divisor \(2\pi \).

Fig. 11
figure 11

Time responses of V(t), \(E(t)-E_r\), and \(\tau _1(t)\) under controllers (15) and (26) with initial condition (29), where the dashed vertical line indicates the switching time

Fig. 12
figure 12

Time responses of \(\theta _1(t)\), \(\theta _2(t)\), and \(\theta _3(t)\) under controllers (15) and (26) with initial condition (29), where the dashed vertical line indicates the switching time

Fig. 13
figure 13

Time responses of V(t), \(E(t)-E_r\), and \(\tau _1(t)\) under controllers (15) and (26) with initial condition (29) after the switching at \(t =107.701\) s

Fig. 14
figure 14

Time responses of \(\theta _1(t)\), \(\theta _2(t)\), and \(\theta _3(t)\) under controllers (15) and (26) with initial condition (29) after the switching at \(t = 107.701\) s

The simulation result under controller (26) for \(t\in [0, ~ 0.2]\) s is depicted in Fig. 15, which indicates that controller (26) did not stabilize the APP robot to the UEP from initial condition (29). The maximal value of \(\tau _1(t)\) in \(t\in [0, ~ 0.2]\) s was \(9.0179 \times 10^5\) Nm. It can be seen that the linear control law (26) achieves only local stabilization of the UEP from initial conditions in the close neighborhood of the UEP. Only the combination of both control laws (15) and (26) with the switching rule (27) practically achieves almost global stabilization.

Fig. 15
figure 15

Time responses of \(\theta _1(t)\), \(\theta _2(t)\), and \(\theta _3(t)\) under controller (26) with initial condition (29)

6 Conclusion

For a 3-link planar robot with only the first joint being active (the APP robot), we presented a nonlinear energy-based controller whose objective is to drive the APP robot into an invariant set where the first link is in the upright position and the total mechanical energy converges to its value at the UEP. By presenting and using a new property of the motion of the APP robot, without any condition on the mechanical parameters of the robot, we proved that if the control gains are larger than specific lower bounds, then only a measure-zero set of initial conditions converges to three strictly unstable equilibrium points instead of converging to the invariant set \(W_r\) in (24). The new property described in Lemma 3 is that if link 1 of the APP robot does not move under a constant torque on joint 1, then links 2 and 3 do not move. Three strictly unstable equilibrium points are the up–up–down, up–down–up, and up–down–down equilibrium points of the APP robot. The presented energy-based control law achieves objectives (1) and (2) corresponding to the UEP for almost all initial conditions but does not achieve objective (3), since the UEP becomes strictly unstable. We presented numerical results for the physical 3-link planar robot in [20] to validate the obtained theoretical results and to show a successful application to the swing-up and stabilizing control of the APP robot.

Even though the UEP is contained in the invariant set \(W_r\) in (24), we are unable to formally prove that the solution is ALWAYS guaranteed to come into a small neighborhood of the UEP at some time. Nevertheless, simulations under physically realistic parameter values show that this is indeed satisfied in practical scenarios.