1 Introduction

In the field of dynamics and control theory, inverted pendulum is one of the challenging problems because of its distinct characteristics of being nonlinear, unstable and underactuated. Therefore, the inverted pendulum system is used as a test bed to validate the performance of emerging control strategies [1]. Apart from that, the dynamics of inverted pendulum is analogous to many real-time applications including underactuated robotic systems [2], humanoid robots [3], Segway [4], buildings [5], and vertical take-off and land aircrafts [6], etc. Based upon the motion constraints of the base of the inverted pendulum systems, they can be categorized into two classes, i.e., the rotary inverted pendulum (RIP) system [7] and the linear inverted pendulum system [8]. In rotary inverted pendulum, the pendulum is hinged to a rotary arm which is actuated in order to control the motion of both rotary arm and pendulum, whereas in linear inverted pendulum, the pendulum is hinged to a cart which is actuated linearly in order to control the motion. This paper focuses on rotary inverted pendulum.

The literature on the control of inverted pendulum system can be broadly classified into three categories, i.e., swing-up control problem [9], stabilization control problem [10] and tracking control problem [11]. Stabilization and tracking control problems have diverse applications due to which they are exhaustively studied in the literature. Significant control algorithms including PID controller [2], pole placement controller [12], LQR controller [13, 14], sliding mode controller [15,16,17], linear quadratic Gaussian controller [17, 18], state-dependent Riccati equation-based controller [19], perceptual controller [20], model estimation-based controller [21, 22], fuzzy controller [7, 10, 23] and neural network-based controller [24, 25] have been proposed in the literature for the stabilization as well as tracking control problem of the inverted pendulum. The linear quadratic regulator (LQR) controller is one of the well-known optimal controllers; however, it is not robust to uncertainties in the system. The sliding mode controller is known for its robustness characteristics; however, it has a problem of non-robust reachability phase where the controller becomes sensitive to uncertainties.

Therefore, the objective of this work is to design a hybrid controller for rotary inverted pendulum which takes advantage of the optimality in LQR controller and robustness in sliding mode controller while eliminating the non-robust reachability phase in the sliding mode controller. This controller has a characteristic feature of avoiding non-robust reachability phase present in conventional sliding mode controllers while achieving robustness to matched uncertainties. The approach to design LQR-based sliding mode controller along with the stability analysis is presented, and the simulation as well as experimental investigation on the real-time stabilization control of rotary inverted pendulum is conducted. The robustness of the proposed controller to matched uncertainties is validated by adding a disturbance in the input of the controller. Furthermore, the problem of chattering in the controller is dealt by smoothening the control input with an insignificant loss in robustness.

The paper is structured as follows: Sect. 2 illustrates the dynamic modeling of rotary inverted pendulum, while Sect. 3 discusses the design of LQR-based sliding mode controller. In Sect. 4, implementation of LQR-based sliding mode controller on rotary inverted pendulum and its simulation and experimental results are presented, and finally the conclusions are drawn in Sect. 5.

2 Dynamic Modeling of Rotary Inverted Pendulum

Consider a RIP system consisting of the pendulum of length Lp connected/hinged to the end of a rotary arm of length Lr as shown in Fig. 1. The rotary arm is directly actuated by the direct-drive rotary servomotor of input voltage Vm, while the pendulum is underactuated and is indirectly controlled by the rotary arm. Let Jp and Jr correspond to the mass moment of inertia of pendulum and rotary arm about their center of mass, respectively. Here, \(\theta\) symbolizes the rotary arm angle and \(\alpha\) represents the pendulum angle such that pendulum angle zero corresponds to the vertically upright position of the pendulum. The experimentation is done on the QUBE-Servo platform, as shown in Fig. 2, and the parameters of system are described in Table 1.

Fig. 1
figure 1

Kinematics of rotary inverted pendulum

Fig. 2
figure 2

QUBE-Servo platform

Table 1 Rotary inverted pendulum parameters

Considering the viscous friction of the pendulum and rotary arm with the addition of motor dynamics, the dynamics of the RIP can be given by the following nonlinear equations [7, 26]:

$$\begin{aligned} & \left( {m_{\text{p}} L_{\text{r}}^{2} + \frac{1}{4}m_{\text{p}} L_{\text{p}}^{2} - \frac{1}{4}m_{\text{p}} L_{\text{p}}^{2} \cos^{2} \theta + J_{\text{r}} } \right)\ddot{\theta } - \frac{1}{2}m_{\text{p}} L_{\text{p}} L_{\text{r}} \cos \alpha \ddot{\alpha } \\ &\quad+ \left( {\frac{1}{2}m_{\text{p}} L_{\text{p}}^{2} \sin \alpha \cos \alpha \dot{\alpha } + B_{\text{r}} + \frac{{K_{\text{t}} K_{\text{m}} }}{{R_{\text{m}} }}} \right)\dot{\theta } \\ & \quad + \,\frac{1}{2}m_{\text{p}} L_{\text{p}} L_{\text{r}} \sin \alpha \dot{\alpha }^{2} = \frac{{K_{\text{t}} V_{\text{m}} }}{{R_{\text{m}} }} \\ \end{aligned}$$
(1)
$$\begin{aligned} & \left( {J_{\text{p}} + \frac{1}{4}m_{\text{p}} L_{\text{p}}^{2} } \right)\ddot{\alpha } - \frac{1}{2}m_{\text{p}} L_{\text{p}} L_{\text{r}} \cos \alpha \ddot{\theta } + B_{\text{p}} \dot{\alpha } \\ &\quad- \frac{1}{4}m_{\text{p}} L_{\text{p}}^{2} \cos \alpha \sin \alpha \dot{\theta }^{2} - \frac{1}{2}m_{\text{p}} L_{\text{p}} g\sin \alpha = 0. \end{aligned}$$
(2)

Thus, the dynamics of the rotary inverted pendulum is represented by (1) and (2). These nonlinear equations can be linearized around the stabilization point, i.e., \(\alpha = 0\), with an assumption that the controller bounds the pendulum angle near the stabilization point with small velocities. Considering the state vector \({\mathbf{x}} = \left[ {\theta \alpha \dot{\theta }\dot{\alpha }} \right]^{T}\), the system can be depicted in the state-space form by:

$$\begin{aligned} \left[ {\begin{array}{*{20}l} {\dot{\theta }} \hfill \\ {\dot{\alpha }} \hfill \\ {\ddot{\theta }} \hfill \\ {\ddot{\alpha }} \hfill \\ \end{array} } \right] & = \left[ {\begin{array}{*{20}c} 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \\ 0 & {\left( {\frac{{m_{\text{p}}^{2} L_{\text{p}}^{2} - L_{\text{r}} g}}{{4J_{\text{t}} }}} \right)} & {\frac{{ - B_{\text{r}} }}{{J_{\text{t}} }}\left( {J_{\text{p}} + \frac{{m_{\text{p}} L_{\text{p}}^{2} }}{4} - } \right) - \frac{{K_{\text{t}}^{2} }}{{R_{\text{m}} }}\left( {\frac{{K_{\text{t}} }}{{J_{\text{t}} R_{\text{m}} }}\left( {J_{\text{p}} + \frac{1}{4}m_{\text{p}} L_{\text{p}}^{2} - } \right)} \right)} & {\left( {\frac{{ - m_{\text{p}} L_{\text{r}} B_{\text{p}} L_{\text{p}} }}{{2J_{\text{t}} }}} \right)} \\ 0 & {\frac{{m_{p} gL_{p} }}{{2J_{t} }}(J_{r} + m_{p} L_{r}^{2})} & { - \frac{{m_{\text{p}} L_{\text{p}} L_{\text{r}} B_{\text{r}} }}{{2J_{\text{t}} }} - \frac{{K_{\text{t}}^{2} }}{{R_{\text{m}} }}\left( {\frac{{K_{\text{t}} }}{{2J_{\text{t}} R_{\text{m}} }}m_{\text{p}} L_{\text{p}} L_{\text{r}} } \right)} & {\frac{{ - B_{\text{p}} }}{{J_{\text{t}} }}(J_{\text{r}} + m_{\text{p}} L_{\text{r}}^{2})} \\ \end{array} } \right]\left[ {\begin{array}{*{20}l} \theta \hfill \\ \alpha \hfill \\ {\dot{\theta }} \hfill \\ {\dot{\alpha }} \hfill \\ \end{array} } \right] \\ & \quad + \left[ {\begin{array}{*{20}c} 0 \\ 0 \\ {\frac{{K_{\text{t}} }}{{J_{\text{t}} R_{\text{m}} }}\left( {J_{\text{p}} + \frac{1}{4}m_{\text{p}} L_{\text{p}}^{2} - } \right)} \\ {\frac{{K_{\text{t}} }}{{J_{\text{t}} R_{\text{m}} }}\left( {\frac{1}{2}m_{\text{p}} L_{\text{p}} L_{{{\text{r}} }} } \right)} \\ \end{array} } \right]\left[ {V_{\text{m}} } \right] \\ \end{aligned}$$
(3)

where \(J_{t} = J_{p} m_{p} L_{r}^{2} + J_{r} J_{p} + \frac{1}{4}J_{r} m_{p} L_{p}^{2}\). After incorporating the parameter values, the state-space equation can be rewritten as:

$$\left[ {\begin{array}{*{20}l} {\dot{\theta }} \hfill \\ {\dot{\alpha }} \hfill \\ {\ddot{\theta }} \hfill \\ {\ddot{\alpha }} \hfill \\ \end{array} } \right] = \left[ {\begin{array}{*{20}l} 0 \hfill & 0 \hfill & 1 \hfill & 0 \hfill \\ 0 \hfill & 0 \hfill & 0 \hfill & 1 \hfill \\ 0 \hfill & {149.2751} \hfill & { - 2.0886} \hfill & 0 \hfill \\ 0 \hfill & {261.6091} \hfill & { - 2.0886} \hfill & 0 \hfill \\ \end{array} } \right]\left[ {\begin{array}{*{20}l} \theta \hfill \\ \alpha \hfill \\ {\dot{\theta }} \hfill \\ {\dot{\alpha }} \hfill \\ \end{array} } \right] + \left[ {\begin{array}{*{20}l} 0 \hfill \\ 0 \hfill \\ {49.7275} \hfill \\ {49.1493} \hfill \\ \end{array} } \right]\left[ {V_{\text{m}} } \right] .$$
(4)

3 LQR-based Sliding Mode Control

The basic idea behind the proposed LQR-based sliding mode controller is to obtain an optimal control of the system while avoiding the non-robust reachability phase present in conventional sliding mode controllerFootnote 1. This is done by enforcing a sliding mode from the initial value of the system response; thus, the controller will be robust to matched uncertainties during the entire system response. While designing the proposed controller, it is considered that there exists a nominal LQR controller which has already been properly designed for nominal plant to ensure asymptotic stability as well as predefined performance of the system. To maintain the nominal performance along with insensitivity to external disturbances and matched uncertainties, a discontinuous sliding mode controller is combined to the nominal LQR controller.

To design the proposed LQR-based sliding mode controller, firstly a nominal LQR controller is designed assuming the nominal plant as given in (5). The state-space representation of the nominal plant system is given as follows:

$${\dot{\mathbf{x}}}\left( t \right) = {\mathbf{Ax}}\left( t \right) + {\mathbf{B}}u_{n} \left( t \right)$$
(5)

where \({\mathbf{x}}\left( t \right)\) represents a state vector, \(u_{n} \left( t \right)\) represents an input vector, and A and B are the state matrices. The LQR controller works with an objective of minimizing the cost function, given in (6). The cost function for LQR controller is given by:

$$J_{o} \left( t \right) = \frac{1}{2}\mathop \int \limits_{0}^{\infty } \left( {{\mathbf{e}}^{T} \left( t \right)\varvec{ }{\mathbf{Q}} {\mathbf{e}}\left( t \right) + u^{T} \left( t \right) R u\left( t \right)} \right){\text{d}}t$$
(6)

where \({\mathbf{e}}\left( t \right) = {\mathbf{x}}_{{\varvec{des}}} \left( t \right) - {\mathbf{x}}\left( t \right)\) denotes the error between the desired state vector \({\mathbf{x}}_{{\varvec{des}}} \left( t \right)\) and measured state vector \({\mathbf{x}}\left( t \right)\). The state weighing matrix Q and control cost matrix R are defined by user and play a significant role in the performance of the controller. The output of the controller can be expressed as:

$$u_{n} \left( t \right) = {\mathbf{Ke}}\left( t \right) = {\mathbf{K}}\left( {{\mathbf{x}}_{{\varvec{des}}} \left( t \right) - {\mathbf{x}}\left( t \right)} \right)$$
(7)

where K denotes the state feedback matrix which can be represented as:

$${\mathbf{K}} = {\mathbf{R}}^{ - 1} {\mathbf{B}}^{{\mathbf{T}}} {\mathbf{P}}$$
(8)

where P is obtained by solving algebraic Riccati equation given as:

$${\mathbf{PA}} + {\mathbf{A}}^{{\mathbf{T}}} {\mathbf{P}} - {\mathbf{PBR}}^{ - 1} {\mathbf{B}}^{{\mathbf{T}}} {\mathbf{P}} + {\mathbf{Q}} = 0.$$
(9)

Thus, the state feedback matrix K is dependent on A, B, Q and R matrix, where, the matrices A and B are dependent on the system under consideration, while the matrices Q and R are selected by user based on desired performance. The MATLAB command lqr can also be used to evaluate the state feedback matrix K as:

$${\mathbf{K}} = lqr\left( {{\mathbf{A}},{\mathbf{B}},{\mathbf{Q}},{\mathbf{R}}} \right).$$
(10)

Furthermore, after designing an LQR controller, a discontinuous sliding mode controller is integrated with LQR controller to compensate the effect of parametric uncertainties and input disturbance. The plant dynamics with parametric uncertainties and input disturbance is represented as follows:

$${\dot{\mathbf{x}}}\left( t \right) = {\mathbf{A}} {\mathbf{x}}\left( t \right) + {\mathbf{B}} {\mathbf{u}}\left( t \right) + {\mathbf{d}}\left( {{\mathbf{x}},t} \right).$$
(11)

The additional \({\mathbf{d}}\left( {{\mathbf{x}},t} \right)\) term in (11) accounts for unmolded plant dynamics and input disturbance which satisfies the matching condition given by:

$${\mathbf{d}}\left( {{\mathbf{x}},t} \right) = {\mathbf{B}}\varvec{ }d_{m}$$
(12)

where \(d_{m}\) denotes a bounded disturbance in input with some known maximum value. The control input for the system in (11) is given as

$$u = u_{n} + u_{d}$$
(13)

where \(u_{n}\) represents the nominal control input given by LQR controller and \(u_{d}\) represents the discontinuous control input given by sliding mode controller. On substituting the value of \(u\) in (13) into (11), the plant dynamics can be represented as:

$${\dot{\mathbf{x}}}\left( t \right) = {\mathbf{A}}\varvec{ }{\mathbf{x}}\left( t \right) + {\mathbf{B}}\varvec{ }u_{n} \left( t \right) + {\mathbf{B}}\varvec{ }u_{d} \left( t \right) + {\mathbf{B}}\varvec{ }d_{m}.$$
(14)

The sliding surface for sliding mode controller is taken as

$$s\left( t \right) = {\mathbf{Gx}}\left( t \right) + z\left( t \right)$$
(15)

where G is a user-defined matrix. During sliding, \(s\left( t \right) = \dot{s}\left( t \right) = 0\) and therefore

$$\dot{s}\left( t \right) = {\mathbf{G\dot{x}}}\left( t \right) + \dot{z}\left( t \right) = 0.$$
(16)

Substituting the value of \({\dot{\mathbf{x}}}\left( t \right)\) from (14) in (16), we obtain:

$$\dot{s}\left( t \right) = {\mathbf{G}}\left( {{\mathbf{A}}\varvec{ }{\mathbf{x}}\left( t \right) + {\mathbf{B}}\varvec{ }u_{n} \left( t \right) + {\mathbf{B}}\varvec{ }u_{d} \left( t \right) + {\mathbf{B}}\varvec{ }d_{m} } \right) + \dot{z}\left( t \right) = 0.$$
(17)

During sliding, it is expected that \(u_{{d{\text{eq}}}} \left( t \right) = - \varvec{ }d_{m}\), i.e., it should compensate for the uncertainty; then, selecting

$$\dot{z}\left( t \right) = - {\mathbf{G}}\left( {{\mathbf{A}}\varvec{ }{\mathbf{x}}\left( t \right) + {\mathbf{B}} u_{n} \left( t \right)} \right), z\left( 0 \right) = - {\mathbf{Gx}}\left( 0 \right)$$
(18)

ensures

$$\dot{s}\left( t \right) = {\mathbf{GB}}u_{d} \left( t \right) + {\mathbf{G}} {\mathbf{B}}\varvec{ }d_{m}$$
(19)

and so, during sliding \(u_{{d{\text{eq}}}} \left( t \right) = - \varvec{ }d_{m}\). Substituting the value of \(u_{{d{\text{eq}}}} \left( t \right)\) in (14), the system is governed by the same state-space representation of (5). Thus, it can be said that the effect of matched uncertainty has been completely rejected and the system is governed by (5) for which nominal control input \(u_{n} \left( t \right)\varvec{ }\) is given by LQR controller. Furthermore, using (15) and (18), the hybrid sliding surface which eliminates the reachability phase is given as

$$s\left( t \right) = {\mathbf{G}}\{ {\mathbf{x}}\left( t \right) - {\mathbf{x}}\left( 0 \right) - \mathop \int \limits_{0}^{t} ({\mathbf{A}}\varvec{ }{\mathbf{x}}\left( t \right) + {\mathbf{B}} u_{n} \left( t \right)){\text{d}}t\}.$$
(20)

Note that the term \(- {\mathbf{x}}\left( 0 \right)\) in (20) ensures that \(s\left( 0 \right) = 0,\) so the reachability phase is eliminated. Thus, the sliding mode will exist from the very beginning (\(t = 0\)) and the system robustness against matched uncertainties is ensured throughout the entire closed-loop system response. The matrix G is chosen as \({\mathbf{G}} = {\mathbf{B}}^{ + }\) so as to ameliorate the effect of unmatched disturbance. Here, \({\mathbf{B}}^{ + }\) denotes left inverse of B and is given by

$${\mathbf{B}}^{ + } = \left( {{\mathbf{B}}^{{\mathbf{T}}} {\mathbf{B}}} \right)^{ - 1} {\mathbf{B}}.$$
(21)

3.1 Stability Analysis

The discontinuous control input for sliding mode control is computed using Lyapunov stability theorem. The Lyapunov function considered is given as

$$V\left( t \right) = 0.5 s^{T} \left( t \right) s\left( t \right).$$
(22)

\(\dot{V}\left( t \right)\) can be given as:

$$\dot{V}\left( t \right) = s^{T} \left( t \right) \dot{s}\left( t \right).$$
(23)

Furthermore, substituting \(\dot{s}\left( t \right)\) from (19), \(\dot{V}\left( t \right)\) can be formulated as:

$$\dot{V}\left( t \right) = s^{T} \left( t \right)\varvec{ }{\mathbf{GB}}u_{d} \left( t \right) + s^{T} \left( t \right){\mathbf{G}} {\mathbf{B}}\varvec{ }d_{m}.$$
(24)

Now, the discontinuous control input which satisfies Lyapunov stability condition \(\dot{V} < 0\) is chosen as

$$u_{d} = - M {\text{sgn}}\left( {s\left( t \right)} \right).$$
(25)

Substituting the value of \(u_{d}\) from (25) in (24) yields:

$$\dot{V}\left( t \right) = - \varvec{GB}Ms\left( t \right) + s^{T} \left( t \right)\varvec{G} \varvec{B }d_{m}.$$
(26)

Since \(\varvec{G} = \varvec{B}^{ + }\) implies \(\varvec{GB} = 1\), (26) can be further written as

$$\dot{V}\left( t \right) = - Ms\left( t \right) + s^{T} \left( t \right)\varvec{ }d_{m}$$
(27)
$$\dot{V}\left( t \right) \le s\left( t \right)( - M + d_{m} ).$$
(28)

So, for the system to be stable (\(\dot{V} < 0\)), the value of the modulation gain M should be chosen as

$$M \ge d_{m}.$$
(29)

Hence, the above condition will enforce the sliding mode and therefore ensure the stability of the system.

4 Results and Discussion

In this section, the proposed controller is implemented on rotary inverted pendulum system and the simulation as well as experimental results are presented. The objective of the controller is to track the desired trajectory for the rotary arm while stabilizing the pendulum at the vertically upright position, i.e., the unstable point. The robustness of the proposed controller against matched uncertainties is investigated by adding the disturbance at the input of the rotary inverted pendulum system. A square wave of magnitude 1 V and frequency f = 1 Hz (as shown in Fig. 3) is added as an input disturbance to the input of rotary inverted pendulum. The results of the proposed controller are compared with the results of the conventional LQR controller, to observe the improvement in the robustness.

Fig. 3
figure 3

Disturbance given to RIP input voltage

The tuning parameters for LQR controller are chosen as Q = diag[5, 1, 1, 20] and R = 1 based on trial-and-error method. Using the chosen tuning parameters, the LQR gain K is calculated as

$${\mathbf{K}} = [\begin{array}{*{20}c} {\begin{array}{*{20}c} { - 2.2361} & {53.8740} \\ \end{array} } & {\begin{array}{*{20}c} { - 1.7400} & {6.5269} \\ \end{array} ]} \\ \end{array}.$$
(30)

Thus, the nominal LQR control input \(u_{n}\) can be obtained from (7). To compensate the effect of input disturbance of magnitude \(d_{m} = 1\), M is chosen in accordance with (29) as 1.1. The design matrix G using (21) is computed as \({\mathbf{G}} = [\begin{array}{*{20}c} {\begin{array}{*{20}c} { - 2.2361} & {53.8740} \\ \end{array} } & {\begin{array}{*{20}c} { - 1.7400} & {6.5269} \\ \end{array} ]} \\ \end{array}\). Thus, the discontinuous control input \(u_{d}\) is given as:

$$u_{d} = - 1.1 {\text{sgn}}\left( {s\left( t \right)} \right).$$
(31)

Incorporating (30) and (31) in (13) yields

$$u\left( t \right) = - Ke\left( t \right) - 1.1 {\text{sgn}}\left( {s\left( t \right)} \right).$$
(32)

The MATLAB Simulink environment is used in order to obtain simulation as well as experimental results. The block diagram for the experimentation is shown in Fig. 4. The comparison of simulation and experimentation response for LQR and LQR-SMC controller on rotary inverted pendulum is shown in Figs. 5 and 6, respectively.

Fig. 4
figure 4

Simulink block diagram of the proposed LQR-SMC on rotary inverted pendulum

Fig. 5
figure 5

Comparison of simulated response with experimental response of LQR controller on RIP with input disturbance (red line: simulated response; black line: experimental response)

Fig. 6
figure 6

Comparison of simulated response with experimental response of the proposed LQR-SMC controller on RIP with input disturbance (red line: simulated response; black line: experimental response)

From Figs. 5 and 6, a close agreement between the simulation and experimental results is observed. The range of magnitude of the results appears to be the same; however, a shift in phase is observed between the experimental results and simulation results in Fig. 5. This could be because of unmodeled dynamics or time delay in the simulation results. A similar pattern in phase shift is observed in Fig. 6. However, the magnitude of error is observed to be larger in simulation results compared to experimental results. This could be because of the finite sampling rate of the sensors.

The comparison of experimental response of LQR and proposed LQR-SMC controller is shown in Fig. 7. From the results, a large oscillation of magnitude 8 degree and 2 degree around the desired rotary arm position and pendulum angle, respectively, is observed using conventional LQR controller. However, using the proposed LQR-SMC controller a small oscillation of magnitude 3 degree and 1 degree is observed around the desired rotary arm position and pendulum angle, respectively. Thus, a reduction in error is detected using the proposed LQR-SMC controller, thus validating the improved robustness to input disturbance.

Fig. 7
figure 7

Comparison of experimental response of the proposed LQR-SMC controller and LQR controller for RIP with input disturbance (red line: LQR-SMC; green line: LQR; blue line: θ reference)

Also, it can be noted that the discontinuous control input \(u_{d}\) contains a signum function, which leads to abrupt switching in control input and thus might be harmful for practical situations. Thus, to prevent it, the discontinuous control input is smoothened by replacing signum function with a smooth function given as

$$u_{d} = - 1.1 \frac{s\left( t \right)}{s\left( t \right) + \delta }.$$
(33)

Here, \(\delta\) controls the smoothness of the function, i.e., increasing the value of δ causes an increase in the smoothness of the function. However, choosing a large value of δ causes a degradation in the robustness and performance of the controller. Figure 8 shows the response of the system using the smooth function [given in (33)] for \(\delta = 0.001\). The results show that with the use of smooth function for \(\delta = 0.001\), the control input is reduced and smoothened with a minor loss in performance of the controller.

Fig. 8
figure 8

Comparison of experimental response of smooth LQR-SMC controller and LQR-SMC controller for RIP with input disturbance (red line: LQR-SMC; black line: smooth LQR-SMC; blue line: θ reference)

5 Conclusions

In this work, an LQR-based sliding mode controller for stabilization problem of the rotary inverted pendulum is proposed. The primary objective of this work is to achieve better robust performance than conventional controllers, which is done using the proposed LQR-based sliding mode controller. The proposed controller is robust to matched uncertainties along with having an advantage of avoiding non-robust reachability phase over conventional sliding mode controller. The simulation and experimental results are obtained for the proposed controller, which are furthermore compared to the results of conventional LQR controller to validate the robustness of the proposed controller. The comparative results have shown that the proposed controller has outperformed the conventional LQR controller in achieving better robust performance to matched uncertainties. Furthermore, a smooth LQR-based sliding mode controller is proposed to deal with the problem of chattering in control input of which the comparative results have shown a reduced and smoothened control input with minor loss in robust performance.