Next Article in Journal
The Effect of Block-Matrix Interface of SRM with High Volumetric Block Proportion on Its Uniaxial Compressive Strength
Previous Article in Journal
On Selecting, Ranking, and Quantifying Features for Building a Liver CT Diagnosis Aiding Computational Intelligence Method
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Comparative Study for Control of Quadrotor UAVs

Department of Mechanical and Aerospace Engineering, Politecnico di Torino, Corso Duca degli Abruzzi 24, 10129 Torino, Italy
*
Author to whom correspondence should be addressed.
Appl. Sci. 2023, 13(6), 3464; https://doi.org/10.3390/app13063464
Submission received: 15 February 2023 / Revised: 3 March 2023 / Accepted: 7 March 2023 / Published: 8 March 2023
(This article belongs to the Section Robotics and Automation)

Abstract

:
Modeling and controlling highly nonlinear, multivariable, unstable, coupled and underactuated systems are challenging problems to which a unique solution does not exist. Modeling and control of Unmanned Aerial Vehicles (UAVs) with four rotors fall into that category of problems. In this paper, a nonlinear quadrotor UAV dynamical model is developed with the Newton–Euler method, and a control architecture is proposed for 3D trajectory tracking. The controller design is decoupled into two parts: an inner loop for attitude stabilization and an outer loop for trajectory tracking. A few attitude stabilization methods are discussed, implemented and compared, considering the following control approaches: Proportional–Integral–Derivative (PID), Linear–Quadratic Regulator (LQR), Model Predictive Control (MPC), Feedback Linearization (FL) and Sliding Mode Control (SMC). This paper is intended to serve as a guideline work for selecting quadcopters’ control strategies, both in terms of quantitative and qualitative considerations. PID and LQR controllers are designed, exploiting the model linearized about the hovering condition, while MPC, FL and SMC directly exploit the nonlinear model, with minor simplifications. The fast dynamics ensured by the SMC-based controller together with its robustness and the limited estimated command effort of the controller make it the most promising controller for quadrotor attitude stabilization. The outer loop consists of three independent PID controllers: one for altitude control and the other two, together with a dynamics’ inversion, are entitled to the computation of the reference attitude for the inner loop. The capability of the controlled closed-loop system of executing complex trajectories is demonstrated by means of simulations in MATLAB/Simulink®.

1. Introduction

The growth of the number of applications of Unmanned Aerial Vehicles (UAVs) in many different fields, from civilian to military applications, has experienced a big rise over the last decade. As highlighted in specific literature reviews [1,2], the civilian applications of UAVs include activities such as parcel delivery, transportation of medical samples, mapping, surveillance, precision agriculture and greenhouses [3], population health monitoring, disaster recovery, personal use and photography, to name a few. The advantages due to the adoption of UAVs in each application domain have been widely reviewed. Just to give an example, considering the logistic domain discussed in [4], UAVs can contribute to optimizing the logistic process, reducing resources’ usage, traffic and CO2 emissions, inducing the diversification of transportation options as well as giving rise to new business models.
Therefore, UAVs have gained significant interest from the engineering research world over the last two decades. In particular, quadrotors are the most researched and used type of UAVs because of their mechanical structure, which is relatively simple to model, their enhanced closed-loop stability with respect to other configurations and their high maneuverability in both indoor and outdoor spaces, as described in [5]. However, quadcopters are mechatronic systems with nonlinear, multivariable, unstable, coupled and underactuated characteristics, which make the control not trivial.
Literature reviews such as [6,7,8,9] provide a comprehensive analysis of the main state-of-the-art control strategies for quadrotor UAVs. The well-known Proportional–Integral–Derivative (PID) control can effectively handle both linear and nonlinear systems. This is because it is model-independent and has a simple-to-understand tuning principle. Additionally, PID control can achieve zero steady-state error. On the other hand, PID control cannot handle constraints, is poorly robust with respect to disturbances and uncertainties and may require extensive tuning. The research in [10] implements a quadrotor attitude controller by means of a PID controller optimized with a genetic algorithm.
The Linear–Quadratic Regulator (LQR) control approach is equivalent to solving an optimization problem, with the cost function weighted of the squared norms of tracking error and control input signals, under the constraint of satisfying the system’s dynamics. It is designed with a linear approximation of the system and may not guarantee a zero steady-state error. LQR control can find an optimal feedback gain matrix considering both the tracking performances and the command input effort of the controller.
The Feedback Linearization (FL) control approach consists of a systematic procedure to linearize the system with a model inversion and control it with a new control input term. The system is transformed into a linear system without any linearization assumption and can be controlled according to the linear control theory. FL performs well when the nonlinear plant is similar to the one used for control design, so it is not very robust to parametric uncertainties and cannot handle constraints. A feedback linearization attitude controller with proportional action is proposed in [11].
The Sliding Mode Control (SMC) approach aims at bringing the system state to the “sliding surface”, which is a subset of the state space that corresponds to a desired dynamical behavior. The control law is the sum of a continuous function of the system’s state and the reference, which guarantees that the “sliding surface” is invariant (once the state is on the sliding surface, it remains on it), and a discontinuous term for convergence to the “sliding surface”. SMC shows, in general, good robustness to model uncertainties and disturbances, but a smooth approximation of the control law is necessary to avoid chattering, which may lead to instability.
The Model Predictive Control (MPC) approach solves an optimization problem at each defined time step to compute the optimal control input, satisfying the system’s dynamics, input and state constraints. A prediction model is exploited to predict the future states of the system. MPC is quite robust to disturbances but may be slow in tracking. The MPC-based position trajectory controller designed in [12], despite exploiting a linear model for prediction, shows the ability to ensure tracking of complex trajectories.
Furthermore, other control laws can be effectively applied to quadrotors, such as H-infinity, Backstepping, Adaptive, Fuzzy and Neural Network control. A Backstepping controller for position control of a quadrotor helicopter is designed and validated in [13], with stability being proven by the Lyapunov method. Additionally, a Fuzzy Logic controller for attitude control has been proposed in [14]. An L1 adaptive controller is designed and validated in [15] for the attitude controller of a mini-UAV. Adaptive control does not need a parameter tuning procedure and deals with parametric uncertainties and unmodelled dynamics. The Sliding Mode-based adaptive controller with Proportional–Integral–Derivative gains proposed in [16] controls a micro-UAV, the Parrot Mambo Minidrone, and is demonstrated on a model-based platform. In [17], an adaptive controller is proven to be able to deal with parametric uncertainties and external disturbances and performs well with unknown time delays inserted in the closed-loop dynamics.
In this paper, a comparative study of 3D trajectory control of a quadrotor system is proposed. The control system is decoupled into an outer loop for trajectory control and an inner loop for attitude control; input saturation is also taken into account. Despite several reviews of control algorithms for quadrotors being proposed in the literature, such as [6,7,8,9] to state a few, there is, to the best extent of our knowledge, poor availability of comparative studies where several approaches are implemented and discussed. The comparative study proposed in [18] implements PID, LQR, Fuzzy and Adaptive controllers for position trajectory tracking, while PID, LQR and MPC-based attitude stabilizers are implemented and discussed in [19]. In order to enlarge the available state of the art of quantitative comparative performance evaluation for quadrotors’ control, we propose a broad comparative implementation of different control approaches (PID, LQR, MPC, FL and SMC) to the quadrotor attitude stabilization problem. Linearized or simplified attitude dynamical systems are exploited in the design phase, yet all the controllers are tested with the proposed full nonlinear model. According to the fast dynamic response, the robustness to the discrepancy between the control model and the full nonlinear model and an approximative L2 norm-based trade-off evaluation of both the tracking performance and the command effort of the controller, the most suitable method is selected for the inner loop control part of the complete proposed control architecture. The outer loop is designed to track velocity references by exploiting PID control and a dynamics inversion from a simplified translational dynamical model.
This paper is organized as follows. The system model derived with the Newton–Euler formalism is reported in Section 2, as well as the proposed control system architecture, the proposed control laws and the simulation parameters setting. Section 3 presents the simulation results in which a micro-UAV is demonstrated to be able to execute complex trajectories with the complete control system. Conclusions and future research directions are drawn in Section 4.

2. Materials and Methods

2.1. System Model

Quadrotor UAVs are mechatronic systems with two rigid arms arranged in a cross configuration and four rotors. Each pair of rotors is located at the arm’s extremity and rotates in opposite directions. The speed of the rotors is controlled independently. A picture of a commercial quadrotor platform is shown in Figure 1. The movement of flying quadrotors derives from the total lift force produced by all rotors and from their capability of inclination, which is due to the resultant forces acting on the arms and to the resultant counter-torque caused by the pairs of rotors. The representation shown in Figure 2 is derived from the configuration of Figure 1, considered as a reference for the formulation of the quadrotor dynamical model.
Two reference frames are defined in order to characterize the position and the orientation of the UAV: a fixed inertial reference frame OXYZ and a body reference frame oxyz attached to the quadrotor. The relation between the two is expressed by the homogeneous transformation matrix T L derived with the Euler ZYX convention, also known as the RPY convention. The RPY convention involves three rotations. Firstly, a rotation of ψ (Euler yaw angle) about Z produces the frame OX 1 Y 1 Z . Secondly, a second rotation of ϑ (Euler pitch angle) about Y 1 results in the frame OX 2 Y 1 Z 1 . Lastly, a third rotation of ϕ (Euler roll angle) about X 2 results in the frame OX 2 Y 2 Z 2 (coincident with oxyz ). These rotations are performed according to a post multiplication rule,
T L = T ψ T θ T ϕ = c ψ s ψ 0 s ψ c ψ 0 0 0 1 c θ 0 s θ 0 1 0 s θ 0 c θ 1 0 0 0 c ϕ s ϕ 0 s ϕ c ϕ   = c ψ c θ c ψ s θ s ϕ s ψ c ϕ s ψ s ϕ + c ψ s θ c ϕ s ψ c θ c ψ c ϕ + s θ s ψ s ϕ s θ s ψ c ϕ s ϕ c ψ s θ c θ s ϕ c θ c ϕ  
where c and s denote cosine and sine functions, respectively. T L transforms linear movement-related vectors from oxyz to OXYZ . Consequently, T R transforms rotational movement-related vectors from OXYZ to oxyz ,
Δ = p q r = T ϕ T ϕ 0 0 + T ϕ T T θ T 0 θ 0 + T ϕ T T θ T T ψ T 0 0 ψ = 1 0 s θ 0 c ϕ c θ s ϕ 0 s ϕ c θ c ϕ ϕ θ ψ = T R ϕ θ ψ
where p , q and r denote the rotational velocities in the body frame, while ϕ , ϑ and ψ denote the Euler rates. The Newton–Euler formalism is adopted to present the quadrotor dynamical model; for further details about modeling refer to [21,22,23,24].
In the adopted model, the following assumptions are made:
  • The structure is perfectly symmetrical.
  • The structure is perfectly symmetrical.
  • The structure is perfectly rigid.
  • The quadrotor’s center of mass coincides with the origin of the body fixed frame.
  • The rotors’ motors dynamics are neglected.
  • Complex phenomena of difficult modeling are neglected, such as the ground effect, blade flapping and any other minor aerodynamical or inertial contributions not explicitly taken into account.
It follows the translational dynamical model in the inertial fixed reference frame,
m R = m g K d L R F 1 + F 2 + F 3 + F 4 T L
F i = 0 0 bw i 2   ,   with   i = 1 , 2 , 3 , 4
where R denotes the position vector in OXYZ , F i is the thrust force produced by rotor i , w i is the angular speed of rotor i , b is the thrust coefficient, m is the quadcopter’s mass, g is the gravity acceleration and K d L denotes the aerodynamic thrust drag coefficient. It follows the rotational dynamical model in the body reference frame,
I Δ = Δ   x   I Δ M g y K d R Δ + M
M g y = I R w 1 + w 3 w 2 w 4   Δ × 0 0 1  
M = L ( F 2 F 4 ) L ( F 1 F 3 ) d w 1 2 w 2 2 + w 3 2 w 4 2
I = I x 0 0 0 I y 0 0 0 I z
with the quadrotor’s arm length being L , the diagonal inertia matrix I , the inertia of the rotors I R , the drag coefficient d , the aerodynamic moment drag coefficient K d R , the rotors’ induced moment vector M and the gyroscopic moment vector M g y ; the latter is due to the fact that the axes of rotation of the propellers are attached to the quadrotor and rotate with it. The complete nonlinear dynamical model of the quadrotor is derived by evaluating Equations (3) and (5) and considering the transformations in Equations (1) and (2):
X = 1 m K d L X 1 m s ψ s ϕ + c ψ s θ c ϕ U 1  
Y = 1 m K d L Y 1 m s θ s ψ c ϕ s ϕ c ψ U 1  
Z = g 1 m K d L Z 1 m c θ c ϕ U 1  
p = I Y I z I x qr I R I x q w 1 + w 3 w 2 w 4 1 I x K d R p + 1 I x LU 2  
q = I z I x I y pr I R I y p w 1 + w 3 w 2 w 4 1 I y K d R q + 1 I y LU 3  
r = I x I y I z pq 1 I z K d R r + 1 I z U 4
ϕ = p + s ϕ s θ c θ 1 q + c ϕ s θ c θ 1 r  
θ = c ϕ q s ϕ r
ψ = s ϕ c θ 1 q + c θ 1 c ϕ r
u = U 1 U 2 U 3 U 4 = M bd w 2 = b b b b 0 b 0 b b 0 b 0 d d d d w 1 2 w 2 2 w 3 2 w 4 2  
It is worth noting that Equation (18) stands for an artificial input transformation made for ease of representation and control law definition. U 1 denotes the total lift force produced by the rotors, U 2 and U 3 are the resultant forces generating pitch and roll movement respectively and U 4 is the resultant moment acting on the yaw axis. The presented quadrotor dynamical model has 12 state variables x = x 1 ,   x 2 ,   x 3 , x 4 , x 5 , x 6 , x 7 , x 8 , x 9 , x 10 , x 11 ,   x 12 = X , Y , Z ,   X ,   Y ,   Z , ϕ , θ , ψ , p , q , r and 4 input variables u = u 1 , u 2 , u 3 , u 4 = U 1 , U 2 , U 3 , U 4 . Note that the rotors’ velocities giving the gyroscopic effect contribution still appear in Equations (12) and (13) but can be rewritten as a nonlinear function of the artificial input variables f u by inversion and manipulation of Equation (18).
f u = i = 1 4 1 i + 1   ( M bd 1 u ) i   = w 1 + w 3 w 2 w 4  
The system, besides presenting under-actuation characteristics that always yield to challenging control design aspects, is highly nonlinear and coupled. When dealing with a dynamical system with such properties, it is convenient to derive a linearized model in order to obtain a clearer understanding of the relation between control and state variables and the system’s stability. Furthermore, linearized models are often exploited for the design of the control law itself.
X = θ g  
Y = ϕ g
Z = g 1 m U 1  
ϕ = 1 I x LU 2
θ = 1 I y LU 3  
ψ = 1 I z U 4
The Equations (20)–(25) refer to the linearization of the model represented by the Equations (9)–(17) by means of a Taylor expansion of the first order and adopting approximations for small angles, under the following assumptions:
  • The quadrotor is hovering: external forces and moments are neglectable, linear and rotational velocities are small (the Euler rates coincide with the rotational velocities in the body frame).
  • The equilibrium control input and state vectors are u 1 , u 2 , u 3 , u 4 = mg , 0 , 0 , 0 and x 1 ,   x 2 ,   x 3 , x 4 , x 5 , x 6 , x 7 , x 8 , x 9 , x 10 , x 11 ,   x 12 = 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , respectively.
  • All terms of order higher than one are neglected.

2.2. System Control

If considering the linearized model in equations from (20) to (25) in the Laplace variable domain formulation, it is straightforward that the system is unstable due to the presence of poles in the origin. Additionally, the inputs U 2 , U 3 and U 4 directly affect the quadrotor’s attitude, while U 1 directly affects the altitude dynamics. Figure 3 shows the proposed control system’s architecture, decoupled in two parts: the inner loop performs attitude stabilization, while the outer loop is responsible for altitude control and reference attitude computation, given a 3D trajectory to be followed. Each control input signal Ui is saturated before being given to the plant, i.e., the quadcopter. The lower and upper saturation bounds are U i LB and U i UB , respectively. The propellers’ capacity is assumed to be such that the absolute value of the saturated total lift force U 1 SAT is equal to 3   mg . Analogously, an absolute value of 1.5   mg refers to U 2 SAT and U 3 SAT , while an absolute value equal to mgL refers to U 4 SAT .
The inner loop is intended to be sufficiently faster than the outer loop so that the UAV’s attitude can be effectively stabilized. Additionally, the state variables are assumed to be perfectly known to the controllers at each sampling instant. On the other hand, it is well known that the accuracy of position estimates may not be high enough to implement position-based trajectory controllers in many real-world applications. Consequently, the outer loop is intended to ensure tracking of velocity references.
As far as the inner loop is concerned, the choice of the best control law derives from a comparative evaluation of different linear and nonlinear controllers designed for attitude stabilization: PID, LQR, FL, SM and MPC. Both the tracking error and the controller command effort related to each controller are taken into account by means of the sum of the L2 norms of state and controller command input signals. Each attitude stabilization controller is designed with simplified models but is applied to the complete nonlinear attitude system expressed by Equations (12) to (17) for the sake of the evaluation. Instead, the outer loop implements a dynamic inversion and PID-based velocity controller.

2.2.1. Inner Loop—PID Control

This follows the linearized attitude dynamical system expressed by equations from (23) to (25) in state space form, with x = ϕ , θ , ψ , ϕ ,   θ ,   ψ and u = U 2 , U 3 , U 4 . Three independent Proportional–Integral–Derivative controllers are designed with the aim of stabilizing the linearized system in hovering.
x ˙ = A x + B u y = C x + D u  
A = 0 0 0 1 0 0 0 0 0 0 1 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0   ,   B = 0 0 0 0 0 0 0 0 0 LI x 1 0 0 0 LI y 1 0 0 0 I z 1   ,   C = 1 0 0 0 0 0 0 1 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0   ,   D = 0 0 0 0 0 0 0 0 0  
A classical formulation of the PID control law applied to the quadrotor stabilization problem in the time domain is presented in Equation (27). The three control parameters ( K p i , K i i , K d i ) of each control command are set in order to stabilize the model in (26) for the hovering equilibrium point. Refer to [25] for the theoretical foundations of PID control and further details.
u p t = u eq p K p p y p t y eq p K i p 0 T y p t y eq p dt K d p   y ˙ p t   y ˙ eq p   , u eq =   y eq = 0 , 0 , 0   ,   p = 1 , 2 , 3  

2.2.2. Inner Loop—LQR Control

The linearized attitude dynamical model in (26) is exploited to design the LQR-based attitude stabilizer. LQR controllers are based on optimization (minimization) of the sum of the weighted energies (L2 norms) of the state and the control command, with the constraints that the system dynamics are respected. According to the Linear–Quadratic Regulator method, since the linearized system is completely controllable, i.e., the controllability matrix has full rank, it is possible to define the following feedback control action,
u t = K x t  
K = R 1 B T P  
A T P + Q + PA PBR 1 B T P = 0  
Q = q 1 0 0 0 0 0 0 q 2 0 0 0 0 0 0 q 3 0 0 0 0 0 0 q 4 0 0 0 0 0 0 q 5 0 0 0 0 0 0 q 6   ,   R = r 1 0 0 0 r 2 0 0 0 r 3  
where K denotes the feedback control gain, Q and R are diagonal fixed weight matrices for the weighted L2 norms of x and u , respectively. The dynamics of the closed-loop system depend on the relative values of the control parameters: q i , r i . P can be computed by solving the Algebraic Riccati Equation formulated in Equation (30). Refer to [26] for the theoretical foundations of LQR control and further details.

2.2.3. Inner Loop—Feedback Linearization Control

This follows the attitude dynamical system exploited for the design of the feedback linearization-based attitude controller, with x = ϕ , θ , ψ , ϕ ,   θ ,   ψ and u = U 2 , U 3 , U 4 .
  x ˙ p = x p + 3   ,   p = 1 , 2 , 3
  x ˙ 4 = I Y I z I x x 5 x 6 I R I x x 5 f u 1 I x K d R x 4 + 1 I x Lu 1
  x ˙ 5 = I z I x I y x 4 x 6 I R I y x 4 f u 1 I y K d R x 5 + 1 I y Lu 2
  x ˙ 6 = I x I y I z x 4 x 5 1 I z K d R x 6 + 1 I z u 3  
Coincidence between Euler rates and angular velocities is assumed for the attitude controller’s design. The FL control law aims at linearizing the system with the term f L i and controlling it with a new control input term, u i , which is intended as the sum of a proportional gain with respect to the Euler angles’ errors and a derivative term, proportional to the Euler rates. Refer to [27] for the theoretical foundations of FL control and further details. Each control input is defined as follows.
u 1 = f L 1 + u 1 = I x L I Y I z I x x 5 x 6 + I R I x x 5 f u + 1 I x K d R x 4 + D 1 x 4 + P 1 x 1 ref x 1
u 2 = f L 2 + u 2 = I y L I z I x I y x 4 x 6 + I R I y x 4 f u + 1 I y K d R x 5 + D 2 x 5 + P 2 x 2 ref x 2  
u 3 = f L 3 + u 3 = I z I x I y I z x 4 x 5 + 1 I z K d R x 6 + D 3 x 6 + P 3 x 3 ref x 3  
The closed-loop attitude dynamical subsystem becomes linear and decoupled, the dynamics of the system can be adjusted by tuning the pairs ( D i , P i ). This follows the closed-loop attitude dynamics of the controlled system.
  x ˙ p = x p + 3   ,   p = 1 , 2 , 3  
  x ˙ 4 = D 1 x 4 + P 1 x 1 ref x 1  
x ˙ 5 = D 2 x 5 + P 2 x 2 ref x 2  
  x ˙ 5 = D 3 x 6 + P 3 x 3 ref x 3  

2.2.4. Inner Loop—Sliding Mode Control

The nonlinear attitude dynamical model in equations from (32) to (35) is exploited to design the sliding mode-based attitude stabilizer. The SM control method aims at the convergence of the state vector to another one, called the “sliding surface”, which corresponds to an exponential achievement of the desired dynamical behavior of the system. The control input is the sum of two terms: a continuous term and a discontinuous one. The former is a continuous function of the state variables and the reference, uc, that makes the “sliding surface”, s , an invariant set. The discontinuous term, ud, is added to achieve convergence to the “sliding surface”. s is intended as a PD “sliding surface” with respect to the Euler angles and Euler rates tracking errors. Refer to [28,29] for the theoretical foundations of SM control and further details.
u i = u c i + u d i   ,   i = 1 , 2 , 3  
u d i = K di sign s i = K di sign x i + 3 ref x i + 3 + β i x i ref x i   ~   K di s i s i 2 + a   ,   i = 1 , 2 , 3  
u c 1 = I x L I Y I z I x x 5 x 6 + I R I x x 5 f u + 1 I x K d R x 4 +   x   ˙ 4 ref + β 1 x 4 ref x 4  
u c 2 = I y L I z I x I y x 4 x 6 + I R I y x 4 f u + 1 I y K d R x 5 +   x   ˙ 5 ref + β 2 x 5 ref x 5  
u c 3 = I z I x I y I z x 4 x 5 + 1 I z K d R x 6 +   x   ˙ 6 ref + β 3 x 6 ref x 6  
The sign   · function in the discontinuous part of the control action is approximated with a smooth function (with a small value of a ) to avoid chattering, i.e., oscillations, when the state approaches the “sliding surface”. The closed-loop attitude dynamics of the system can be adjusted by tuning the control parameters: a , K di , β i . This follows the closed-loop attitude dynamics of the controlled system.
  x ˙ p = x p + 3   ,   p = 1 , 2 , 3
  x ˙ 4 =   x ˙ 4 ref + β 1 x 4 ref x 4 + K d 1 x 4 ref x 4 + β 1 x 4 ref x 4   x 4 ref x 4 + β 1 x 4 ref x 4 2 +   a
  x ˙ 5 =   x ˙ 5 ref + β 2 x 5 ref x 5 + K d 2 x 5 ref x 5 + β 2 x 5 ref x 5   x 5 ref x 5 + β 2 x 5 ref x 5 2 +   a
  x ˙ 6 =   x ˙ 6 ref + β 3 x 6 ref x 6 + K d 3 x 6 ref x 6 + β 3 x 6 ref x 6   x 6 ref x 6 + β 3 x 6 ref x 6 2 +   a

2.2.5. Inner Loop—Model Predictive Control

The state space form of the nonlinear attitude dynamical model in equations from (32) to (35) is exploited to design the model predictive attitude stabilizer. The MPC method is based on two phases: prediction and optimization. A prediction of the model’s states,   x p , is made over a certain prediction horizon, T P , by integration of the model itself. An optimal control input u is chosen to bring the predicted state to the reference r. The optimization problem formalized in (52) is solved to compute u t t + T P   = U 2 t t + T P , U 3 t t + T P ,   U 4 t t + T P
u Ϻ = arg   minJ u Ϻ   ,   subject   to :  
J u Ϻ = t t + T p x e r r T Ϻ Q x e r r Ϻ + u T Ϻ R u Ϻ d Ϻ + x e r r T t + T P Q x e r r t + T P   ,
x e r r Ϻ = r Ϻ x p Ϻ   ,  
Q = q 1 0 0 0 0 0 0 q 2 0 0 0 0 0 0 q 3 0 0 0 0 0 0 q 4 0 0 0 0 0 0 q 5 0 0 0 0 0 0 q 6   ,   R = r 1 0 0 0 r 2 0 0 0 r 3   ,   P = p 1 0 0 0 0 0 0 p 2 0 0 0 0 0 0 p 3 0 0 0 0 0 0 p 4 0 0 0 0 0 0 p 5 0 0 0 0 0 0 p 6   ,  
x ˙ P Ϻ = f x p Ϻ , u Ϻ   ,     x p Ϻ = x Ϻ   ,  
u Ϻ U L B ,   U U P   ,   Ϻ = t t + T P  
where U L B and U U P denote the lower and upper bounds of the optimal control input u , which would be subject to saturation anyway, x e r r is the predicted state’s error vector, Q , R and P denote diagonal matrices that contain the cost function J u Ϻ weight factors. The receding horizon strategy is applied to the aforementioned formulation of the problem at each time T z . T s denotes the sampling time. A constant input parametrization is chosen such that u t t + T z   = u T z   . q i , r i , p i , T s , T p and T z represent the control parameters. Refer to [30] for the theoretical foundations of MPC and further details.

2.2.6. Outer Loop

A simplified translational dynamical model is reported in state space form, with x = x 1 , x 2 , x 3 , x 4 , x 5 , x 6 =   X ,   Y ,   Z , ϕ , θ , ψ and u = U 1 .
  x ˙ 1 = 1 m s x 6 s x 4 + c x 6 s x 5 c x 4 u  
x ˙ 2 = 1 m s x 5 s x 6 c x 4 s x 4 c x 6 u  
  x ˙ 3 = g 1 m c x 5 c x 4 u  
The aim of the outer loop controller is to control the quadcopter’s altitude and to compute the reference Euler angles to be tracked by the inner loop controller. The outer loop controller is divided into two parts: the first part implements three PID controllers that compute the reference linear accelerations from the linear velocity errors, the second part performs a dynamics inversion of the system in equations from (53) to (55), with the assumption that ψ ref = 0 , for the computation of the reference pitch and roll angles, θ ref and ϕ ref , respectively, and the total lift force, u .
  x ˙ ref p t = K p p x p t x ref p t K i p 0 T x p t x ref p t dt K d p x p t x ref p t   ,   p = 1 , 2 , 3  
β = sign   x ˙ ref 1 1 + g   x ˙ ref 3   x ˙ ref 1 2 1 2  
x ref 4 = arcsin Bm u  
x ref 5 = arcsin β  
x ref 6 = 0  
u = m   x ˙ ref 1 2 β 2 +   x ˙ ref 2 2  
Equations from (56) to (61) express the full outer loop trajectory controller. The control parameters ( K p i , K i i , K d i ) can be set in order to ensure satisfactory dynamics for different 3D complex trajectories of reference, expressed by the signals x ref i t . In order to avoid numerical problems,   x   ˙ ref 1 is forced to have a lower bound different from zero in absolute value. A similar approach is proposed in [11].

2.2.7. Trajectory Generator

The ascent helix and the complex ascent helix are examples of relatively hard trajectories for quadcopters. They are considered as a benchmark for demonstrating the complete control system’s capability of executing complex trajectories. The ascent helix and the complex ascent helix are expressed as follows,
  X ˙ ref 1 t = f x 1 sin f x 1 t   ,   X ˙ ref 2 t = f x 2 sin f x 2 t 2 f x 2 sin f x 2 t cos f x 2 t  
  Y ˙ ref 1 t = f y 1 cos f y 1 t   ,   Y ˙ ref 2 t = f y 2 cos f y 2 t + 2 f y 2 cos f y 2 t sin f y 2 t
  Z ˙ ref 1 t =   Z ˙ ref 2 t = a  
where superscripts 1 and 2 indicates the ascent helix and complex ascent helix trajectories, respectively. t is the simulation time, f x , f y denotes the frequency of the signal components on the plane OXY and a denotes the climb velocity. The equations from (62) to (64) represent the derivation with respect to t of reference trajectories designed in space and time, expressed by the position variables X ref t , Y ref t , Z ref t .

2.3. Simulation Setting

The whole control architecture is implemented in the MATLAB/Simulink® software environment, mainly by means of MATLAB function blocks. Table 1 shows the simulation parameters, while the control parameter settings of all the proposed attitude stabilizers are reported in Table 2. All the values are expressed according to the International System of Units.

3. Simulation Results

3.1. Inner Loop

All the attitude stabilizers proposed in Section 2.2.1, Section 2.2.2, Section 2.2.3, Section 2.2.4, Section 2.2.5 are shown to be able to stabilize the nonlinear quadrotor attitude model, expressed by Equations (12)–(17), yet at different performance levels. All the simulations are performed considering the same initial condition for the plant, with the quadrotor having initial roll, pitch and yaw angles of 20° and initial roll, pitch and yaw rates of 10 rad/s. The gyroscopic effect is part of the nonlinear attitude dynamical system and is computed assuming a constant total lift force equal to the quadcopter’s weight in Equation (19). Figure 4, Figure 5, Figure 6, Figure 7 and Figure 8 show the Euler angles signals of the PID, LQR, FL, SMC and MPC-based attitude stabilizers, respectively.
The three pairs of proportional, integral and derivative gains of the PID-based attitude controller are tuned exploiting the automatic tuning library in MATLAB applied to the linearized system in (26), considering the control input saturation, to achieve a fast (rise time of ~1 s) and robust step response. As shown in Figure 4, the Euler angles dynamics relative to the PID-based stabilizer are much slower with respect to all the others, meaning that PID control is effective but requires extensive gain tuning and is not robust to model uncertainties, as the performances significantly decrease when the controller is applied to the nonlinear attitude system. As far as the classical PID control approach is concerned, which is the approach adopted in this work, a systematic procedure exists for tuning the controller’s gains; however, a highly time-consuming offline gains optimization is required when dealing with nonlinear systems, as for quadrotor UAVs. The amount of computation related to the online optimization of the MPC-based attitude stabilizer is such that the optimal solution is computed, on average, within 0.01 s. A control horizon T z = 0.05 s is chosen in order to guarantee the optimal controller command at each step. A trial-and-error tuning procedure is adopted for the choice of the control parameters of the other attitude stabilizers, which show faster dynamics and greater robustness to model uncertainties. The sum of the L2 norms of the Euler angles’ tracking error signals, L2x, is chosen as the approximative evaluation parameter of the controllers’ tracking performance. Analogously, the sum of the L2 norms of the controller command signals, L2u, represents the approximative evaluation parameter of the expected command activity of an on-board hardware implementation of the controller. Since the L2 norm of a signal represents the “energy” associated with the signal itself, it can be considered as an approximative quantitative estimation of both the overall tracking error and the controller command effort. Table 3 shows the controllers’ evaluation parameters referring to the attitude stabilization simulations presented in this section.
The proposed attitude stabilizers are ranked from best to worse as SMC, LQR, FL, MPC, PID for L2x and as PID, MPC, SMC, LQR, FL for L2u. Considering the attitude controllers that lead to the fastest dynamics (SMC, LQR and FL), the choice of the inner loop control law derives from a trade-off between tracking performances and controller command effort, since the battery consumption, being related to the forces and moments required to act on the quadcopter platform, is a key limitation factor when dealing with multirotor UAVs executing medium-to-long range missions. The SMC-based attitude stabilizer is the most promising one, having minimum L2x, intermediate L2u and ensuring fast dynamics to the controlled variables. Besides the norm evaluation, the FL-based controller yields to bigger peaks in the controlled signals. It is worth noting that ad-hoc simulation campaigns may be designed in order to tune the control parameters of each attitude stabilizer such that the system achieves a reference dynamic response. This could enhance performance, but the inherent features of each control approach would not change, as well as the highlighted differences among the methods.

3.2. Closed-Loop System

The complete controlled quadrotor system is proven to be able to execute complex 3D trajectories, defined by Equations (62)–(64). Both an ascent helix (trajectory 1) and a more complex ascent helix (trajectory 2) are simulated. The signals related to the controlled variables are shown in Figure 9 for trajectory 1, Figure 10 shows the corresponding quadcopter’s 3D trajectory, Figure 11 shows the control command signals required for executing trajectory 1. The Euler Angles signals related to trajectory 1 are shown in Figure 12. The signals related to the controlled variables are shown in Figure 13 for trajectory 2, Figure 14 shows the corresponding quadcopter’s 3D trajectory, Figure 15 shows the control command signals required for executing trajectory 2. The Euler Angles signals related to trajectory 2 are shown in Figure 16. Considering that either PID control is a model-free approach with an easy gain tuning procedure, or the outer loop controller is intended to ensure a much slower dynamic response with respect to the inner loop controller (order of a few seconds), a PID controller in the outer loop is sufficient to ensure a satisfactory dynamic response. The tracking performances are satisfactory for either the sinusoidal-based or the unitary step reference velocity signals, as shown in Figure 9 and Figure 13, which spatially derive in the helicoidal maneuvers shown in Figure 10 and Figure 14. Due to the inherent characteristics of PID control, a relatively small delay between the sinusoidal-based reference velocity signal and the actual quadcopter velocity is inevitable. That is reflected also in a smaller, yet present, delay in the tracking of the consequent sinusoidal-based Euler angles signals, as shown in Figure 12 and Figure 16. Overall, the proposed architecture can effectively control the quadcopter during complex maneuvers without exceeding the saturation limits, as shown by the signals of the controller commands in Figure 11 and Figure 15.

4. Conclusions

In this paper, a control system architecture for 3D trajectory tracking is implemented and simulated in MATLAB/Simulink® for a micro-quadrotor UAV. The highly nonlinear, coupled, unstable and underactuated plant system, i.e., the quadrotor, is modelled with the Newton–Euler formalism. The control architecture is intended to stabilize the quadrotor attitude dynamics, which is fully actuated with a sufficiently fast inner loop controller, and to track velocity references in the outer loop. A comparative study of well-known linear and nonlinear model-free and model-based control laws applied to the attitude stabilization problem is proposed: PID, LQR, FL, SMC and MPC attitude stabilization laws are designed and implemented. The choice of the inner loop controller derives from either the fast dynamics requirement of the inner loop or an L2 norm-based approximative evaluation of both tracking error and controller command signals since the relatively poor battery autonomy is still one of the main limitations for the deployment of multirotor UAVs in medium-to-long range missions. The reference attitude signals for the inner loop controller are derived from a simplified translational dynamics inversion performed in an outer loop controller, which is also responsible for altitude control. In the outer loop, the dynamics inversion is combined with three independent PID controllers, while the Sliding Mode attitude stabilizer is implemented in the inner loop. A velocity trajectory generator and a control input saturation block complete the proposed control architecture. The controlled closed-loop quadrotor system is proven to be able to execute complex 3D trajectories, such as ascent helixes. Consistent with the aim of this work, the main summarizing considerations are reported in Table 4 in order to highlight the main observations drawn from the study and provide guidelines for further research in this field.
Future research directions will include the realization of other comparative studies for control of quadrotor UAVs, considering external disturbances, e.g., the wind, and parametric uncertainties, e.g., variable payloads.

Author Contributions

All authors contributed extensively to the current study. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data used in the current study are available from the corresponding author upon reasonable request.

Acknowledgments

The authors wish to thank the Piedmont Aerospace District for supporting the PhD activity of Marco Rinaldi.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Cohen, A.; Shaheen, A.; Farrar, E. Urban Air Mobility: History, Ecosystem, Market Potential, and Challenges. IEEE Trans. Intell. Transp. Syst. 2022, 22, 6074–6087. [Google Scholar] [CrossRef]
  2. Nawaz, H.; Ali, H.M.; Massan, S.U.R. Applications of unmanned aerial vehicles: A review. 3c Tecnol. Glosas Innovación Apl. Pyme. 2019, 2019, 85–105. [Google Scholar]
  3. Aslan, M.F.; Durdu, A.; Sabanci, K.; Ropelewska, E.; Gültekin, S.S. A Comprehensive Survey of the Recent Studies with UAV for Precision Agriculture in Open Fields and Greenhouses. Appl. Sci. 2022, 12, 1047. [Google Scholar] [CrossRef]
  4. Skrinjar, J.P.; Skorput, P.; Furdic, M. Application of Unmanned Aerial Vehicles in Logistic Processes. In Proceedings of the New Technologies, Development and Applications (NT-2018), Sarajevo, Bosnia and Herzegovina, 14–16 June 2018. [Google Scholar]
  5. Idrissi, M.; Salami, M.R.; Annaz, F. A Review of Quadrotor Unmanned Aerial Vehicles: Applications, Architectural Design and Control Algorithms. J. Intell. Robot. Syst. 2022, 104, 22. [Google Scholar]
  6. Roy, R.; Islam, M.; Sadman, N.; Mahmud, M.A.P.; Gupta, K.D.; Ahsan, M.M. A Review on Comparative Remarks, Performance Evaluation and Improvement Strategies of Quadrotor Controllers. Technologies 2021, 9, 37. [Google Scholar]
  7. Shauqee, M.N.; Rajendran, P.; Suhadis, N.M. Quadrotor Controller Design Techniques and Applications Review. Incas Bull. 2021, 13, 179–194. [Google Scholar]
  8. Zulu, A.; John, S. A Review of Control Algorithms for Autonomous Quadrotors. Open J. Appl. Sci. 2014, 4, 547–556. [Google Scholar] [CrossRef] [Green Version]
  9. Shraim, H.; Awada, A.; Youness, R. A survey on quadrotors: Configurations, modeling and identification, control, collision avoidance, fault diagnosis and tolerant control. IEEE Aerosp. Electron. Syst. Mag. 2018, 33, 14–33. [Google Scholar] [CrossRef]
  10. Bolandi, H.; Rezaei, M.R.; Mohsenipour, R.; Nemati, H.; Smailzadeh, S.M. Attitude Control of a Quadrotor with Optimized PID Controller. Intell. Control Autom. 2013, 4, 335–342. [Google Scholar] [CrossRef] [Green Version]
  11. Voos, H. Nonlinear control of a quadrotor micro-UAV using feedback-linearization. In Proceedings of the 2009 IEEE International Conference on Mechatronics, Malaga, Spain, 14–17 April 2009. [Google Scholar]
  12. Islam, M.; Okasha, M.; Idres, M. Dynamics and Control of Quadcopter using Linear Model Predictive Control Approach. In Proceedings of the AEROS Conference 2017, Putrajaya, Malaysia, 12 December 2017. [Google Scholar]
  13. Madani, T.; Benallegue, A. Backstepping Control for a Quadrotor Helicopter. In Proceedings of the 2006 IEEE/RSJ International Conference on Intelligent Robots and Systems, Beijing, China, 9–15 October 2006. [Google Scholar]
  14. Petrusevski, I.; Aleksandar, R. Simple fuzzy solution for quadrotor attitude control. In Proceedings of the 12th Symposium on Neural Network Applications in Electrical Engineering (NEUREL), Belgrade, Serbia, 25–27 November 2014. [Google Scholar]
  15. Capello, E.; Guglieri, G.; Quagliotti, F.; Sartori, D. Design and Validation of an L1 Adaptive Controller for Mini-UAV Autopilot. J. Intell. Robot. Syst. 2013, 69, 109–118. [Google Scholar] [CrossRef]
  16. Noordin, A.; Mohd Basri, M.A.; Mohamed, Z. Position and Attitude Tracking of MAV Quadrotor Using SMC-Based Adaptive PID Controller. Drones 2022, 6, 263. [Google Scholar] [CrossRef]
  17. Sankaranarayanan, V.N.; Satpute, S.; Nikolakopoulos, G. Adaptive Robust Control for Quadrotors with Unknown Time-Varying Delays and Uncertainties in Dynamics. Drones 2022, 6, 220. [Google Scholar] [CrossRef]
  18. Shakeel, T.; Arshad, J.; Jaffery, M.H.; Rehman, A.U.; Eldin, E.T.; Ghamry, N.A.; Shafiq, M. A Comparative Study of Control Methods for X3D Quadrotor Feedback Trajectory Control. Appl. Sci. 2022, 12, 9254. [Google Scholar] [CrossRef]
  19. Okasha, M.; Kralev, J.; Islam, M. Design and Experimental Comparison of PID, LQR and MPC Stabilizing Controllers for Parrot Mambo Mini-Drone. Aerospace 2022, 9, 298. [Google Scholar] [CrossRef]
  20. Available online: https://basecamp-shop.com/en/product/dji-quadcopter-flame-wheel-arf-kit-450 (accessed on 18 November 2022).
  21. Ghazbi, S.N.; Aghli, Y.; Alimohammadi, M.; Akbari, A.A. Quadrotors Unmanned Aerial Vehicles: A Review. Int. J. Smart Sens. Intell. Syst. 2016, 9, 309–333. [Google Scholar] [CrossRef]
  22. Zhang, X.; Li, X.; Wang, K.; Lu, Y. A Survey of Modelling and Identification of Quadrotor Robot. Abstr. Appl. Anal. 2014, 2014, 1–16. [Google Scholar] [CrossRef]
  23. Moness, M.; Bakr, M. Development and Analysis of Linear Model Representations of the Quad-Rotor System. In Proceedings of the Aerospace Sciences and Aviation Technology, Cairo, Egypt, 26–28 May 2015. [Google Scholar]
  24. Naidoo, Y.; Stopforth, R.; Bright, G. Quad-Rotor Unmanned Aerial Vehicle Helicopter Modelling & Control. Int. J. Adv. Robot. Syst. 2011, 8, 139–149. [Google Scholar]
  25. Astrom, K.J.; Hagglund, T. Advanced PID Control; Instrumentation, Systems and Automation Society: Pittsburgh, PA, USA, 2006. [Google Scholar]
  26. Dorato, P.; Abdallah, C.; Cerone, V. Linear Quadratic Control: An Introduction; Krieger Pub Co.: Malabar, FL, USA, 2000. [Google Scholar]
  27. Krener, A.J. Feedback Linearization. In Mathematical Control Theory; Baillieul, J., Willems, J.C., Eds.; Springer: New York, NY, USA, 1999; pp. 66–98. [Google Scholar]
  28. Edwards, C.; Spurgeon, S. Sliding Mode Control: Theory and Applications; CRC Press: London, UK, 1998. [Google Scholar]
  29. Yan, B.; Dai, P.; Liu, R.; Xing, M.; Liu, S. Adaptive super-twisting sliding mode control of variable sweep morphing aircraft. Aerosp. Sci. Technol. 2019, 92, 198–210. [Google Scholar] [CrossRef]
  30. Rawlings, J.B.; Mayne, D.Q.; Diehl, M.M. Model Predictive Control: Theory, Computation, and Design; Nob Hill Publishing: Santa Barbara, CA, USA, 2020. [Google Scholar]
Figure 1. Picture of a commercial quadcopter platform [20].
Figure 1. Picture of a commercial quadcopter platform [20].
Applsci 13 03464 g001
Figure 2. Schematic representation of the quadrotor configuration of reference.
Figure 2. Schematic representation of the quadrotor configuration of reference.
Applsci 13 03464 g002
Figure 3. Overview of the proposed control system’s architecture.
Figure 3. Overview of the proposed control system’s architecture.
Applsci 13 03464 g003
Figure 4. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled attitude system (blue): PID-based Attitude Stabilizer (red).
Figure 4. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled attitude system (blue): PID-based Attitude Stabilizer (red).
Applsci 13 03464 g004
Figure 5. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled attitude system (blue): LQR-based Attitude Stabilizer (red).
Figure 5. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled attitude system (blue): LQR-based Attitude Stabilizer (red).
Applsci 13 03464 g005
Figure 6. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled attitude system (blue): FL-based Attitude Stabilizer (red).
Figure 6. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled attitude system (blue): FL-based Attitude Stabilizer (red).
Applsci 13 03464 g006
Figure 7. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled attitude system (blue): SMC-based Attitude Stabilizer (red).
Figure 7. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled attitude system (blue): SMC-based Attitude Stabilizer (red).
Applsci 13 03464 g007
Figure 8. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled attitude system (blue): MPC-based Attitude Stabilizer (red).
Figure 8. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled attitude system (blue): MPC-based Attitude Stabilizer (red).
Applsci 13 03464 g008
Figure 9. Velocity signals [ X t ,   Y t ,   Z t ] of the controlled quadrotor system (blue) and reference velocity signals of trajectory 1 (red).
Figure 9. Velocity signals [ X t ,   Y t ,   Z t ] of the controlled quadrotor system (blue) and reference velocity signals of trajectory 1 (red).
Applsci 13 03464 g009
Figure 10. 3D view of trajectory 1: position trajectory of the controlled quadrotor system.
Figure 10. 3D view of trajectory 1: position trajectory of the controlled quadrotor system.
Applsci 13 03464 g010
Figure 11. Control input signals [ u 1 t ,   u 2 t ,   u 3 t ,   u 4 t ] of the controlled quadrotor system executing trajectory 1.
Figure 11. Control input signals [ u 1 t ,   u 2 t ,   u 3 t ,   u 4 t ] of the controlled quadrotor system executing trajectory 1.
Applsci 13 03464 g011
Figure 12. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled quadrotor system (blue) and reference attitude signals for trajectory 1 (red).
Figure 12. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled quadrotor system (blue) and reference attitude signals for trajectory 1 (red).
Applsci 13 03464 g012
Figure 13. Velocity signals [ X t ,   Y t ,   Z t ] of the controlled quadrotor system (blue) and reference velocity signals of trajectory 2 (red).
Figure 13. Velocity signals [ X t ,   Y t ,   Z t ] of the controlled quadrotor system (blue) and reference velocity signals of trajectory 2 (red).
Applsci 13 03464 g013
Figure 14. 3D view of trajectory 2: position trajectory of the controlled quadrotor system.
Figure 14. 3D view of trajectory 2: position trajectory of the controlled quadrotor system.
Applsci 13 03464 g014
Figure 15. Control input signals [ u 1 t ,   u 2 t ,   u 3 t ,   u 4 t ] of the controlled quadrotor system executing trajectory 2.
Figure 15. Control input signals [ u 1 t ,   u 2 t ,   u 3 t ,   u 4 t ] of the controlled quadrotor system executing trajectory 2.
Applsci 13 03464 g015
Figure 16. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled quadrotor system (blue) and reference attitude signals for trajectory 2 (red).
Figure 16. Euler angles signals [ ϕ t ,   ϑ t , ψ t ] of the controlled quadrotor system (blue) and reference attitude signals for trajectory 2 (red).
Applsci 13 03464 g016
Table 1. Simulation parameters.
Table 1. Simulation parameters.
Simulation Parameter TypeParameterValue
UAV m 0.60   kg
g 9.81   m · s 2
b 3.60 · 10 6   kg · m
d 1.60 · 10 7   kg · m 2
I x 5.20 · 10 3   kg · m 2
I y 5.20 · 10 3   kg · m 2
I z 9.40 · 10 3   kg · m 2
I R 4.20 · 10 5   kg · m 2
L 0.20   m
K d R 0.15   kg · m 2 · s 1
K d L 0.15   kg · s 1
Saturation[ U 1 LB , U 1 UB ][ 17 ,   17 ] N
[ U 2 LB , U 2 UB ][ 9 ,   9 ] N
[ U 3 LB , U 3 UB ][ 9 ,   9 ] N
[ U 4 LB , U 4 UB ][ 1.2 ,   1.2 ] N · m
Trajectory Generator f x 1 = f y 1 1   s 1
a 1 m · s 1
f x 2 = f y 2 1   s 1
Outer Loop Controller K p 1 = K p 2 = K p 3 8
K i 1 = K i 2 = K i 3 8.5
K d 1 = K d 2 = K d 3 0.01
Derivative Filter Coefficient 100
Table 2. Attitude stabilization controllers’ parameters.
Table 2. Attitude stabilization controllers’ parameters.
Inner Loop ControllerControl ParameterValue
PID K p 1 = K p 2 = K p 3 0.56
K i 1 = K i 2 = K i 3 0.28
K d 1 = K d 2 = K d 3 0.23
Derivative Filter Coefficient 49.74
LQR[ q 1 , q 2 , q 3 , q 4 , q 5 , q 6 ][0, 0, 0, 1, 1, 1]
r 1 = r 2 = r 3 0.0001
FL[ D 1 , P 1 ][ 120 , 38 ]
[ D 2 , P 2 ][ 120 , 38 ]
[ D 3 , P 3 ][ 50 , 20 ]
SM[ K d 1 , β 1 ][ 0.2 , 20 ]
[ K d 2 , β 2 ][ 0.2 , 20 ]
[ K d 3 , β 3 ][ 0.05 , 5 ]
a 0.1
MPC T s 0.01 s
T p 0.1 s
T z 0.05 s
[ q 1 , q 2 , q 3 , q 4 , q 5 , q 6 ][10, 10, 1, 0, 0, 0]
r 1 = r 2 = r 3 0.0001
[ p 1 , p 2 , p 3 , p 4 , p 5 , p 6 ] [1, 1, 1, 0, 0,0]
Table 3. Evaluation parameters: sum of L2 norms of the controller commands signals, L2u, and sum of L2 norms of the Euler angles error signals, L2x.
Table 3. Evaluation parameters: sum of L2 norms of the controller commands signals, L2u, and sum of L2 norms of the Euler angles error signals, L2x.
Attitude Stabilizer.L2uL2x
PID1.601.40
LQR4.530.41
FL5.60.64
SMC4.350.36
MPC3.700.65
Table 4. Summarizing table of considerations drawn from the study. The number of diamonds is proportional to the “suitability of the method to UAV control”.
Table 4. Summarizing table of considerations drawn from the study. The number of diamonds is proportional to the “suitability of the method to UAV control”.
Control MethodAdvantagesDisadvantagesOverall Suitability to UAV Control
PID
  • Systematic gain tuning method for linear systems
  • Possible zero steady state error
  • Model free
  • No constraints handling
  • Poor robustness
  • No multiple inputs and multiple outputs handling
  • Extensive offline gain optimization
LQR
  • Possible handling of multiple inputs and multiple outputs
  • Possible handling of performance and command effort
  • Fast dynamics
  • May fail to overcome steady-state error
◊◊◊
FL
  • Systematic cancellation of nonlinearities
  • No constraints handling
  • Poor robustness
  • Model in affine form only
◊◊
SMC
  • Robustness
  • Fast dynamics
  • Good performances with highly nonlinear systems
  • Chattering may cause instability
◊◊◊◊
MPC
  • Possible handling of multiple inputs and multiple outputs
  • Possible handling of performance and command effort
  • Possible handling of input and output constraints
  • Slow dynamics
◊◊
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Rinaldi, M.; Primatesta, S.; Guglieri, G. A Comparative Study for Control of Quadrotor UAVs. Appl. Sci. 2023, 13, 3464. https://doi.org/10.3390/app13063464

AMA Style

Rinaldi M, Primatesta S, Guglieri G. A Comparative Study for Control of Quadrotor UAVs. Applied Sciences. 2023; 13(6):3464. https://doi.org/10.3390/app13063464

Chicago/Turabian Style

Rinaldi, Marco, Stefano Primatesta, and Giorgio Guglieri. 2023. "A Comparative Study for Control of Quadrotor UAVs" Applied Sciences 13, no. 6: 3464. https://doi.org/10.3390/app13063464

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop