Contribution to the Control and Command of a Quadrirotor with Six Degrees of Freedom in an Urban Environment

Abstract

The objective of this article is to make a contribution relating to the modeling, control, simulation and stabilization of a complex system, with six degrees of freedom of a particular drone which presents many advantages and challenges. On the technological, military, political and other levels with an enormous and beneficial social contribution, it is a quadrotor which is a nonlinear, strongly coupled and unstable system. Such a structure is difficult to master, because the control is multivariable in the sense that six degrees of freedom are to be controlled simultaneously and operating in an environment subject to disturbances. Two commands, in particular Backstepping and PID, will be applied to obtain the stabilization of the quadcopter at the desired values, in attitude and in altitude. This article presents the comparative results of the performance of the quadcopter under the two controls. The effect of the parameters of each command on the response time of the system is elucidated under the Matlab/Simulink environment. For a simulation time of up to 10 seconds minimum with a less good response time of almost 2 seconds for the PID control, these results prove the robustness of the Backstepping command.

Share and Cite:

Calvin, N. , Aurelien, Y. , Jeannot, M. , Vivien, A. and Cyrille, N. (2020) Contribution to the Control and Command of a Quadrirotor with Six Degrees of Freedom in an Urban Environment. World Journal of Engineering and Technology, 8, 800-813. doi: 10.4236/wjet.2020.84059.

1. Introduction

Unmanned Aerial Vehicle (UAV) is commonly known as drones, constituting the flagship of the aerospace industry. Its applications are as visible, useful and remarkable in military projects, as regards surveillance, intelligence or combat missions, remote sensing, destruction of targets and any other task that would put a crew in danger. Drones have also proven to have a very high potential for civilian applications, such as surveillance and observation of risk areas, infrastructure management, customs, the environment, field mapping, scientific experiments, intervention in hostile sites etc. [1].

A quadrotor is a miniature rotary-wing drone with four rotors. It has been the subject of several research projects focusing on its ease of implementation, vertical take-off and landing, and its efficiency in hovering. One of its major characteristics is stabilization in attitude and altitude. This stabilization allows the quadcopter to be steered to the desired position (x, y, z) or the desired angle (ϕ, θ, ψ) [2]. The literature is full of several mathematical models describing the translational and rotational dynamics of a quadrotor, with six degrees of freedom, as well as the control algorithms. Among defined, the linear controls PID [1] [2] [3], LQR, H∞ [4] applied to a linearized model (around an operating point using the Jacobian method). The nonlinear controls take into account the important nonlinearities of the vehicle dynamics. We can cite the hierarchical control [5], the sliding mode control [6], the Backstepping algorithm [7] - [12]. Other commands exploit visual data extracted from acquired images; we will speak of visual serving or command by vision [13]. Some have also been interested in author’s flight commands based on neural networks and fuzzy logic [13]. In this article, we will focus on two approaches to controlling a quadcopter. This is the Backstepping controller first, and the PID controller second. Each of the commands will be simulated in the Matlab/Simulink environment. The results will be compared by analyzing their performances in terms of system response time, stabilization, convergence towards the desired setpoints and their behavior in the face of disturbances. The article is divided into three parts: the first describes the dynamic model of the quadrotor according to the Newton-Euler formalism. The proposed control strategies will find their applications in the second part. In the third part, the discussion of the results and the analysis of the performance of each control algorithm will be given.

2. Dynamic Model

­ The flight dynamics of a quadrotor are complex and strongly coupled. To develop a dynamic model close to the real physical model, taking into account the effects of the environment, we make these assumptions:

­ The structure of the quadrotor is assumed to be rigid and symmetrical, which implies that the inertia matrix will be assumed to be diagonal.

­ The propellers are supposed to be rigid in order to be able to neglect the effect of their deformation during rotation.

­ The center of mass and the origin of the coordinate system linked to the structure of the quadrotor coincide.

­ The lift and drag forces are proportional to the squares of the rotational speed of the rotors, which is a very close approximation of aerodynamic behavior.

1) Definition of benchmarks (Figure 1)

­ The movement of a quadrotor is described by two reference marks:

­ The Earth Inertial frame noted E:

E = ( O , x e ; y e ; z e )

­ The mobile mark (in English Body frame) noted B:

B = ( G , x b ; y b ; z b )

2) Euler angles

Euler angles are angles introduced by Leonhard Euler to describe the orientation of a solid. We have three: the roll angle ( π 2 < ϕ < π 2 ), pitch angle ( π 2 < θ < π 2 ) and the yaw angle ( π < ψ < π ). A rotation is obtained by varying one of Euler’s three angles and a sequence of three rotations is sufficient to describe any transformation based on Euler’s theorem (Figure 2).

3) Kinematic parameters

They include four vectors of three elements describing the state of the system. The first two define the position and speed of the center of gravity of the quadrotor and the other two relate to its orientation and angular speed.

r ( t ) = [ x y z ] T is the position of the center of gravity of the quadrirotor with respect to the reference {E} and defined in the reference {E}.

Figure 1. Repères.

Figure 2. Angles d’Euler.

η ( t ) = [ ϕ θ ψ ] T is the vector of Euler angles representing the angular position of the frame {B} linked to the quadrirotor with respect to the frame {E} and defined in the frame {E}.

υ ( t ) = [ x ˙ y ˙ z ˙ ] E T = [ u v w ] B T is the speed of the center of gravity compared to the reference vector E and described in the reference {B}. Also called linear speed. Ω ( t ) = [ p q r ] E T = [ ϕ ˙ θ ˙ ψ ˙ ] B T is the instantaneous speed vector of rotation between the reference marks {E} and {B} and described in the reference {B}. Also called angular speed of rotation.

4) Kinetic parameters

They establish the link between the forces and the variation of the kinematic parameters. They are constant in our study. We can cite: the mass m of the quadrotor, the center of gravity G, the matrix of inertia J of the point G of the moving frame

J = [ J x x 0 0 0 J y y 0 0 0 J z z ] (1)

5) Rotation matrix

The rotation matrix is an orthogonal matrix and in fact it belongs to the subspace of orthogonal matrices, called special orthogonal group, denoted by SO (3), defined by:

{ 3 × 3 / T = I 3 × 3 et det ( ) = 1 }

In the case where the mobile frame {B} linked to the quadrirotor rotates in inertial relation {E} with an angular speed Ω, the rotation matrix varies; this results in the kinematic height matrix: R ̇ = R s k ( Ω )

sk(Ω) is the antisymmetric tensor associated with the angular speed Ω Î R3. The rotation matrix defines three angles of Euler rotation around the axes respectively described as:

x ( ϕ ) ; y ( θ ) ; z ( ψ ) . The product of these three elementary matrices of rotation forms the matrix of rotation R.

x ( ϕ ) = [ 1 0 0 0 cos ϕ sin ϕ 0 sin ϕ cos ϕ ]

y ( θ ) = [ cos θ 0 sin θ 0 1 0 sin θ 0 cos θ ]

z ( ψ ) = [ cos ψ sin ψ 0 sin ψ cos ψ 0 0 0 1 ]

= x ( ϕ ) × y ( θ ) × z ( ψ ) (2)

= [ c 1 θ c ψ c ψ s 2 ϕ s θ c ϕ s ψ c ϕ s θ c ψ + s ϕ s ψ c θ s ψ s ϕ s θ s ψ + c ϕ c ψ c ϕ s θ s ψ s ϕ c ψ s θ s ϕ c θ c ϕ c θ ]

6) Aerodynamic forces

A moving quadrirotor is under the action of four (4) main forces: the weight P, the total thrust U1, the drag in the propellers Tr (propeller) and the drag along the axes Tr(ax).

Note: P = m g z e = [ 0 0 m g ]

U 1 = i = 1 4 b ω i 2

T r ( helice ) = d ω i 2

T r ( axe ) = K f t V = [ K f t x K f t y K f t z ] [ x ˙ y ˙ z ˙ ] = [ K f t x x ˙ K f t y y ˙ K f t z z ˙ ]

Avec:

m is the mass of the quadrirotor in kg; g is the gravitational acceleration in m/s2; z e = [ 0 0 1 ] T is a unit vector in the terrestrial inertial frame {E}.

b is the coefficient of lift; ωi the speed of rotation of a motor number i (i ranging from 1 to 4).

d is the coefficient of proportionality of drag.

K f t x Translation drag coefficient along the x axis.

K f t y Translation drag coefficient along the y axis.

K f t z Translation drag coefficient along the z axis.

7) Moments due to thrust forces of rotors along the axes

­ We have two moments due to the pushing force:

­ Moment due to thrust forces on the axis x:

U 2 = l b ( ω 4 2 ω 2 2 ) (3)

U 2 is called roll control.

Moment due to thrust forces on the axis:

U 3 = l b ( ω 3 2 ω 1 2 ) (4)

U 3 is called pitch control.

8) Moments due to drag forces

­ They left as follows:

­ The moment due to the drag forces in the propellers along the axis z:

U 4 = d ( ω 1 2 ω 2 2 + ω 3 2 ω 4 2 ) (5)

U 4 is called lace command.

By grouping together with the expression of the total thrust U 1 and Equations (3), (4) and (5),

{ U 1 = b ( ω 1 2 + ω 2 2 + ω 3 2 + ω 4 2 ) U 2 = l b ( ω 4 2 ω 2 2 ) U 3 = l b ( ω 3 2 ω 1 2 ) U 4 = d ( ω 1 2 ω 2 2 + ω 3 2 ω 4 2 ) (6)

­ The moment resulting from aerodynamic friction:

M a = K f a Ω 2 = [ K f a x ϕ ˙ 2 K f a y θ ˙ 2 K f a z ψ ˙ 2 ] (7)

K f a x coefficient of aerodynamic friction along the axis x.

K f a y coefficient of aerodynamic friction along the axis y.

K f a z coefficient of aerodynamic friction along the axis z.

9) Gyroscopic effects

The gyroscopic effect is defined as the difficulty of modifying the position or the orientation of the plane of rotation of a rotating mass. Each rotor can thus rotate around its own vertical axis with a speed of rotation ωi. Even the vertical axis moves as the vehicle rotates. This action produces two additional moments among which, on one: the gyroscopic moment of the helices Mgh and the gyroscopic moment due to the movements of the quadrirotor Mgm. Note:

M g h = i = 1 4 Ω r J r [ 0 0 ( 1 ) i + 1 ω i ] T

M g h = [ ϕ ˙ θ ˙ ψ ˙ ] J r [ 0 0 Ω r ] = [ J r Ω r θ ˙ J r Ω r ϕ ˙ 0 ] (8)

or : vector product operator; J r is the inertia of the rotors and Ω r = ω 2 + ω 4 ω 1 ω 3

M g m = Ω J Ω

M g m = [ ( J z z J y y ) θ ˙ ψ ˙ ( J x x J z z ) ϕ ˙ ψ ˙ ( J y y J x x ) ϕ ˙ θ ˙ ] (9)

10) Translational dynamics

The equations governing the translational motion of a quadrotor are:

{ r ˙ = υ m r ¨ = × [ 0 0 1 ] × U 1 T r ( axe ) P (10)

11) Rotational dynamics

The equations governing the rotational motion of a quadrotor are:

{ ˙ = s k ( Ω ) J Ω ˙ = M g m M a M g h + M f (11)

12) Complete dynamic model (12)

From Equations (10) and (11) we obtain the complete dynamic model:

{ x ¨ = K f t x m x ˙ + 1 m U x U 1 y ¨ = K f t y m y ˙ + 1 m U y U 1 z ¨ = K f t z m z ˙ + cos ϕ cos θ m U 1 g ϕ ¨ = J y y J z z J x x θ ˙ ψ ˙ J r J x x Ω r θ ˙ K f a x J x x ϕ ˙ 2 + 1 J x x U 2 θ ¨ = J z z J x x J y y ϕ ˙ ψ ˙ + J r J y y Ω r ϕ ˙ K f a x J y y θ ˙ 2 + 1 J y y U 3 ψ ¨ = J x x J y y J z z ϕ ˙ θ ˙ K f a x J z z ψ ˙ 2 + 1 J z z U 4

and:

{ U x = cos ϕ sin θ cos ψ + sin ϕ sin ψ U y = cos ϕ sin θ sin ψ sin ϕ cos ψ (13)

13) System state representation

For a physical system there are a multitude of state representations, in our case we choose the state vector as follows:

X = [ r T υ T η T Ω T ] (14)

Each of the 4 vectors of relation (14) has 3 components. In total, our state vector contains (4 × 3) = 12 elements and the control vector U has 4 elements such that:

{ X = [ ϕ ϕ ˙ θ θ ˙ ψ ψ ˙ x x ˙ y y ˙ z z ˙ ] T U = [ U 1 U 2 U 3 U 4 ] T

We get the state representation in the form:

X ˙ = f ( X , U )

{ x 1 = ϕ x 2 = x ˙ 1 = ϕ ˙ x 3 = θ x 4 = x ˙ 3 = θ ˙ x 5 = ψ x 6 = x ˙ 5 = ψ ˙ x 7 = x x 8 = x ˙ 7 = x ˙ x 9 = y x 10 = x ˙ 9 = y ˙ x 11 = z x 12 = x ˙ 11 = z ˙ (15)

We ask:

{ a 1 = J y y J z z J x x , a 2 = K f a x J x x , a 3 = J r J x x b 1 = 1 J x x , a 4 = J z z J x x J y y , a 5 = K f a x J y y a 6 = J r J y y , b 2 = 1 J y y , a 7 = J x x J y y J z z a 8 = K f a x J z z , b 3 = 1 J z z , a 9 = K f t x m a 10 = K f t y m , a 11 = K f t z m (16)

Taking into account relations (15) and (16), on Equation (17):

{ x ˙ 1 = x 2 x ˙ 2 = a 1 x 4 x 6 + a 2 x 2 2 + a 3 Ω r x 4 + b 1 U 2 x ˙ 3 = x 4 x ˙ 4 = a 4 x 2 x 6 + a 5 x 4 2 + a 6 Ω r x 2 + b 2 U 3 x ˙ 5 = x 6 x ˙ 6 = a 7 x 2 x 4 + a 8 x 6 2 + b 3 U 4 x ˙ 7 = x 8 x ˙ 8 = a 9 x 8 + 1 m U x U 1 x ˙ 9 = x 10 x ˙ 10 = a 10 x 10 + 1 m U y U 1 x ˙ 11 = x 12 x ˙ 12 = a 11 x 12 + cos ϕ cos θ m U 1 g

We can derive a simplified state representation of our state system as follows:

X ˙ = f ( X , U ) = { ϕ ˙ θ ˙ ψ ˙ a 1 + ϕ ˙ 2 a 2 + θ ˙ a 3 Ω r + b 1 U 2 θ ˙ ϕ ˙ ψ ˙ a 4 + θ ˙ 2 a 5 + ϕ ˙ a 6 Ω r + b 2 U 3 ψ ˙ ϕ ˙ θ ˙ a 7 + ψ ˙ 2 a 8 + b 3 U 4 x ˙ x ˙ a 9 + 1 m U x U 1 y ˙ y ˙ a 10 + 1 m U y U 1 z ˙ z ˙ a 11 + cos ϕ cos θ m U 1 g }

3. Return Control

The Backstepping control algorithm is synthesized to force the system to follow a desired trajectory.

The Backstepping command controls orientations (ϕ, θ, ψ) and positions (x, y, z). This design is based on the derived state vector (17) and relying on Lyapunov’s theory (particularly Lyapunov’s second method).

We first consider the command input for the angular rotations subsystem, then the position command input will be derived. On will deal for the subsystem of angular rotations: the roll controls U2, pitch U3 and yaw U4; with regard to the translations subsystem, we will highlight the commands for position in x Ux, position in y Uy and position z U1.

{ x ˙ 1 = x 2 x ˙ 2 = a 1 x 4 x 6 + a 2 x 2 2 + a 3 Ω r x 4 + b 1 U 2

The synthesis of the roll command U2 is done in two stages:

Step 1:

We take the first equation: x ˙ 1 = x 2

We define the error e1 between ϕ et ϕ d by:

e 1 = ϕ ϕ d = x 1 x 1 d

whose dynamics can be derived as follows:

e ˙ 1 = x ˙ 1 x ˙ 1 d = x 2 x ˙ 1 d

This definition explicitly indicates our command objective: the error e1 must asymptotically converge towards zero.

We choose the first candidate Lyapunov function of the following form:

V ( e 1 ) = 1 2 e 1 2

The calculation of the derivative of the Lyapunov function along the trajectory is solved as follows:

V ˙ ( e 1 ) = e 1 e ˙ 1 = e 1 ( x 2 x ˙ 1 d )

To ensure stability, it is necessary that V ˙ ( e 1 ) 0 ; for that we take as a virtual command x ˜ 2 avec x ˜ 2 = x ˙ 1 d k 1 e 1 avec k 1 > 0

This choice makes it possible to obtain:

V ˙ ( e 1 ) = e 1 ( k 1 e 1 ) = k 1 e 1 2

Step 2: As the virtual control cannot instantly take its desired value, we seek in what follows to stabilize the error between the virtual control and the stabilizing function. The second equation is defined by:

x ˙ 2 = a 1 x 4 x 6 + a 2 x 2 2 + a 3 Ω r x 4 + b 1 U 2

The new error variable between the virtual control and the stabilizing function is given by:

e 2 = x 2 x ˜ 2

e 2 = x 2 x ˙ 1 d + k 1 e 1

By linear combination, on a:

e ˙ 1 = e 2 k 1 e 1

And by derivation:

e ˙ 2 = x ˙ 2 x ¨ 1 d + k 1 ( e 2 k 1 e 1 )

The new Lyapunov function of the augmented system is ready as follows:

V ( e 1 , e 2 ) = 1 2 e 1 2 + 1 2 e 2 2

Its derivative is given by:

V ˙ ( e 1 , e 2 ) = e 1 ( e 2 k 1 e 1 ) + e 2 ( x ˙ 2 x ¨ 1 d + k 1 ( e 2 k 1 e 1 ) )

The choice of the control law must lead to a negative derivative of the Lyapunov function V ˙ ( e 1 , e 2 ) 0 as following:

V ˙ ( e 1 , e 2 ) = k 1 e 1 2 k 2 e 2 2 avec ( k 1 , k 2 ) > 0

The desirable dynamic for error at this stage is defined as:

e ˙ 2 = k 2 e 2 e 1

We find:

k 2 e 2 e 1 = x ˙ 2 x ¨ 1 d + k 1 ( e 2 k 1 e 1 ) (18)

By replacing with the expressions of (17) in (18):

U 2 = 1 b 1 [ x ¨ 1 d e 1 k 2 e 2 k 1 ( e 2 k 1 e 1 ) a 1 x 4 x 6 a 2 x 2 2 a 3 Ω r x 4 ]

U 3 , U 4 , U 1 , U x , U y are calculated in the same way.

U 3 = 1 b 2 [ x ¨ 3 d e 3 k 4 e 4 k 3 ( e 4 k 3 e 3 ) a 4 x 4 x 2 a 5 x 2 2 a 6 Ω r x 2 ]

U 4 = 1 b 3 [ x ¨ 5 d e 5 k 6 e 6 k 5 ( e 6 k 5 e 5 ) a 7 x 2 x 4 a 8 x 6 2 ]

U 1 = m cos x 1 cos x 3 [ x ¨ 11 d + g e 11 k 12 e 12 k 11 ( e 12 k 11 e 11 ) a 11 x 12 ]

U x = m U 1 [ x ¨ 7 d e 7 k 8 e 8 k 7 ( e 8 k 7 e 7 ) a 9 x 8 ]

U y = m U 1 [ x ¨ 9 d e 9 k 10 e 10 k 9 ( e 10 k 9 e 9 ) a 10 x 10 ]

4. Simulation Results

The six (6) control laws acquired in section II will be implemented in the Matlab/Simulink environment with the parameters of Table 1. Through these commands, it is a question of orienting and stabilizing the quadcopter to the desired values: [ ϕ d θ d ψ d ] = [ 0.2 0.2 0.2 ] (en radian) [ x d y d z d ] = [ 20 20 20 ] (en mètre).

Table 1. Physical parameters.

The results of the simulations are shown in Figures 3-5. They are distributed as follows:

Figure 4 presents the simulations of the Backstepping command applied to roll, pitch, yaw and the three positions (x, y, z), without disturbances. It can be seen that the Backstepping control correctly orientates and stabilizes the quadrirotor at the desired values. Ease of regaining gains favoring the stabilization of the quadrirotor.

Figure 5 shows the influence of disturbances on the Backstepping command. Using the Beaufort scale, we applied wind frequencies (frequency = 0.049 Hz) corresponding to winds of at least 22 m/s to our dynamics. There is a slight phase shift between the measurement and the desired destination for roll, pitch and yaw: the quadrirotor tends asymptotically towards the reference. On the other hand, despite this significant disturbance, the air vehicle awaits its altitude z and the x and y positions with stabilization at the desired value.

To validate the robustness of the backstepping control to a quadrirotor with six (6) degrees of freedom and to consolidate our work, we compared this control to the PID control. The PID controller was designed in the Matlab/Simulink environment and the results can be seen in Figure 5. From Figure 6, the response time of the system to the PID control is quite long compared to the Backstepping control, the difficulty of finding adequate gains allowing the quadrotor to reach the desired value and the stabilizer. This command is satisfactory at altitude.

Figure 3. Simulink model of Backstepping control and Quadrotor dynamics.

Figure 4. Backstepping control of roll, pitch, yaw, x, y, z positions without disturbances.

Figure 5. Backstepping control of roll, pitch, yaw, x, y, z positions with disturbances.

Figure 6. PID control of roll, pitch, yaw, x, y, z positions.

5. Conclusion

In this article, the stabilization in attitude and altitude of a quadrirotor by the Backstepping command has been successfully demonstrated. First, we presented the dynamic model of the quadcopter with six degrees of freedom, taking into account all the aerodynamic and gyroscopic effects. In the second part, we developed the Backstepping control strategy based on the Lyapunov function in order to guarantee the stability of the system. Then, this control algorithm was applied to the quadrirotor. Finally, the simulation results come from a high level of reliability, a very short and precise response time, stabilization with or without turbulence. All these advantages prove the robustness of the Backstepping command.

NOTES

1c: cosines.

2s: sinus.

Conflicts of Interest

The authors declare no conflicts of interest regarding the publication of this paper.

References

[1] Salih, A.-L., Moghavvemi, M., Mohamed, H.A.F. and Gaeid, K.S. (2010) Flight PID Controller Design for a UAV Quadrotor. Scientific Research and Essays, 5, 3360-3367.
[2] Szafranski, G. and Czyba, R. (2011) Different Approaches of PID Control UAV Type Quadrotor. International Micro Air Vehicles Conference, 70-75.
[3] García, R.A., et al. (2012) Robust PID Control of the Quadrotor Helicopter. IFAC Proceedings Volumes, 45, 229-334.
https://doi.org/10.3182/20120328-3-IT-3014.00039
[4] Yassine, J. (2016) Commande Non Linéaire Hiérarchique d’un drone de type quadrirotor sans mesure de la vitesse linéaire. Ecole de Technologie Supérieure, Université du Québec.
[5] Belobo Mevo, B. (2019) Contribution à la commande adaptative et robuste d’un robot mobile de type unicycle avec modèle non linéaire. Université du Québec en Abitibi Témiscamingue.
[6] Brossard, J., Bensoussan, D., Landry, R. and Hammami, M. (2019) A New Fast Compensator Design Applied to a Quadcopter. Proceedings of the 8th International Conference on Systems and Control, Marrakech, 23-25 October 2019, 238-247.
https://doi.org/10.1109/ICSC47195.2019.8950601
[7] Basri, M.A.M., Abidin, M.S.Z. and Subha, N.A.M. (2018) Simulation of Backstepping-Based Nonlinear Control for Quadrotor Helicopter. Applications of Modelling and Simulation, 2, 34-40.
[8] Djamel, K., Abdellah, M. and Benallegue, A. (2016) Attitude Optimal Backstepping Controller Based Quaternion for a UAV. Mathematical Problems in Engineering, 2016, Article ID: 8573235.
https://doi.org/10.1155/2016/8573235
[9] Bellahcene, Z., Bouhamida, M., Benghanem, M. and Laidani, A. (2012) La Commande Intégrale Backstepping Appliquée à un Hélicoptère à quatre hélices. 2ème CIMGLE’ 2012-19/21 Novembre 2012, Oran-ALGERIE.
[10] Babaei, R. and Ehyaei, A.F. (2015) Robust Backstepping Control of a Quadrotor UAV Using Extended Kalman Bucy Filter. International Journal of Mechatronics, Electrical and Computer Technology, 5, 2276-2291.
[11] Rodriguez, H.R., Vega, V.P., Orta, A.S. and Salazar, O.G. (2014) Robust Backstepping Control Based on Integral Sliding Modes for Tracking of Quadrotors. Journal of Intelligent & Robotic Systems, 73, 51-66.
https://doi.org/10.1007/s10846-013-9909-4
[12] Chen, F.Y., Jiang, R.Q., Zhang, K.K. and Jiang, B. (2016) Robust Backstepping Sliding Mode Control and Observer-Based Fault Estimation for a Quadrotor UAV. IEEE Transactions on Industrial Electronics, 63, 5044-5056.
[13] Nguyen, X.-M. and Hong, S.K. (2019) Robust Backstepping Trajectory Tracking Control of a Quadrotor with Input Saturation via Extended State Observer. Applied Sciences, 9, 5184.
https://doi.org/10.3390/app9235184

Copyright © 2024 by authors and Scientific Research Publishing Inc.

Creative Commons License

This work and the related PDF file are licensed under a Creative Commons Attribution 4.0 International License.