Open access peer-reviewed chapter

A Hybrid Control Approach Based on the Combination of PID Control with LQR Optimal Control

Written By

Ibrahim K. Mohammed

Submitted: 08 July 2020 Reviewed: 04 November 2020 Published: 03 December 2020

DOI: 10.5772/intechopen.94907

Chapter metrics overview

478 Chapter Downloads

View Full Metrics

Abstract

Proportional Integral Derivative (PID) is the most popular controller that is commonly used in wide industrial applications due to its simplicity to realize and performance characteristics. This technique can be successfully applied to control the behavior of single-input single-output (SISO) systems. Extending the using of PID controller for complex dynamical systems has attracted the attention of control engineers. In the last decade, hybrid control strategies are developed by researchers using conventional PID controllers with other controller techniques such as Linear Quadratic Regulator (LQR) controllers. The strategy of the hybrid controller is based on the idea that the parameters of the PID controller are calculated using gain elements of LQR optimal controller. This chapter focuses on design and simulation a hybrid LQR-PID controller used to stabilize elevation, pitch and travel axes of helicopter system. An improvement in the performance of the hybrid LQR-PID controller is achieved by using Genetic Algorithm (GA) which, is adopted to obtain best values of gain parameters for LQR-PID controller.

Keywords

  • proportional integral derivative (PID)
  • fractional order proportional integral derivative (FOPID)
  • linear quadratic regulator (LQR)
  • hybrid control system
  • genetic algorithm (GA)

1. Introduction

PID is regarded as the standard control structure of classical control theory. PID controllers are used successfully for single-input single-output (SISO) and linear systems due to their good performance and can be easily implemented. The control of complex dynamic systems using classic PID controllers is considered as a big challenge, where the stabilization of these systems requires applying a more robust controller technique. Many studies have proposed to develop a new hybrid PID controller with ability to provide better and more robust system performance in terms of transient and steady-state responses over the standard PID controllers. Lotfollahzade et al. [1] proposed a new LQR-PID controller to obtain an optimal load sharing of an electrical grid. The presented hybrid controller is optimized by Particle Swarm Optimization (PSO) to compute the gain parameters of the PID controller. A new hybrid control algorithm was presented by Lindiya et al. for power converters [2]. They adopted a conventional multi-variable PID and LQR algorithm for reducing cross-regulation in DC-to-DC converters. Sen et al. introduced a hybrid LQR-PID controller to regulate and monitor the locomotion of a quadruped robot. The gain parameters of the hybrid controller is tuned using the Grey-Wolf Optimizer (GWO) [3]. In [4] a new PID and LQR control system was proposed to improve a nonlinear quarter car suspension system.

The intent of this study is to design a new hybrid PID controller based on an optimal LQR state feedback controller for stabilization of 3DOF helicopter system. To this end an improvement in the system performance has been achieved in both the transient and steady-state responses. In the proposed system the classical PID and optimal LQR controller have been combined to formulate a hybrid controller system. Simulations were implemented utilizing Matlab programming environment to verify the efficiency and effectiveness of the proposed hybrid control method.

Advertisement

2. Controller theory

In this section, basics and theory of integer and fractional order PID controllers are presented. Theory of an intelligent LQR controller, which is used with PID controller to combine a hybrid control system, is also introduced.

2.1 Calssical PID controller

A PID is the most popular controller technique that is widely used in industrial applications due to the simplicity of its structure and can be realized easily for various control problems as the gain parameters of the controller are relatively independent [5, 6]. Basically, the controller provides control command signals ut based on the error et between the demand input and the actual output of the system. The continuous time structure of the classical PID controller is as follows:

ut=Kpet+Ki0teτ+KddetdtE1

where Kp,Ki and Kd are the proportional, integral and differential components of the controller gain. These controller gain parameters should be tuned properly to enable the output states of the system to efficiently follow the desired input.

2.2 FOPID controller

FOPID is a special category of PID controller with fractional order derivatives and integrals. Its concept was introduced by Podlubany in 1997. During the last decade, this controller approach has attracted the attention of control engineers in both academic and industrial fields. Compared with the classical PID controller, it offers flexibility in dynamic systems design and more robustness.

2.2.1 Fractional order calculus

Fractional order calculus is an environment of calculus that generates the derivatives or integrals of problem functions to non-integer (fractional) order. This fractional order mathematical operation allows to establish a more accurate and concise model than the classical integer-order method. Moreover, the fractional order calculus can also produce an effective tool for describing dynamic behavior for control systems [7].

aDtα=dαdtαα>01α=1αtdtαα<0E2

Fractional order calculus is a generalization of differentiation and integration to non-integer order fundamental operator which is denoted by aDtα where a and t are the operation limits and ααR is the order of the operation. The formula of continuous differ-integral operator (aDtα) is defined as in Eq. (2) [8]. There are two commonly used definitions for general fractional differ-integral aDtα, which are used for realization of control problem algorithm:

Grunwald – Letnikov (GL) definition:

aDtαft=dαftdtα=limh0hαj=0x1jαjftjhE3

where x is integer part of x, x=tah, h is time step and αj is binomial coefficients, its expression is given by:

αj=αα1..αj+1j!E4

Riemann-Liouville definition:

aDtαft=1Γnαdndtnatfτtταn+1E5

where nR+. The condition for above equation is n1<α<n,Γ. is called Gamma function, which its defination is given by:

ΓX=0zX1ezdzE6

Laplace transform of differ-integral operator aDtα is given by expected form:

LaDtαft=0estaDtαftdtE7
LaDtαft=sαFsm=0n1s1j0Dtαm1ftE8

Where Fs=Lft is the normal Laplace transformation and n is an integer number that satisfies n1<αn and s=jw denotes the Laplace transform variable.

2.2.2 Fractional order controller

Fractional order PID controller denoted by PIλDμ was proposed by Igor Podlubny [9] in 1997. It is an extension of traditional PID controller where λ and μ have non-integer fractional values. Figure 1 shows the block diagram of the fractional order PID controller. The integer-differential equation defining the control action of a fractional order PID controller is given by:

ut=Kpet+KiDλet+KdDμetE9

Figure 1.

The block diagram of a FOPID structure.

Based on the above equation, it can be expected that the FOPID controller can enhance the performance of the control system due to more tuning knobs introduced. Taking the Laplace transform of Eq. (9), the system transfer function of the FOPID controller is given by:

GFOPIDs=Kp+Kisλ+KdsμE10

Where λ and μ are arbitrary real numbers. Taking λ=1 andμ=1 a classical PID controller is obtained. Thus, FOPID controller generalizes the classical PID controller and expands it from point to plane as shown in Figure 2(b). This expansion provides the designer much more flexibility in designing PID controller and gives an opportunity to better adjust the dynamics of the control system. This increases robustness to the system and makes it more stable [10]. A number of optimization techniques can be implemented for getting the best values of the gain parameters of the controller.

Figure 2.

PID controllers with fraction orders. (a) Classical. (b) Fractional order.

2.3 LQR controller

Linear quadratic regulator is a common optimal control technique, which has been widely utilized in various manipulating systems due to its high precision in movement applications [11]. This technique seeks basically a tradoff betwwen a stable performance and acceptable control input [12]. Using the LQR controller in the design control system requires all the plant states to be measurable as it bases on the full state feedback concept. Therefore, using the LQR controller to stabilize the 3DOF helicopter system based on the assumption that the system states are considered measurable. LQR approach includes applying the optimal control effort:

ut=KxtE11

Where K is the state feedback gain matrix, that will enable the output states of the system to follow the trajectories of reference input, while minimizing the following the cost function:

J=0xTtQxtuTtRutdtE12

Where Q and R are referred to as weighting state and control matrices. The controller feedback gain matrix can be determined by using below equation:

K=R1BTPE13

Where P is (nxn) matrix deterrmined from the solution of the following Riccati matrix equation:

ATP+PAPBR1BTP+Q=0E14

For nth order system with mth input, the gain matrix and control input are given by:

K=k11k12k13k1nk21k22k23k2n.....km1km2km3kmnandut=u1u2u3.um

Based on the above expression, the control effort ut of the system stated in Eq. (11) can be written as in Eq. (15). For the purpose of simplicity of control problem the weighting matrices Q and R are chosen as the diagonal matrices:

Q=blkdig(q11,q22,q33,,qnn),R=blkdigr11r22r33rmm

so that the cost function Eq. (12) can be reformulated as in Eq. (16).

ut=k11k12k13k1nk21k22k23k2n.....km1km2km3kmnx1x2x3.xnE15
J=0q11x12+q11x22+..+qnnxn2+r11u12+r22u22+..+rmmum2dtE16

Where q11,q22,q33,..,qnn and r11,r22,r33,..,rmm denote the weighting elements of Q and R matrices respectively. The optimal control approach LQR is highly recommended for stabilizing complex dynamic systems as it basically looks for a compromise between the best control performance and minimum control input effort. Based on the LQR controller an optimum tracking performance can be investigated by a proper setting of the feedback gain matrix. To achieve this, the LQR controller is optimised by using GA tuning method which is adopted to obtain optimum elements values for of Q andR weighting matrices.

Advertisement

3. Tuning method

In this study, GA tuning approach has been invoked to tune the gain matrix of LQR controller used to approximate the gain parameters of PID controller for 3DOF helicopter system. GA is a global search optimization technique bases on the strategy of natural selection. This optimization method is utilized to obtain an optimum global solution for more control and manipulating problems. The procedure of GA approach includes three basic steps: selection, crossover and mutation, that constitute the main core of GA with powerful searching ability.

Selection: This step includes choosing individual genomes with high adaptive value from the current population to create mating pool. At present, there mainly are: sequencing choice, adaptive value proportional choice, tournament choice and so on. In order to avoid the best individuals of current population missing in the next generation due to destruction influence of crossover and mutation or selection error, De Jong put forward to the cream choice strategy [3xxx];

Crossover: This operation is the process of mimicking gene recombination of natural sexual reproduction, through combining the genetic information of two gens to create a new offspring contining more complicated gene structur. Reproduction may proceed in three stages as follows: (1) two newly reproduced strings are randomly selected from a Mating Pool; (2) a number of crossover positions along each string are uniformly selected at random and (3) two new strings are created and copied to the next generation by swapping string characters between the crossover positions defined before.

Mutation: In this process one or more indivisual values in a chromosome are altered from its initial state. This can result in entirely new gene values being added to the gene pool. This stage is also important by the view of preventing the genes local optimal points.

Applying these main operations creates new individuals which could be better than their parents. Based on the requirements of desired response, the sequence of GA optimization technique is repeated for many iterations and finally stops at generating optimum solution elements for the application problems. The sequence of the GA tuning method is presented in Figure 3 [13, 14]. The steps of the GA loop are defined as follows:

  1. Initial set of population.

  2. Choose individuals for mating.

  3. Mating the population to create progeny.

  4. Mutate progeny.

  5. Inserting new generated individuals into populations.

  6. Are the system fitness function satisfied?

  7. End search process for solution.

Figure 3.

Process loop of GA optimization method.

In this study, the aim of using GA optimization method is to tune the elements of the state weighting matrix Q and input weighting matrix R of the optimal LQR controller based on a selected fitness function which, should be minimised to a smallest value. The fitness function should be formulated based on the required performance characteristics. These optimized LQR elements are then employed to calculate the optimum values for PID controller gain parameters, which are used to stabilize the control system. The implementation procedure of the GA tuning method begins with the definition step of the chromosome representation. Each chromosome is represented by a strip of cells. Each cell corresponds to an element of the controller gain parameters. These cells are formed by real positive numbers and characterize the individual to be evaluated [13].

Advertisement

4. Hybrid PID control approaches

PID controller is a simple manipulating technique that can be successfully implemented for one dimension control systems. For multi dimensions systems it can use a multi channel PID controller system to control the dynamic behavior of these systems. Currently, there is a considerable interest by many researchers in development new control approaches using PID controller. Xiong and Fan [15] proposed a new adaptive PID controller based on model reference adaptive control (MRAC) concept for control of the DC electromotor drive. They presented an autotuning algorithm that combines PID control scheme and MRAC based on MIT rule to tune the controller parameters. Modified PI and PID controllers are introduced to regulate output voltage of DC-DC converters using MRAC manipulating technique [16, 17]. The parameters of the controllers are adapted effectively using MIT rule. Based on the adapted controllers parameters an improvement in the regulation behavior of the converters has been investigated.

Further improvement in the performance of the standard PID controller is also achieved by involving an integrator of order λ and differentiator of order μ to the controller structure based on Fractional Calculus and it is known as fractional order (FO) PID controller [7]. This extension could provide more flexibility in PID controller design and makes the system more robust, thus, enhancing its dynamic performance compared to its integer counterpart. In FOPID controller the manipulating parameters become five that provides more flexibility in the controller design and robust in the performance.

In the last decades, a new hybrid controller scheme using PID technology is proposed in [18, 19, 20] for different applications. The structure of the presented hybrid controller system is constructed by combination between conventional PID controller and state feedback LQR optimal controller. The gain parameters of the PID controller used to achieve desired output response are determined based on optimal LQR theory.

In this chapter, a hybrid PID controller based on LQR optimal technique is designed to stabilize 3DOF helicopter system. The proposed hybrid LQR-PID controller is optimized using GA optimization method, which is used to tune its gain parameters.

Advertisement

5. Case study: helicopter control system

5.1 Helicopter structure and modeling

The conceptual platform of 3DOF helicopter scheme is presented in Figure 4. It consists of an arm mounted on a base. The main body of the helicopter constructed of propellers driven by two motors mounted are the either ends of a short balance bar. The whole helicopter body is fixed on one end of the arm and a balance block installed at the other end.

Figure 4.

Prototype model of 3DOF helicopter system.

The balance arm can rotate about the travel axis as well as slope on an elevation axis. The body of the helicopter is free to roll about the pitch axis. The system is provided by encoders mounted on these axes used to measure the travel motion of the arm and its elevation and pitch angle. The propellers with motors can generate an elevation mechanical force proportional to the voltage power supplied to the motors. This force can cause the helicopter body to lift off the ground. It is worth considering that the purpose of using a balance block is to reduce the voltage power supplied to the propellers motors. In this study, the nonlinear dynamics of 3DOF helicopter system is modelled mathematically based on developing the model of the system behavior for each of the axes.

5.1.1 Elevation axis model

The free body diagram of 3DOF helicopter system based on elevation axis is shown in Figure 5. The movement of the elevation axis is governed by the following differential equations:

Figure 5.

Schematic diagram of elevation axis model for 3DOF helicopter system.

Jϵϵ¨=JpJττ̇2cosϵsinϵ+l1Fmcosρl1FmMGMf,ϵE17

Where Fm is the thrust force of propeller motor and Mf,ϵ represents the torque component generated from combining the joint friction and air resistance. But the rotation angle of the pitch axis ρ=0, if the elevation angle ϵ=0, then the torque exerted on the elevation axis will be zero. Eq. (17) based on Euler’s second law becomes:

Jϵϵ¨=l1FmMw,ϵ+Mf,ϵE18
Jϵϵ¨=l1Ff+FbMw,ϵ+Mf,ϵE19
Fi=KcVii=f,bE20
Jϵϵ¨=Kcl1Vf+VbMw,ϵ+Mf,ϵE21
Jϵϵ¨=Kcl1VsMw,ϵ+Mf,ϵE22

5.1.2 Pitch axis model

Consider the pitch schematic diagram of the system in Figure 6. It can be seen from the figure that the main torque acting on the system pitch axis is produced from the thrust force generated by the propeller motors. When ρ0, the gravitational force will also generate a torque Mw,ρ acts on the helicopter pitch axis. The dynamics of the pitch axis can be modeled mathematically as follows:

Figure 6.

Schematic diagram of the pitch axis model for 3DOF helicopter scheme.

Jρρ¨=FflρFblρMw,ρMf,ρE23

Where Mf,ρ is the friction moment exerted on the pitch axis.

Mw,ρ=mhglhsinρcosϵE24

Based on the assumption that the pitch angle ρ=0, Mw,ρ=0, then Eq. (23) becomes as follows:

Jρρ¨=lρFfFbMf,ρE25
Jρρ¨=KclρVfVbMf,ρE26
Jρρ¨=KclρVdMf,ρE27

5.1.3 Travel axis model

The free body diagram of the helicopter system dynamics based on the travel axis is presented in Figure 7. In this model, when ρ0, the main forces acting on the helicopter dynamics are the thrust forces of propeller motors (Ff,Fb). These forces have a component that generates a torque on the travel axis. Assume that the helicopter body has roll up by an angle ρ as shown in Figure 7. Then the dynamics of travel axis for 3DOF helicopter system is modeled as follows:

Figure 7.

Schematic diagram of the travel rate axis model for 3DOF helicopter scheme.

Jrṙ=Ff+Fbsinρl1Mf,rE28

The thrust forces of the two propeller motors Ff+Fb are required to keep the helicopter in flight case and is approximately W.

Jrṙ=Wsinρl1Mf,rE29

Where Mf,r is the friction moment exerted on the travel axis. As ρ approaches to zero, based on sinc function, sinρ=ρ, the above equation becomes as follows:

Jrṙ=l1Mf,rE30

Based on the assumption that the coupling dynamics, gravitational torque (Mw,ϵ) and friction moment exerted on elevation, pitch and travel axis are neglected, then the dynamics modeling equations Eqs. (22), (27) and (30) for 3DOF helicopter system can be simplified as in Eqs. (31), (32) and (33) respectively [21].

ϵ¨=Kcl1JϵVsE31
ρ¨=KclρJρVdE32
ṙ=Wl1JrρE33

5.2 Helicopter state space model

In order to design a state feedback controller based on LQR technique for 3DOF helicopter system, the dynamics model of the system should be formulated in state space form. In this study, the proposed hybrid control algorithm is investigated for the purpose of control of pitch angle, elevation angle and travel rate of 3DOF helicopter scheme by regulating the voltage supplies to the front and back motors. Let xnx1=x1,x2x3,x4x5,x6x7T=ϵρϵ̇ρ,̇rʓγT be the state vector of the system, the state variables are chosen as the angles and rate and their corresponding angular velocities, and ʓ̇=ϵ,γ̇=r . The voltages supplied to the front and back propellers motors are considered the input’s vector such that, utmx1=u1,u2T=VfVbT and the elevation angle, pitch angle and travel rate are assumed the output’s vector such that, ytpx1=ϵρrT.

Based on Eqs. (31)-(33), choosing these state variables yields the following system state space model:

x1̇=ρ=x2x2̇=ϵ̇=x3x3̇=ϵ¨=Kcl1JϵVf+Vbx4̇=ρ¨=KclρJρVfVbx5̇=ṙ=Wl1Jrx2x6̇=ʓ̇=x1x7̇=γ̇=x4E34

The general state and output matrix equations describing the dynamic behavior of the linear-time-invariant helicopter system in state space form are as follows:

x(̇t)=Axt+ButE35
yt=Cxt+DutE36

Where Anxn is the system matrix, Bnxm is the input matrix, Cpxm is the output matrix, and Dmxp is feed forward matrix, for the designed system. Based on Eqs. (34)(36) are rewritten as follows [21].

ϵ̇ρ̇ϵ¨ρ¨ṙʓ̇γ̇=00100000001000000000000000000Gl1Jt0000010000000000100ϵρϵ̇ρ̇rʓγ+0000Kcl1JeKcl1JeKclρJpKcρJρ000000VfVbE37

In this study, for the purpose of control system design, the model of the system is formulated in state space form using the physical parameters values listed in Table 1 [21]. Based on Eq. (37) and using the parameters values in Table 1, the state equation of the system is given by Eq. (39):

SymbolPhysical unitNumerical values
Jϵkg m21.8145
Jrkg m21.8145
Jρkg m20.0319
WN4.2591
lmm0.88
lbm0.35
lρm0.17
KcN/V12

Table 1.

Values of physical parameters of 3DOF helicopter system.

ϵρr=100000001000000000100ϵρϵ̇ρ̇rʓγ+000000VfVbE38
ϵ̇ρ̇ϵ¨ρ¨ṙʓ̇γ̇=001000000010000000000000000002.0650000010000000000100ϵρϵ̇ρ̇rʓγ+00005.81975.819763.94963.949000000VfVbE39

5.3 Helicopter control system design

Based on step input, a hybrid controller is designed for the following desired performance parameters: rise time (tr) less than 10 ms, settling time (ts) less than 30 ms, maximum overshoot percentage, (MO) less than 5%.

Under the assumption that the desired system states are zero the block diagram of the proposed helicopter control system based on the LQR controller is shown in Figure 8. The control system is analysed mathematically and then simulated using Matlab software tool to validate the proposed hybrid controller. Based on the desired performance parameters, which include rise and settling time, overshoot and error steady state, the fitness function of the control problem is formulated as follows:

Figure 8.

LQR controller based on GA for 3DOF helicopter system.

F=0.3S.tr+0.3S.ts+0.2S.O+0.2S.essE40

where, S is closed loop transfer function of the helicopter system, S.tr,ts,O,ess are the rise time, settling time, maximum overshoot and error steady state of the closed-loop control system. It is worth considering that the control input effort is considered in the evaluation process of the proposed stabilizing helicopter system. In this study, the design of the controller is effectively optimized by using GA tuning method which is adopted to obtain optimum elements values for LQR weighting matrices Q and R. These optimized matrices are used to calculate the optimum controller gain matrix by using Eqs. (13) and (14). However, in this study, the LQR gain matrix is determined by using the Matlab command ‘lqr’.

5.3.1 PID approximation

In this subsection, the gain parameters Kp,Ki,Kd of the PID controller are calculated approximately from the feedback gain K of LQR controller based on

GA tuning method. For this application, analyzing Eq. (15) yields the following control effort [22]:

u1u2=k11k12k13k14k15k16k17k11k12k13k14k15k16k17xTE41

where xT=ϵρϵ,̇ρ̇rʓγT.

If ϵd,ρd and rd are the desired pitch angle, elevation angle and travel rate of the helicopter system, it can express the form of PID controllers used to meet the desired output states as follows: [7, 8].

In this study, for elevation angle, the control equation is based on the following PID control equation:

Vs=Kϵpeϵ+Kϵdeϵ̇+KϵieϵdtE42
Vs=KϵpϵdϵKϵdϵ̇+KϵiϵdϵdtE43

While the pitch angle is controlled by the following PD control equation:

Vd=Kρpeρ+Kρdeρ̇E44
Vd=KρpρdρKρdρ̇E45

The travel rate is gonverned by the following PI control equation:

ρd=Krper+KrierdtE46
ρd=Krprdr+KrirdrdtE47

Where eϵ=ϵdϵ,eρ=ρdρ,er=rdr,eϵ̇=ϵ̇ andeρ̇=ρ̇.

5.3.2 Elevation control using PID controller

Summing the rows of (41) results the following [21]:

u1+u2=2k11ϵ+2k13ϵ̇+2k16ξ=2k11ϵ+2k13ϵ̇+2k16ϵdtE48

The above equation can be written as

Vs=2k11ϵdϵ2k13ϵ̇+2k16ϵdϵdtE49

It is obvious that Eqs. (43) and (49) have the same structure, this means that the gain parameters of the pitch PID controller can be obtained from the gain elements of the LQR controller. Thus, comparing Eq. (43) with Eq. (49), yields the following gain relationships:

Kϵp=2k11Kϵd=2k13Kϵi=2k16E50

The block diagram of closed-loop control system for 3DOF helicopter system based on hybrid LQR-PID controller is shown in Figure 9. Taking Laplace transform for elevation axis model Eq. (31) yields the following equation:

Figure 9.

Control system block diagram for helicopter elevation, pitch and travel axis using PID controller.

Jeϵs.s2=Kcl1VssE51

The transfer function of the elevation axis plant is given by:

ϵsVss=Kcl1Jes2E52

The transfer function of the PID controller is as follows:

VssEϵs=Kϵds2+Kϵps+KϵisE53

where Eϵs=ϵdsϵs, the open loop transfer function of the elevation axis control Gϵs is given by:

Gϵs=ϵsEϵs=VssEϵsϵsVssE54

Based on Eqs. (52) and (53), the open loop elevation transfer function becomes:

Gϵs=Kcl1Jes2Kϵds2+Kϵps+KϵisE55

The closed loop transfer function for elevation angle control is as follows:

ϵsϵcs=Gϵs1+Gϵs=Kcl1Kϵds2+Kcl1Kϵps+Kcl1KϵiJes3+Kϵds2+Kϵps+KϵiE56

5.3.3 Pitch control using PD controller

Similarly, the difference of the rows of Eq. (41) results in

u1u2=2k12ρ2k14ρ̇2k15rrd2k17γE57
Vd=2k12ρ2k14ρ̇2k15rrd2k17rrddtE58

Substitution Eq. (47) in Eq. (45) results,

Vd=KρpρKρdρ̇+KρpKrprdr+KρpKrirdrdtE59

It is clear that Eqs. (58) and (59) have exactly the same structure. Then, by comparing these equations, it can obtain the feedback gains for the PID controller from the LQR gains parameters as follows:

Kρp=2k12Kρd=2k14Krp=k15k12Kri=k17k12E60

Taking Laplace transform for pitch axis model Eq. (32) yields:

Jρρss2=KclρVdsE61

The transfer function for pitch axis model is given by:

ρsVds=KclρJρs2E62

The transfer function of the PD controller is as follows:

VdsEρs=Kρds+KρpE63

where Eρs=ρdsρs, based on Eqs. (62) and (63) the open loop transfer function of the pitch axis control is given by:

Gps=ρsEρs=ρsVdsVdsEρs=KclρKρds+KρpJes2E64

The closed loop transfer function of pitch angle is given by:

ρsρcs=KclρKρds+KclρKρpJρs2+KclρKρds+lρKρpE65

5.3.4 Travel control using PI controller

Taking Laplace transform for travel axis model Eq. (33) results:

rss=Wl1JrρdsE66

The transfer function for travel axis model is given by:

rsρds=Wl1JrsE67

The transfer function of the PI controller is as follows:

ρρsErs=Krp+KrisE68

where Es=ρdsρs, the open loop transfer function of the travel axis control is given by:

Grs=rsρdsρρsErs=Wl1Krps+KriJrs2E69

The closed loop transfer function for travel angle is as follows:

rsrds=Gl1Krps+Gl1KriJts2+Gl1Krps+Gl1KriE70

5.4 Controller simulation and results

5.4.1 GA-LQR controller

In order to validate the proposed helicopter stabilizing system, the LQR controller is analysed mathematically using Matlab tool. Based on objective function (J) and using the Matlab command “lqr” the elements of the LQR weighting matrices Q, R are tuned using GA optimization method. For this application, each chromosome in GA tuning approach is represented by nine cells which correspond to the weight matrices elements of the LQR controller as shown in Figure 10. By this representation it can adjust the LQR elements in order to achieve the required performance. The parameters of the GA optimization approach chosen for the tuning process of the helicopter control system are listed in Table 2. Converging elements of the LQR weight matrices Q and R through iteration based on GA optimization method are presented in Figure 11.

Figure 10.

Definition of GA chromosome.

GA propertyValue/Method
Population Size20
Max No. of Gen.100
Selection MethodNormalized Geo. Selection
Crossover MethodScattering
Mutation MethodUniform Mutation

Table 2.

Parameters of GA tuning method.

Figure 11.

Number of generation of GA-LQR parameters Q and R.

Based on the proposed fitness function stated in Eq. (40), the LQR weighting matrices Q and R obtained based on the GA tuning approach are given by:

Q=blkdig26.2580.8690.431,0.475,1.870.026,0.705,R=blkdig0.4690.469,

The feedback gain matrix of the LQR controller can be mathematically calculated using Eq. (13), where P matrix is the stabilizing solution of the Riccati equation stated in Eq. (14).

In this application, by using the state matrix A, input matrix B and the tuned weighting matrices (Q,R), the optimized feedback gain matrix K stated below is determined using the Matlab software instruction:

K=lqrABQR
K=5.32322.68171.17190.73992.05900.16510.86615.32322.68171.17190.73992.05900.16510.8661

Based on the feedback gain matrix and using Eq. (11), the LQR control effort vector for the 3DOF helicopter system is dertermined as follows:

u1u2=5.3232.6821.1720.7392.0590.1650.8665.3232.6821.1720.7392.0590.1650.866xTE71

5.4.2 GA-PID controller

Based on Eqs. (50), (60) and (71), the absolute values of PID, PD and PI gain parameters for elevation, pitch and travel axis model respectively for helicopter

system are listed in Table 3 [21]. Using the values in Tables 1 and 3, the closed-loop transfer function of elevation, pitch and travel axis Eqs. (56), (65) and (70) become as in Eqs. (72), (73) and (74) respectively:

ϵsϵcs=1445s3+247s+674.91.8145s3+1445s2+2474s+674.9E72
pspcs=69.08s+269.30.0319s2+69.08s+269.3E73
rsrcs=2.878s+1.6341.815s2+2.878s+1.634E74

Based on bounded input signal, the elevation, pitch and travel axis model of 3DOF helicopter system are unstable as they give unbounded outputs. The output responses for elevation, pitch and travel angle are illustrated in the Figure 12. It can be say that the open loop helicopter system without control action is unable to provide a stable output response.

Figure 12.

Open loop response of Helicopter system.

In this study, in order to achieve a stable output, a hybrid control system using LQR based PID controller for 3DOF helicopter system is proposed to control the dynamic behaviour of the system. To validate the proposed helicopter stabilization system, the controller is simulated using Matlab programming tool. Three axis, elevation, pitch, travel rate, are considered in the simulation process of the control system. The performance of the helicopter balancing system is evaluated under unit step reference input using rise, settling time overshoot and steady state error parameters for the elevation, pitch and travel angles to simulate the desired command given by the pilot.

5.4.2.1 Elevation LQR-PID controller

This section deals with the simulation of LQR based PID controller used to control the position of helicopter elevation model. The parameters of the hybrid controller are tuned using GA optimization method. Figure 13 presents a tracking control curve of the demand input based on the PID controller using optimized gain parameters listed in Table 3 for helicopter elevation angle.

Figure 13.

Closed-loop response of the elevation model system.

The simulation results show that the controller successed to guide the system output through the desired input trajectory effectively with negligible overshoot, short rise and settling time of 0.1 ms and 0.3 ms respectively.

5.4.2.2 Pitch LQR-PD controller

In this section, an optimized LQR-PD controller based on GA tuning approach is designed to control the dynamic model of helicopter pitch angle. Based on the optimized PD parameters stated in Table 3, the output response of the proposed helicopter tracking system is illustrated in Figure 14. It is obvious from the minifigure of the system response that the LQR-PD controller succeeded to force the pitch angle state of the helicopter system to follow the desired trajectory effectively without overshoot, shorter rise and settling time and zero steady state tracking error.

Figure 14.

Closed-loop response of the pitch model system.

5.4.2.3 Travel LQR-PI controller

The control of the travel rate for the 3DOF helicopter system is governed by a GA-LQR based PI controller. The time response of the optimized PI tracking system using optimum gain parameters which are listed in Table 3. is shown in Figure 15. It can be noted from the miniplot of the system response that the optimised hybrid LQR-PI controller enabled the system output state to track the desired input trajectory without overshoot, and shorter rise and settling time with minimal steady state tracking error.

Figure 15.

Closed-loop response of the travel model system.

The control inputs supplied to the propellers motors of the proposed 3DOF helicopter system are shown in Figure 16. Consequently, it can say that the control performance of optimised GA-LQR based PID, PD and PI controllers for helicopter elevation, pitch and travel axis model respectively was acceptable through tracking the system output states for the reference input efficiently. Based on the minifigures of Figures 13 and 14 and Figure 15, the performance parameters of PID, PD and PI controller for helicopter elevation, pitch and travel axis are listed in Table 4. From the response data of the controlled helicopter system in Table 4 it can be said that the hybrid controllers were able to provide robust and good tracking performance in both the transient and steady state responses.

Figure 16.

Conrol input of 3DOF helicopter control system.

PID parametersRelationshipAbsolute Value
Kϵp2k1110.6463
Kϵd2k132.3438
Kϵi2k160.3302
Kρp2k125.3634
Kρdk141.4799
Krpk15k120.7678
Krik17k120.3230

Table 3.

Values of gain parameters for PID, PD and PI controllers.

Controllertr(s)ts(s)Mo %
Elevation PID0.3430.5351.1
Pitch PD0.5821.050
Travel PI1.1712.45.29

Table 4.

Values of performance elements s of controllers.

Advertisement

6. Conclusions

In this study, a new hybrid control methodology has been developed for complex dynamical systems through combinig the LQR optimal technique with traditional PID controller. An efficient hybrid control system has been designed to stabilize 3DOF helicopter systems. The dynamics of elevation, pitch and travel axis for a helicopter system is modeled mathematically and then formulated in state space form to enable utilizing state feedback controller technique. In the proposed helicopter stabilizing scheme, a combination of a conventional PID control with LQR state feedback controller is adopted to stabilize the elevation, pitch and travel axis of the helicopter scheme. The gain parameters of the traditional PID controller are determined from the gain matrix of state feedback LQR controller. In this research, the LQR controller is optimized by using GA tuning technique. The GA optimization method has been adopted to find optimum values for LQR gain matrix elements which are utilized to find best PID gain parameters. The output response of the optimized helicopter control system has been evaluated based on rise time, setting time, overshoot and steady state error parameters. The simulation results have shown the effectiveness of the proposed GA-LQR based PID controller to stabilize the helicopter system at desired values of the elevation and pitch angle and travel parameters.

References

  1. 1. Lotfollahzade M, Akbarimajd A, Javidan J. Design LQR and PID Controller for Optimal Load Sharing of an Electrical Microgrid. Int. Res. J. Appl. Basic Sci. 2013;4:704-712 https://europub.co.uk/articles/5372
  2. 2. Lindiya S, Subashini N, Vijayarekha K. Cross Regulation Reduced Optimal Multivariable Controller Design for Single Inductor DC-DC Converters. Energies. 2019;12:477. DOI: 10.3390/en1203047
  3. 3. Sen M A, Kalyoncu M. Grey Wolf Optimizer Based Tuning of a Hybrid LQR-PID Controller for Foot Trajectory Control of a Quadruped Robot. Gazi Univ. J. Sci. 2019, 32, 674–684. https://www.researchgate.net/publication/335015963_Grey_Wolf_Optimizer_Based_Tuning_of_a_Hybrid_LQR-PID_Controller_for_Foot_Trajectory_Control_of_a_Quadruped_Robot
  4. 4. Nagarkar M, Bhalerao Y, Patil GV, Patil RZ. Multi-Objective Optimization of Nonlinear Quarter Car Suspension System PID and LQR Control. Procedia Manuf. 2018;20:420-427. DOI: 10.1016/j.promfg.2018.02.06
  5. 5. Mohammed I, Sharif B, Neasham J. Design and implementation of a magnetic levitation control system for robotically actuated capsule endoscopes. In: Proceedings International Symposium on Robotic and Sensors Environments (ROSE2012); 16-18 November 2012; Magdeburg. Germany: IEEE; 2012. pp. 140-14
  6. 6. Mohammed I, Sharif B, Neasham J. Design and implementation of positioning and control systems for capsule endoscopes. IET Journal of Science, Measurement and Technology. 2020;14(7): 745-754. https://digital-ibrary.theiet.org/content/journals/10.1049/iet-smt.2019.0223
  7. 7. Mohammed I, Abdulla A. Fractional Order PID Controller Design for Speed Control DC Motor based on Artificial Bee Colony Optimization. International Journal of Computer Applications. 2018;179(24); 43-49. https://www.researchgate.net/publication/323873116_Fractional_Order_PID_Controller_Design_for_Speed_Control_DC_Motor_based_on_Artificial_Bee_Colony_Optimization
  8. 8. Abdelhakim I, Madjid K, Yassine B, Sid Ahmed T. Speed Control of DC Motor Using PID and FOPID Controllers Based on Differential Evolution and PSO. International Journal of Intelligent engineering and Systems. 2018;11(4):241-249. DOI: 10.22266/ijies2018.0831.2
  9. 9. Ahmad A. at. el. Control of magnetic levitation system using fuzzy logic control. In: Proceedings of the 2nd IEEE International Conference on Computational Intelligence; 28-30 September. Vol. 2010. Tuban. Indonesia: IEEE; 2010. pp. 51-5
  10. 10. Jain R, Aware MV, Junghare. Tuning of Fractional Order PID Controller Using Particle Swarm Optimization Technique for DC Motor Speed Control. In: Proceedings International Conference on Power Electronics, Intelligent Control and Energy Systems; 4-6 July 2016; Delhi. India: IEEE; 2016; p. 1-
  11. 11. Mohammed I. Design and Simulation of Three Degrees-of-Freedom Tracking Systems for Capsule Endoscope. Journal of Dynamic Systems, Measurements, and Control. 2016;138: 111002-1-11102-11. DOI: 10.1115/1.403383
  12. 12. Mohammed I, Abdulla A. Design of optimised linear quadratic regulator for capsule endoscopes based on artificial bee colony tuning algorithm. International Journal for Engineering Modeling. 2018;31(12):77-98 https://doi.org/10.31534/engmod.2018.1-2.ri.02_ vjan
  13. 13. Abdulla A, Mohammed I, Jasim A. Roll Control System Design Using Auto Tuning LQR Technique. International Journal of Engineering and Innovative Technology. 2017;6(2):11-22 https://www.ijeit.com/Vol%207/Issue%201/IJEIT1412201707_02.pdf
  14. 14. Mohammed I, Abdulla A, Ahmed J. Speed Control of DC Motor Using MRAC and Genetic Algorithm based PID Controller. International Journal of Industrial Electronics and Electrical Engineering. 2020;8(1):1-6 http://www.ijieee.org.in/paper_detail.php?paper_id=16837&name=Speed_Control_of_DC_Motor_using_MRAC_and_Genetic_Algorithm_based_PID_Controller
  15. 15. Xiong A, Fan Y. Application of a PID Controller using MRAC Techniques for Control of the DC Electromotor Drive. In: Proceedings IEEE International Conference on Mechatronics and Automation; 5-8 Aug 2007; Harbin China: IEEE. 2007. pp. 2616-262
  16. 16. Ardhenta L, Subroto RK. Application of direct MRAC in PI controller for DC-DC boost converter. International Journal of Power Electronics and Drive System (IJPEDS). 2020;11(2):551-858 http://ijpeds.iaescore.com/index.php/IJPEDS/article/view/20543
  17. 17. Ardhenta L, Kuswiradyo P, Subroto RK. Model Direct Adaptive Control of Buck Converter Using MRAC. International Journal of Innovative Technology and Exploring Engineering (IJITEE). 2019;8(12):1108-1112 https://www.ijitee.org/wpcontent/uploads/papers/v8i12/L38821081219.pdf
  18. 18. Kumar EV. Jerome J. LQR based optimal tuning of PID controller for trajectory tracking of Magnetic Levitation System. In: Proceedings: International Conference On DESIGN AND MANUFACTURING. Procedia Engineering; 64(2013). 2013. pp. 254-26
  19. 19. Saleem O, Rizwan M. Performance optimization of LQR-based PID controller for DC-DC buck converter via iterative-learning-tuning of state-weighting matrix. International Journal of Numerical Modeling Electronic Networks, Drives and Fields. 2019;32(3); 1-17. https://onlinelibrary.wiley.com/doi/epdf/10.1002/jnm.2572
  20. 20. Jian-Bo H, Qing-Guo W, Tong-Heng L. PI/PID controller tuning via LQR approach. In: Proceedings the 37th IEEE Conference on Decision and Control; 18-18 Dec 1998. Tampa USA: IEEE; 1998. pp. 1177-118
  21. 21. Choudhary S K. LQR Based PID Controller Design for 3-DOF Helicopter System. International Journal of Electrical and Information Engineering. 2014;8)8(: 1498-1503
  22. 22. Fan L, Joo E. Design for Auto-tuning PID Controller Based on Genetic Algorithms. In: Proceedings IEEE 4th International Conference on Industrial Electronics and Applications (ICIEA); 25-27 May 2009; Xi’an China: IEEE. 2009. pp. 1924-192

Written By

Ibrahim K. Mohammed

Submitted: 08 July 2020 Reviewed: 04 November 2020 Published: 03 December 2020