Next Article in Journal
Numerical Simulation of Surface Subsidence and Fracture Evolution Caused by Pulang Copper Mine Mining
Previous Article in Journal
Impact of Laser Cavity Configurations and Pump Radiation Parameters on the Characteristics of High-Energy Yellow Raman Lasers Based on Potassium Gadolinium Tungstate Crystals
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Critically Leveraging Theory for Optimal Control of Quadrotor Unmanned Aircraft Systems

Department of Mechanical System Engineering, Gyeongsang National University, Tongyeong 53064, Republic of Korea
*
Author to whom correspondence should be addressed.
Appl. Sci. 2024, 14(6), 2414; https://doi.org/10.3390/app14062414
Submission received: 7 November 2023 / Revised: 22 December 2023 / Accepted: 24 December 2023 / Published: 13 March 2024

Abstract

:
In the dynamic realm of Unmanned Aerial Vehicles (UAVs), and, more specifically, Quadrotor drones, this study heralds a ground-breaking integrated optimal control methodology that synergizes a distributed framework, predictive control, H-infinity control techniques, and the incorporation of a Kalman filter for enhanced noise reduction. This cutting-edge strategy is ingeniously formulated to bolster the precision of Quadrotor trajectory tracking and provide a robust countermeasure to disturbances. Our comprehensive engineering of the optimal control system places a premium on the accuracy of orbital navigation while steadfastly ensuring UAV stability and diminishing error margins. The integration of the Kalman filter is pivotal in refining the noise filtration process, thereby significantly enhancing the UAV’s performance under uncertain conditions. A meticulous examination has disclosed that, within miniature Quadrotors, intrinsic forces are trivial when set against the formidable influence of control signals, thus allowing for a streamlined system dynamic by judiciously minimizing non-holonomic behaviors without degrading system performance. The proposed control schema, accentuated by the Kalman filter’s presence, excels in dynamic efficiency and is ingeniously crafted to rectify any in-flight model discrepancies. Through exhaustive Matlab/Simulink simulations, our findings validate the exceptional efficiency and dependability of the advanced controller. This study advances Quadrotor UAV technology by leaps and bounds, signaling a pivotal evolution for applications that demand high-precision orbital tracking and enhanced noise mitigation through sophisticated nonlinear control mechanisms.

1. Introduction

In the dynamic world of aerial technology, Quadrotor Unmanned Aerial Vehicles (UAVs) [1] have emerged as a transformative force, reshaping a multitude of fields from agriculture to disaster response. These versatile machines, known for their stability, vertical takeoff and landing capabilities, and relatively simple mechanical structure, have become increasingly indispensable in scenarios where human intervention is either too risky or impractical. Notable for their deployment in diverse environments–ranging from the precision-required tasks in agriculture [2,3,4,5,6] to the hazardous zones of natural disasters–Quadrotors stand at the forefront of technological innovation.
However, the true potential of these UAVs is yet to be fully realized. The challenges in ensuring stable, reliable, and autonomous operation amidst external uncertainties and noise remain significant [7,8]. While traditional control techniques like the Proportional Derivative (PD), Proportional Integral Derivative (PID), or Linear Quadratic Regulator (LQR) [9,10,11] have laid the groundwork for stability, they fall short in the face of unpredictable environmental variables. This has prompted a shift towards more advanced, AI-driven approaches [12] that seek to leverage complex feedback mechanisms for enhanced adaptability and precision.
Our research enters this evolving landscape with a ground-breaking approach: a novel optimal control system tailored for Quadrotors [13]. This paper unfolds the development of an innovative control methodology, integrating distributed control frameworks with cutting-edge Model Predictive Control (MPC) and H-infinity techniques. At the heart of this approach lies the Kalman filter [14,15], a critical tool in noise reduction and sensor data refinement, ensuring that the UAV’s responses are not just reactive but proactive, able to anticipate and adapt to future states and disturbances.
In this context, our study not only introduces a novel control mechanism but also addresses the non-holonomic control challenges inherent in Quadrotor dynamics [16,17,18,19,20,21]. Through meticulous evaluation and extensive simulations in Matlab/Simulink, we demonstrate that our control system can effectively bypass these constraints without compromising control quality. This development represents a significant leap in UAV technology, marking a new era in high-precision orbital tracking and advanced nonlinear control for noise mitigation. Our work is a testament to the innovative spirit driving the UAV field, signifying a monumental advancement in the practical application of these remarkable machines.

2. The Structure and Mathematical Model of the Quadrotor

2.1. Structure and Working Principle

The Quadrotor-type UAV (referred to as Quadrotor) is a flying device belonging to the helicopter type, with four propellers located in the same plane and equipped with four engines placed symmetrically through the center of the cross (Figure 1). The four propellers are identical in size, with two identical pairs, a pair of reverse blades, and a pair of forward blades interlaced in a clockwise rotation with the Quadrotor center as the center of rotation. The engines are also designed in the same way and operate so that two opposite blades rotate in the same direction, and two adjacent blades rotate in opposite directions to balance the torque generated on the frame.
Assuming that the front and rear propellers rotate counterclockwise while the right and left propellers rotate clockwise, the control of the Quadrotor involves managing the speed ratio between these four propellers. During takeoff (throttle up) and landing (throttle down), all four propellers must generate an equal thrust to achieve a combined force greater or less than gravity. To adjust the roll angle Φ, which involves rotating the Quadrotor around the axis formed by the front–back motor pair, the speed difference between the right and left propellers is varied while maintaining the same thrust produced by this pair. Similarly, to control the pitch rotation θ, which involves rotating the Quadrotor around the axis formed by the right–left motor pair, the speed of the front and rear propellers is adjusted while keeping the total thrust constant. The yaw angle Ψ, which entails rotating the Quadrotor around an axis perpendicular to the plane containing all four rotors, is achieved by changing the speed difference between the front and rear propellers, as well as between the right and left propellers while maintaining the total thrust. This allows the Quadrotor to maintain its original altitude (Figure 2).

2.2. Drone Kinematics

Think of the plane as a solid cross-shaped block. Set B = {B1, B2, B3} to be the coordinate system attached to the airframe, where B1 is the axis in the normal flight direction of the aircraft, B2 is perpendicular to B1, and to the right, B3 has the vertical direction upwards, perpendicular to the plane B1OB2. The coordinate system I = {EX, EY, EZ} is associated with the earth (Figure 3).
Vector ξ = [x y z]’ represents the position of the plane’s center of mass in the earth coordinate system. Orient the plane through a transfer matrix RI: B→I, where RI ϵ SO is an orthogonal matrix [22]. The transfer matrix can be obtained through three consecutive rotations around the three axes of the plane coordinate system. In this project, fixed Euler XYZ angles are utilized to describe the rotation of the UAV relative to the ground [23,24]. These angles must satisfy the following condition:
Roll angle, ɸ: π 2 < ɸ < π 2 ;
Pitch angle, θ: π 2 < θ < π 2 ;
Yaw angle, Ψ: π < Ψ < π .
From the above three rotations, the coordinate system transformation matrix from B→I is:
R I = c o s Ψ c o s θ c o s Ψ s i n θ s i n ɸ s i n Ψ c o s ɸ c o s Ψ s i n θ c o s ɸ + s i n Ψ s i n ɸ s i n Ψ c o s θ s i n Ψ s i n θ s i n ɸ + c o s Ψ c o s ɸ s i n Ψ s i n θ c o s ɸ c o s Ψ s i n ɸ s i n θ c o s θ s i n ɸ c o s θ c o s ɸ
The kinematic equations of rotation and translation can be derived using the transfer matrix. The translational kinematics can be expressed as follows:
v I = R I · v B
For vI = [uO vO wO]’ and vB = [uL vL wL]’, the linear velocities of the plane’s center of mass are represented in the earth coordinate system, and the plane coordinate system.
The rotation kinematics are derived from the relationship between the transfer matrix and the derivative with a skewed symmetry matrix as follows:
η ˙ = W η 1 ω
ɸ ˙ θ ˙ Ψ ˙ = 1 s i n ɸ t a n θ c o s ɸ t a n θ 0 c o s ɸ s i n ɸ 0 s i n ɸ s e c θ c o s ɸ s e c θ p q r
where η = [Φ θ Ψ]’ and ω = [p q r]’ are the angular velocities in the drone coordinate system.

2.3. Euler–Lagrange Equation

The plane kinematics equations can be expressed using the Euler–Lagrange formula based on kinetic and potential energy:
f ξ τ η = d d t L q ˙ i L q i
L q , q ˙ = E C t r a n s + E C r o t E p
where:
L is the Lagrange function of the Quadcopter model.
ECtrans is the kinetic energy of translational motion.
ECrot is the kinetic energy of rotation.
Ep is the total potential energy.
q = [ξ’ η’]’ is the vector of coordinates.
τη ϵ R3 represents roll, pitch, and yaw moments.
f ξ = R I f ^ + α T is the translational force applied to the aircraft by the main control input U1 in the direction of the z-axis with R I f ^ = R I e 3 U 1 2 .
α T = A x A y A z is the aerodynamic force vector, with axes components E x , E y , E z . Aerodynamic forces are considered external perturbations.
Since the Lagrange function does not contain the combined kinetic energy components of ɳ ˙ and ξ ˙ , the Euler–Lagrange equation can be divided into two parts: translational kinematics and rotational kinematics. The translational motion [25,26] can be represented by the following equation:
m ξ ¨ + m g e 3 = f ξ
Equation (7) can be represented by the state vector ξ:
x ¨ = 1 m c o s Ψ s i n θ c o s Φ + s i n Ψ s i n Φ U 1 + A x m y ¨ = 1 m s i n Ψ s i n θ c o s Φ c o s Ψ s i n Φ U 1 + A y m z ¨ = g + 1 m c o s θ c o s Φ U 1 + A z m                                            
where m is the mass of the plane and g is the acceleration due to gravity.
The equation for rotational kinetic energy, which represents rotational motions, is a function of η. Let Wɳ be the Jacobian matrix from ω to ɳ ˙ in (4), there are:
= ( ɳ ) = W ɳ J W ɳ
where J is the moment of inertia.
The equation of rotational kinetic energy:
E C r o t = 1 2 ɳ ˙ ɳ ˙
From the above representation, the Euler–Lagrange rotation equation with respect to ɳ can be written as:
M ɳ ɳ ¨ + C ɳ , ɳ ˙ ɳ ˙ = ɳ
With M ɳ = ɳ
M ɳ = I x x 0 I x x S θ 0 I y y C 2 Φ + I z z S 2 Φ I y y I z z C Φ S Φ C θ I x x S θ I y y I z z C Φ S Φ C θ I x x S 2 Φ + I y y S 2 Φ C 2 θ + I z z C 2 Φ C 2 θ
And
C ɳ , ɳ ˙ = C 11 C 12 C 13 C 21 C 22 C 23 C 31 C 32 C 33
where:
C 11 = 0 ;
C 12 = I y y I z z θ ˙ C ɸ S ɸ + Ψ ˙ S 2 ɸ C θ + I z z I y y Ψ ˙ C 2 ɸ C θ I x x Ψ ˙ C θ ;
C 13 = I z z I y y Ψ ˙ C 2 θ C ɸ S ɸ ;
C 21 = I z z I y y θ ˙ C ɸ S ɸ + Ψ ˙ S 2 ɸ C θ + I y y I z z Ψ ˙ C 2 ɸ C θ + I x x Ψ ˙ C θ ;
C 22 = I z z I y y ɸ ˙ C ɸ S ɸ ;
C 23 = I x x Ψ ˙ S θ C θ + I y y Ψ ˙ S 2 ɸ C θ S θ + I y y Ψ ˙ S 2 ɸ C θ S θ ;
C 31 = I y y I z z Ψ ˙ C 2 θ C ɸ S ɸ I x x θ ˙ C θ ;
C 32 = I z z I y y θ ˙ C ɸ S ɸ S θ + ɸ ˙ S 2 ɸ C θ + I y y I z z ɸ ˙ C 2 ɸ C θ + I x x Ψ ˙ S θ C θ I y y Ψ ˙ S 2 ɸ S θ C θ I z z Ψ ˙ C 2 ɸ C θ S θ ;
C 33 = I y y I z z ɸ ˙ C 2 θ C ɸ S ɸ I y y θ ˙ S 2 ɸ S θ C θ I z z θ ˙ C 2 ɸ S θ C θ + I x x Ψ ˙ θ ˙ S θ C θ .
Therefore, the mathematical model (used for controller synthesis) describing the aircraft’s rotation through the Euler–Lagrange equation is:
η ¨ = M η 1 τ η C η , η ˙ η ˙

3. Optimized Controller Design for Quadrotor

3.1. Controller Design

In order to obtain traction trajectories for the Quadrotor, it is necessary to combine the factors: controllability under the influence of external noise, uncertainty parameters, and dynamic modellessness. The proposed control strategy based on the distributed structure of the Quadrotor [27] is shown in Figure 4 below.
First, the trajectory set for the reciprocating motion is fed offline by the trajectory generator block. This calculation is based on a virtual prototype device that has the same model as the Quadrotor for translational motion. Therefore, based on the path x r , y r , z r , our desired translational motion along with its derivatives will compute the signals set for the control input U 1 r , u x r , u y r . The yaw angle is set later, which has nothing to do with the outer control loop. This trajectory is created with the assumption that no external disturbances will affect the virtual device and that the aircraft state is stable.
A predictive controller is used to control the reciprocating motion of the Quadrotor in the outer loop using the signal provided by the trajectory generator block. The Error-based State Space Predictor Controller (E-SSPC) model also includes an integral component of the position error in the state vector to achieve a steady state when continuous disturbances affect each other motion.
The reciprocating motion control is performed in two stages. The first controls the Quadrotor’s height z, and the total thrust U1 is the impact signal; the second stage, the set signal of the pitch and roll angles (respectively, θ r , ɸ r ) are calculated through two virtual inputs according to the requirement of motion in the x and y coordinates. It is important to mention that in this second step, the control variable U1 is utilized as a time-varying parameter.
Finally, the H controller designed for the rotational subsystem is employed in the inner loop to achieve stabilization of the Quadrotor. The angular position and speed are controlled in this ring through the torques on the three coordinate axes, τ η a = τ ɸ a τ θ a τ Ψ a are the action variables. In order to achieve the zero-displacement steady state in the presence of continuous external noise, the integral of angular position deviation is also considered. Due to the cascade structure of this strategy and considering the closed loop efficiency achieved by the control loop H , Euler angles can be considered as time-varying parameters in the design of the net controller up.

3.2. E-SSPC for Orbital Tracking

In this section, the control law is designed to solve the problem of tracing the set trajectory. In the context of a linear Model Predictive Control (MPC) state space framework incorporating model error (E-SSPC), two predictive controllers are synthesized based on the model error. The first controls the pitch through U1, and the second uses this signal to generate a time parameter in linear motions in the x- and y-axes to compute the two virtual inputs u ¯ x , u ¯ y .
To design the controller, Equation (8) can be rewritten in the state space form as follows:
ξ ˙ t = f ξ ¯ t , u ξ t
where ξ ¯ t = x ( t ) u 0 ( t ) y ( t ) v 0 ( t ) z ( t ) w 0 ( t ) represents the state space vector of the system. The components, u 0 t , v 0 t , w 0 ( t ) correspond to the linear velocity components of the Quadrotor center in the internal coordinate system representation.
Based on Equation (8) and the updated state space vector, the kinematic equation of the system can be formulated, which is utilized for the design of the control algorithm as follows:
ξ ˙ t = u 0 ( t ) u x t U 1 t m + A x ( t ) m u y t U 1 t m + A x ( t ) m g + c o s θ ( t ) c o s Φ ( t ) U 1 t m + A x ( t ) m
where:
u x t = cos Φ t sinθ t cos Ψ t + s i n Φ ( t ) s i n Ψ ( t ) ;
u y t = cos Φ t sinθ t sin Ψ t s i n Φ ( t ) c o s Ψ ( t ) .
Equation (8) demonstrates that the motion along the x- and y-axes is dependent on the control input U1. In fact, U1 is the magnitude of the total thrust designed to achieve the desired linear motion, while ux, uy can be viewed as the directions of U1 causing motions in the x- and y-axes.
The goal of this approach is to ensure that the UAV follows a predetermined trajectory and to minimize deviation. However, due to the fact that the set coordinates change with time, we need a virtual device with the same model as the Quadrotor:
ξ ¯ ˙ r = f ξ ¯ r t , u ξ r t
where:
ξ ¯ ˙ r ( t ) = x r ( t ) u 0 r ( t ) y r ( t ) v 0 r ( t ) z r ( t ) w 0 r ( t ) ;
u ξ r t = u x r u y r U 1 r ;
  • are the set states and control inputs, respectively. Assume there are no external disturbances in the virtual device. This virtual device allows us to obtain set control inputs for translational motions, assuming that the Quadrotor’s height is stable. Therefore, in this case, the set values are:
U 1 r = m · z ¨ r + g ;
u x r = x ¨ r · m U 1 r ;
u y r = y ¨ r · m U 1 r .
By subtracting the imaginary references (17) from (15), we can get the following model error of translational motion:
ξ ¯ ~ ˙ t = A t · ξ ¯ ˙ t + B t · u ~ ξ ( t )
where ξ ¯ ~ ˙ t = ξ ¯ t ξ ¯ r t is the error vector and u ~ ξ t = u ξ t u ξ r is the control input error. The matrices A(t) and B(t) are the Jacobi matrices of system (15). Moreover, to facilitate tracking performance in the presence of continuous perturbations, the error vector now incorporates an integral component of the position error.
Considering the error vector:
x ξ t = x ~ t u ~ 0 ( t ) x ~ t d t y ~ t v ~ 0 ( t ) y ~ t d t z ~ t w ~ 0 ( t ) z ~ t d t = x t x r ( t ) u 0 t u 0 r ( t ) x t x r ( t ) d t y t y r ( t ) v 0 t v 0 r ( t ) y t y r ( t ) d t z t z r ( t ) w 0 t w 0 r ( t ) z t z r ( t ) d t
Using Euler’s method, we get a discrete linear model with respect to time:
x ξ k + 1 = A ¯ · x ξ k + B ¯ k · u ~ ξ ( k )
In the given context, the control input U1(t) is treated as a time-varying parameter that governs the motion set in relation to the x- and y-coordinates. Additionally, considering the hierarchical control structure, the roll, pitch, and yaw angles are also regarded as time-dependent parameters.
The model error (20) can be divided into two subsystems: pitch error and motion error in terms of x and y. The matrices A ¯ , B ¯ for each subsystem are shown as follows:
A ¯ z = 1 t 0 0 1 0 t 0 1                                                                                                                       B ¯ z = 0 t m c o s θ ( k ) 0 c o s Φ ( k )                                                                                  
A ¯ x y = 1 t 0 0 0 0 0 1 0 0 0 0 t 0 1 0 0 0 0 0 0 1 t 0 0 0 0 0 1 0 0 0 0 t 0 1                                                               B ¯ x y = 0 0 t m U 1 ( k ) 0 0 0 0 0 0 t m U 1 ( k ) 0 0                                                                                  
where ∆t is the sampling time chosen to be small enough to retain all the translational errors but also large enough for steady-state rotation.
Based on these analyses, the trajectory tracking problem for Drones can be defined as follows: finding control inputs within a constrained range of values to manipulate the state variables in Equation (20) from an initial position x ξ 0 to the origin. Consequently, by considering the altitude difference and lateral movement, control rules are devised to compel the system to track the desired trajectory.
The first control law computes the input U1 such that the following cost function is minimal:
J z = x ^ ξ z x ^ ξ r z Q z x ^ ξ z x ^ ξ r z + u ~ ^ ξ z u ~ ^ ξ r z R z u ~ ^ ξ z u ~ ^ ξ r z + Ω ( x ^ ξ z k + N 2 z k x ^ ξ z r k + N 2 z k
In which the mass matrices Qz, Rz (which are diagonal matrices) are positively defined, N2z is the forecast window [28], and Ω is the final state cost:
Ω ( x ^ ξ z k + N 2 z k x ^ ξ z r k + N 2 z k ) = x ^ ξ z k + N 2 z k x ^ ξ z r k + N 2 z k × P z x ^ ξ z k + N 2 z k x ^ ξ z r k + N 2 z k
with Pz ≥ 0 [16].
The predictions of the model outputs x ^ ξ z k + j k are determined by linearizing the state-space model of the Quadrotor over time using Equations (20) and (21):
x ^ ξ z = P z k k · x ξ z k k + H z k k · u ~ ^ ξ z
where u ~ ξ z k k = U 1 k U r 1 k is the control input bias, and x ξ z k is the altitude error state vector.
x ^ ξ r z = x ξ r z k + 1 k x ξ r z k k x ξ r z k + N 2 z 1 k x ξ r z k k
u ^ ξ r z = U 1 r k k U 1 r k 1 k U 1 r k + N u z 1 k U 1 r k 1 k
where N u z is the control window.
Without considering the constraints, the control rule can be written as follows:
u ~ ^ ξ z = H z Q z H z + R z 1 · H z Q z x ^ ξ r z P z x ξ z k + R z u ~ ^ ξ r z
Although only u ~ ^ ξ z k k needs the instantaneous value of k.
Therefore, the control signal for the Quadrotor is as follows:
U 1 ( k ) = u ~ ^ ξ z k k + U 1 r ( k )
The second control law calculates the control inputs along the x- and y-axes. Similar to the previous methods utilizing model bias (20) and (21), the resulting control signal is obtained as:
u ~ ^ ξ x y = H x y Q x y H x y + R x y 1 · H x y Q x y x ^ ξ r x y P x y x ξ x y k + R x y u ~ ^ ξ r x y
where:
u ~ ^ ξ x y k k = u ~ x k k u ~ y k k u ξ x y k = u ξ r x y k + u ~ ^ ξ x y k k
The set vectors of the state deviations x ^ ξ r x y and the control input deviations u ^ ξ r x y are obtained by resembling the case of the altitude controller.
As a result, the vector of virtual desired directions, u ¯ ξ x y k = u ¯ x u ¯ y
u ¯ x t = c o s Φ r t s i n θ r t c o s Ψ t + s i n Φ r t s i n Ψ t u ¯ y t = c o s Φ r t s i n θ r t s i n Ψ t s i n Φ r t c o s Ψ t
If u is replaced by the desired values in (31), we have the expression:
u ¯ x k u ¯ y k = u ~ x k k u ~ y k k + u x r k u y r k
Once the imaginary inputs have been calculated, the set value of the roll and pitch angles, Φ r , θ r t , is used in Equation (32). These settings are necessary for the loop that controls the rotation of the Quadrotor.

3.3. Nonlinear Control H for Rotational Subsystem

The H controller [29] for the rotational subsystem is studied to achieve stability under the influence of external noises and uncertain parameters (Figure 5 and Figure 6).
According to the theory of nonlinear control H , and assuming the system ∑ is nonlinear:
: x ˙ = f x , u , d y = g x , u , d z = h x , u , d
has two inputs, u and d, two outputs, y and z, and state variable x:
Figure 5. Model of the H-inf nonlinear system.
Figure 5. Model of the H-inf nonlinear system.
Applsci 14 02414 g005
  • where u is the control vector, d is the input noise (noise to be suppressed or the signal to be tracked), y is the metering output, and z is the control lever output (tracking error, cost function). The optimal control problem H , roughly speaking, is to find a controller C that handles the output y and modulates the input u so that it is a closed loop:
Figure 6. Optimized control structure H-inf.
Figure 6. Optimized control structure H-inf.
Applsci 14 02414 g006
Having the L2-gain from [30], the input to output noise z is minimized; moreover, this closed loop must be stable in some sense ( H comes from the linear system case, L2-gain of the stable system is the H norm of the transfer function matrix).
Normally, optimizing H is a difficult problem; instead, it can approach a suboptimal controller H , with a given noise reduction factor γ such that the closed system has L2-gain ≤ γ and stable. The solution for H-optimal control can be approximated by iteration of the suboptimal H controller.
Going back to the Quadrotor problem, the kinematics of a smooth nonlinear system of order n, affected by unknown perturbations, can be expressed as follows:
x ˙ = f x , t + g x , t u + k x , t d
where:
u   ϵ   R p is the vector of control input signals.
d   ϵ   R p is the vector of external noise variables.
x   ϵ   R p is a vector of state variables.
Cost variable definition ξ   ϵ   R ( m + p ) :
ξ = W h x u
where h x   ϵ   R m is a function of the state vector x and W   ϵ   R ( m + p ) × ( m + p ) is the weight matrix. Assuming the state variable x can be measured, the optimization problem H is posed as follows [31,32]:
Find the minimum value of γ 0 such that for any γ γ , there exists a state response u = u x , t , such that the L2-gain from d to ξ is less than or equal to γ:
0 T ξ 2 2 d t γ 2 0 T d 2 2 d t
The function enclosed within the integral sign on the left-hand side of the inequality is expressed as:
ξ 2 2 = ξ ξ = h x u W W h ( x ) u
And the positive definite symmetry matrix W’W has the form:
W W = Q S S R
where Q and R are positively definite symmetric matrices, and for W W > 0 , then Q S R 1 > O (O is a 0-order matrix of n).
With those assumptions, there is an optimal control signal u ( x , t ) [33] as follows:
u = R 1 S h x + g x , t V ( x , t ) x
Let the system (20), where V(x,t) (provided that V ( x 0 , t ) 0 when t ≥ 0), be the solution of the Hamilton–Jacobi equation [34]:
V t + T V x f x , t + 1 2 T V x 1 γ 2 K x , t K T x , t G x , t R 1 G T ( x , t ) V x T V x G x , t R 1 C T h x + 1 2 h T x Q C R 1 C T h ( x ) = 0
Prove:
Considering the nonlinear system:
  • x ˙ = f x , t + G x , t u + K x , t u
  • y = h ( x )
Suppose there exists a non-negative solution V(x,t) (with V(x,t)≡ 0 for all t ≥ 0) that satisfies the Hamilton–Jacobi–Bellman–Isaacs (HJBI) equation:
V t + V x f x , t + 1 2 V x 1 γ 2 k x , t k x , t g x , t R 1 g ( x , t ) V x V x g x , t R 1 S h x + 1 2 h x Q S R 1 S h ( x ) = 0
Derivative V with respect to t:
d V d t = V t + T V x x ˙ = V t + T V x f + T V x G u + T V x K d = 1 2 u T R + h T C + T V x G R 1 R u + C T h + G T V x 1 2 γ 2 | | d 1 γ 2 K T V x | | 2 1 2 y T Q y 1 2 u T R u y T C u + 1 2 γ 2 | | d | | 2
To:
u = R 1 C T h x + G T ( x , t ) V x
Then:
d V d t 1 2 y T Q y 1 2 u T R u y T C u + 1 2 γ 2 | | d | | 2
Integrate both sides from 0 to t = T and notice that V x 0 , 0 = 0 and V x , t 0 :
1 2 0 T W y u 2 d t 1 2 γ 2 0 T d 2 d t
The rotational kinematics model derived from the Euler–Lagrange formula is used to develop the H nonlinear controller.
τ η can be written as:
τ η = τ η a + τ η d
where τ η a is the torque vector, and τ η d represents the total effect of the system model error and external noises.
Considering the error vector:
x η = η ~ ˙ η ~ η ~ d t = η ~ ˙ η ~ ˙ r η ~ η ~ r ( η ~ η ~ r ) d t
where η r and η ˙ r R n are the desired trajectory and velocity, respectively—notice that an integral component has been added to the error vector. Where η r and η ˙ r R n represent the desired trajectory and velocity, respectively. It is important to note that an integral component has been introduced to the error vector. This component will allow a zero-bias steady state to be achieved when noise components are acting continuously on the system [34,35,36].
Consider the following control structure for the rotary motion subsystem:
τ η a = M η η ¨ + C η , η ˙ η ˙ T 1 1 M η T x ˙ η + C η , η ˙ T x η + T 1 1 u
τ η a can be divided into three parts: the first part consists of the first two expressions, which is the kinematic part of the system. The second part has two components containing the deviation vector x η and its derivative x ˙ η . Assuming τ η d = 0 , these two components of the control law allow perfect tracing of the orbital set. Finally, the third part consists of a vector u, representing the control to remove noise.
The matrix T can be written as:
T = T 1 T 2 T 3
where T 1 = ρ I , ρ is positive and scalar, and I is the unit matrix of order n.
Replace the control rule (49) into (11) and denote d = M η T 1 M 1 η τ η d :
u + d = M η T x ˙ η + C η , η ˙ T x n
The above formula represents the kinematic equation of the systematic error. Considering this nonlinear equation, the H nonlinear control problem can be formulated as follows:
Find a control law u(t) where the ratio between the energy of the cost variable ξ = W h x η u and the energy of the noisy signals d is less than the given attenuation γ.
From considering the matrix W in (39), consider the structure for the matrix Q and S:
Q = Q 11 Q 12 Q 13 Q 21 Q 22 Q 23 Q 31 Q 32 Q 33 ,           S = S 1 S 2 S 3
To apply the theoretical results proved above, we need to rewrite the nonlinear kinematics equation of the deviation according to the standard form of the nonlinear control H in the following form:
x ˙ η = f x η , t + g x η , t u + k x η , t d
where:
f x η , t = T 0 1 M η 1 C η , η ˙ 0 0 T 1 1 I T 1 1 T 2 I + T 1 1 T 2 T 3 0 I I T 0 x η
g x η , t = k x η , t = T 0 1 M η 1 0 0
where:
T 0 = T 1 T 2 T 3 0 I I 0 0 I
The solution of the Hamilton–Jacobi–Bellman–Isaacs (HJBI) function relies on the selection of the cost function ξ, particularly the choice of the function h x η . Here, choose h x η = x η . Once chosen, computing the control law u will require finding the Lyapunov function V x η , t .
The following theorem will help us do this:
Theorem: Given a scalar function V x η , t :
V x η , t = 1 2 x η T 0 M η 0 0 0 Y X Y 0 X Y Z + Y
where X , Y , Z R n × n are constant matrices and positively symmetric such that Z X Y 1 X + 2 X > 0 and T0 are defined in (54). T is the matrix in (50). If these matrices satisfy:
O Y X Y 2 X Z + 2 X X Z + 2 X O + Q + 1 γ 2 T T S + T R 1 S t + T = 0
Then the function V x η , t at (55) will be a solution of the HJBI equation with a value of γ.
This theorem is obtained from Ortega et al. (2005) [34].
Considering the system, prove:
M q q ¨ + N q , q ˙ = τ + τ d
where:
N q , q ˙ = C q , q ˙ q ˙ + F q ˙ + G q
where q R n is the state variable, and q ˙ is its derivative. Assume that these two vectors are both measurable. The vector τ serves as the input signal of the system, while τd represents the cumulative noise and errors of the system. The inertial matrix M(q) is symmetric and positively defined, C q , q ˙ q ˙ is the radial vector and Coriolis, F q ˙ represents friction, and G(q) is gravity.
As we know, the matrix C q , q ˙ is not unique, so for convenience, it can be written as:
C q , q ˙ = 1 2 M ˙ q , q ˙ + N q , q ˙
where M ˙ q , q ˙ and N q , q ˙ are calculated:
M ˙ i j = d d t M i j = M i j q q ˙ = k = 1 n M i j q k q ˙ k
N i j = 1 2 k = 1 n M i k q j M i j q i q ˙ k
Consider the function:
V x , t = 1 2 x T T 0 T M 0 0 0 Y X Y 0 X Y X + Y T 0 x
The function V(x,t) is positive if and only if:
M 0 0 0 Y X Y 0 X Y X + Y > 0
When the inertial matrix M is symmetric, positive definite, and assuming the matrices X , Y , Z R n × n are constant, symmetric, positive definite matrices, then the above inequality is satisfied if and only if:
Z + Y ( X Y ) Y 1 ( X Y ) > 0
Or:
Z X Y 1 X + 2 X > 0
(65) is the hypothesis.
Next, notice that V(x,t) is a solution to the Hamilton-Jacobi equation:
V t + T V x f x , t + 1 2 T V x 1 γ 2 k x , t k T x , t g x , t R 1 g T x , t V x g x , t R 1 S T h x + 1 2 h T x Q S R 1 S T h x = 0
Vector gradient of V(x,t):
T V x , t x = x T T T M 0 0 0 Y X Y 0 X Y Z + Y T 0 + 1 2 0 1 n Ω 0 1 n
where Ω R 1 n
x T T 0 T T M q 1 0 0 0 0 0 0 0 0 T 0 x , , x T T 0 T T M q n 0 0 0 0 0 0 0 0 T 0 x
Deduce:
0 1 n Ω 0 1 n g x , t u + k ( x , t ) ω = 0
The result is:
T V ( x , t ) x f = x T T T M 0 0 0 Y X Y 0 X Y Z + Y T 0 + 1 2 0 1 n Ω 0 1 n f = x T T T M 0 0 0 Y X Y 0 X Y Z + Y T 0 f + 1 2 0 1 n Ω 0 1 n f + 1 2 0 1 n Ω 0 1 n g u + k ω = x T T 0 T M 0 0 0 Y X Y 0 X Y Z + Y T 0 f + 1 2 0 1 n Ω 0 1 n x ˙
Instead, have:
x T T 0 T M 0 0 0 Y X Y 0 X Y X + Y T 0 f = x T T 0 T M 0 0 0 Y X Y 0 X Y X + Y M 1 1 2 M + N 0 0 1 ρ I I 1 ρ T 2 I 1 ρ Y T 3 T 2 0 I I T 0 x = x T T 0 T 1 2 M + N 0 0 1 ρ γ X 1 ρ Y T 2 X 1 ρ Y ( T 3 T 2 ) 1 ρ ( X Y ) A 1 ρ ( X Y ) T 2 A 1 ρ ( X Y ) ( T 3 T 2 ) T 0 x
where A= X + Z.
And:
1 2 0 1 n Ω 0 1 n x ˙ = 1 2 0 1 n Ω 0 1 n e ¨ e ˙ e = 1 2 Ω e ˙ = 1 2 x T T 0 T k = 1 n T M q k q ˙ k q ˙ r k 0 0 0 0 0 0 0 0 T 0 x
The derivative V(x,t) with respect to time is:
V t = 1 2 x T T 0 T k = 1 n T M q k q ˙ r k 0 0 0 0 0 0 0 0 T 0 x
Substituting it into the above expression, we get:
V t + T V ( x , t ) x f = V t + x T T 0 T M 0 0 0 Y X Y 0 X Y Z + Y T 0 f + 1 2 0 1 n Ω 0 1 n x ˙ = 1 2 x T T 0 T k = 1 n T M q k q ˙ r k 0 0 0 0 0 0 0 0 T 0 x + x T T 0 T M 0 0 0 Y X Y 0 X Y Z + Y T 0 f + 1 2 x T T 0 T k = 1 n T M q k q ˙ k q ˙ r k 0 0 0 0 0 0 0 0 T 0 x = x T T 0 T M 0 0 0 Y X Y 0 X Y Z + Y T 0 f + 1 2 x T T 0 T k = 1 n T M q k q ˙ r k 0 0 0 0 0 0 0 0 T 0 x = x T T 0 T 1 2 M + N 0 0 1 ρ γ X 1 ρ Y T 2 X 1 ρ Y ( T 3 T 2 ) 1 ρ ( X Y ) A 1 ρ ( X Y ) T 2 A 1 ρ ( X Y ) ( T 3 T 2 ) T 0 x + 1 2 x T T 0 T M ˙ 0 0 0 0 0 0 0 0 T 0 x = x T T 0 T N 0 0 1 ρ γ X 1 ρ Y T 2 X 1 ρ Y ( T 3 T 2 ) 1 ρ ( X Y ) A 1 ρ ( X Y ) T 2 A 1 ρ ( X Y ) ( T 3 T 2 ) T 0 x
The calculation shows that N is a matching matrix, and due to the special structure of T0, we get:
x T T 0 T N 0 0 0 0 0 0 0 0 T 0 x = 0
Replacing the above equation, we get:
V t + T V ( x , t ) x f = x T T 0 T N 0 0 1 ρ γ X 1 ρ Y T 2 X 1 ρ Y ( T 3 T 2 ) 1 ρ ( X Y ) A 1 ρ ( X Y ) T 2 A 1 ρ ( X Y ) ( T 3 T 2 ) T 0 x = x T 0 0 0 Y X 0 X 2 X + Z 0 x = 1 2 x T 0 0 0 Y X 0 X 2 X + Z 0 + 0 Y X 0 X 2 X + Z 0 0 0 x = 1 2 x T 0 Y X Y X Z + 2 X X 2 X + Z 0 x
The expression g T x , t V x , t x is calculated by:
g T x , t V x , t x = M 1 0 0 T 0 1 T T 0 T M 0 0 0 Y X Y 0 X Y Z + Y T 0 x = I 0 0 T 0 x = T x
1 2 T V x 1 γ 2 k x , t k T x , t g x , t R 1 g T x , t V x = 1 2 x T T T 1 γ 2 I R 1 T x
In addition, there is g(x,t) = k(x,t) so:
1 2 x T 0 Y X Y X Z + 2 X X 2 X + Z 0 x + 1 2 x T T T 1 γ 2 I R 1 T x x T T T R 1 S T x + 1 2 x T Q S R 1 S T x = 0
Simplifying this expression, we get the proof.
Back to the Quadrotor problem:
The matrix T = T 1 T 2 T 3 is calculated by solving some of the following Riccati mathematical equations:
T 1 : T 1 T 1 γ 2 I R 1 T 1 S 1 R 1 T 1 T 1 T R 1 S 1 T S 1 R 1 S 1 T + Q 1 = 0
T 2 : T 2 T 1 γ 2 I R 1 T 2 S 2 R 1 T 2 T 2 T R 1 S 2 T S 2 R 1 S 2 T + Q 2 + 2 X = 0
T 3 : T 3 T 1 γ 2 I R 1 T 3 S 3 R 1 T 3 T 3 T R 1 S 3 T S 3 R 1 S 3 T + Q 3 = 0
X : T 1 T 1 γ 2 I R 1 T 3 S 1 R 1 T 3 T 1 T R 1 S 3 T S 1 R 1 S 3 T + Q 13
Substituting V x η , t into (41), the control law u* corresponding to the optimal index H , γ is:
u = R 1 S + T x η
Finally, substituting the above control rule into (49), together with some transformations, the optimal control law becomes:
τ η a = M η η ¨ + C η , η ˙ η ˙ M η K D η ~ ˙ + K P η ~ + K I η ~ d t
where:
K D = T 1 1 T 2 + M η 1 C η , η ˙ T 1 + M η 1 R 1 S 1 + T 1
K P = T 1 1 T 3 + M η 1 C η , η ˙ T 2 + M η 1 R 1 S 2 + T 2
K I = T 1 1 M η 1 C η , η ˙ T 3 + M η 1 R 1 S 3 + T 3
The special case when the components of W’W are satisfied is:
Q 1 = ω 1 2 I ,   Q 2 = ω 2 2 I ,   Q 3 = ω 3 2 I ,   Q 4 = ω 4 2 I   Q 12 = Q 13 = Q 23 = O S 1 = S 2 = S 3 = O
where:
K D = ω 2 2 + 2 ω 1 ω 3 ω 1 I + M η 1 C η , η ˙ + 1 ω u 2 I
K P = ω 3 ω 1 I + ω 2 2 + 2 ω 1 ω 3 ω 1 M η 1 C η , η ˙ + 1 ω u 2 I
K I = ω 3 ω 1 M η 1 C η , η ˙ + 1 ω u 2 I
where the parameters ω 1 , ω 2 , ω 3 , and ω u can be adjusted.
These expressions have one important feature: they do not depend on the parameter γ, so it can be obtained using an algebraic expression to compute the optimal solution for this particular case. The simulation below will simulate this case.

3.4. Kalman Filter

The Kalman filter is a state estimation algorithm that provides estimates of the internal states of a process in a way that minimizes the mean of the squared error. It is particularly useful in quadcopters for filtering out sensor noise and providing a more accurate state estimate for control purposes.
The basic Kalman filter equations for prediction and update phases are as follows:
-
Prediction:
x ^ k k 1 = A k x ^ k 1 + B k u k 1
P k k 1 = A k P k 1 A k T + Q k
-
Update:
K k = P k k 1 C k T C k P k k 1 C k T + R k 1
x ^ k = x ^ k k 1 + K k y k C k x ^ k k 1
P k = I K k C k P k k 1
where:
x ^ k : State estimation at time k;
A k , B k , C k : System model matrices;
u k 1 : Control input at time k − 1;
P k : State estimation covariance matrix;
Q k : Process noise covariance matrix;
R k : Measurement noise covariance matrix;
y k : Measurement data at time k;
K k : Kalman Gain, balancing between model estimation and measurement data.

3.5. Evaluating Quadrotor Controller Robustness to Disturbances in Maritime Environments

Quadrotors have promising applications for tasks like maritime surveillance, environmental monitoring, and cargo delivery at sea [37]. However, operating in coastal and offshore conditions introduces environmental disturbances not present in typical indoor/outdoor flights. Winds, waves, and vessel motion generate forces that can challenge the stability and tracking performance of onboard controllers [38]. It is, therefore, important to evaluate how Quadrotor flight controllers perform when subjected to realistic wind disturbances representative of different sea states.
This part aims to simulate the effect of turbulent wind gusts on a Quadrotor and assess the robustness of its controller. Wind field and turbulence models are implemented to produce disturbance signals reflecting varying sea conditions. Simulation results under these disturbances provide quantitative metrics to evaluate the controller’s ability to reject wind forces and maintain stable flight. The approach allows for characterizing controller robustness to environmental conditions, benefiting the future development of autonomous Quadrotor systems for maritime operations.
Wind disturbance modeling to realistically simulate wind disturbances can be implemented, as in the following two common turbulence models.
The turbulent wind field model generates 3D wind vector fields based on turbulence kinetic energy (k) and turbulence length scales (87) [39]. The wind speed vector at any point in space and time is given by:
w x , t = w + w x , t
where:
w : the mean wind;
w : represents turbulent fluctuations.
w is calculated as per Kolmogorov’s theory of isotropic turbulence [40].
The Dryden wind turbulence model wind gusts and turbulence as a stationary random process using non-dimensional power spectral density functions S(ω) parameterized by turbulence scales [41]. The model generates independent wind speed components:
w i t = w i 0 + σ i S ω e i ω t d t
where:
w i 0 : means wind;
σ i : the turbulence intensity.
S ω is defined per [41].
Both models realistically simulate gusts of varying magnitude and frequency based on turbulence conditions.

4. Optimized Controller Design for Quadrotor

4.1. Nonlinear Control H for Rotational Subsystem

The control structure for the rotation angles ɳ = Φ θ Ψ and the position ξ = x y z of the Quadrotor unmanned aircraft system [42,43,44] (Figure 7) is as follows:
There are four main blocks in the control structure in the schematic diagram in the simulation.
Trajectory generator block: It is responsible for calculating and giving the set values for the desired position (x, y, z) of the Quadrotor. The values of U 1 r , u x r , u y r are calculated according to the formula:
U 1 r = m · z ¨ r + g
u x r = x ¨ r · m U 1 r
u y r = y ¨ r · m U 1 r
At the same time, this block calculates the prediction matrices of the control inputs U 1 r , u x r , u y r and the desired outputs (x, y, z) to serve the predictive control block E-SSPC.
E-SSPC block: It is responsible for calculating and giving the optimal control value U1 for the Quadrotor and the set values φ r , θ r to put into the optimal control block H from the desired set values of the Quadrotor position and state feedback about the position and rotation of the Quadrotor.
H_infinity controller block: It is responsible for calculating the torque values to control the Quadrotor rotation from the φ r , θ r set values of the ESSPC block and the Quadrotor’s rotational state feedback.
Quadrotor block: Is the kinematic model of the object.

4.2. Control Parameters

The basic parameters of the object in the simulation are shown in Table 1.
Original location ξ 0 = 0.3   m 0.2   m 0   m , η 0 = 0   r a d 0   r a d 0.5   r a d
The parameters ω are adjusted as follows:
ω 1 = 0.1 , ω 2 = 3 , ω 3 = 9 ,       ω u = 1.5
The parameters of the E-SSPC controller are selected as follows:
N 2 z = N u z = 3 , N 2 y = N u y = N 2 x = N u x = 5
Q z = d i a g 1 0.8 10 ; R z = 0.05
Q x y = d i a g 25 25 30 25 25 30 ;
R x y = d i a g 30 30

4.3. Kalman Filter

We used Matlab to simulate Kalman’s noise filtering ability with random noise input signal, as shown in Figure 8.
The provided simulation imagery showcases a comparative analysis of the noise filtering capabilities of the Kalman filter applied to the dynamic states of a quadcopter: position along the x-axis (horizontal), y-axis (vertical), z-axis (altitude), and the angular orientations of pitch (tilt forward and backward), roll (tilt side to side), and yaw (rotation around the vertical axis).
Measured Data: The red lines represent the noisy measurements. This noise may originate from various sources, such as sensor inaccuracies, environmental interference, or the unstable dynamics of the quadcopter. True Data: The green lines depict the actual values of the system, unaffected by measurement noise. This represents the ‘clean’ information that we aim to estimate accurately. Kalman-filtered data: The dashed blue lines illustrate the values post-Kalman filtering. These lines are smoother and closely aligned with the true data, demonstrating the efficacy of the Kalman filter in removing noise and providing accurate estimates.
Across all graphs, the Kalman filter adjusts its estimates to closely follow the true values, even amidst significant measurement fluctuations, showcasing its resilience to noise and system dynamics. In cases of strong measurement volatility (as seen in the roll and yaw graphs), the Kalman filter maintains stability and is not overly influenced by noise, reflecting the filter’s robustness. The Kalman filter also appears to ‘ignore’ random spikes in measurement data, updating its estimates based on the consistent trends of the actual data. This imagery validates the superior noise-filtering performance of the Kalman filter when tracking the state of a quadcopter, an essential aspect in the research and development of autonomous control systems for unmanned aerial vehicles.

4.4. Results

Where there is no interference affecting the object
Considering that there is no interference, the Quadrotor moves from the original position ξ 0 = 0.3   m 0.2   m 0   m to ξ r = 0.5   m 0.5   m 0.2   m .
The results obtained from the simulation are shown in Figure 8 and Figure 9 below.
In the case of no disturbance affecting the Quadrotor system, as shown in Figure 9 and Figure 10, with the predictive controller ESSPC in the outer loop combined with the optimal controller H in the inner loop, the closed system can be tracked, and a value set with negligible overshoot and short transient time, specifically:
-
For position variables x, y, z, the transient time is 0.3 s, 0.2 s, and 0.3 s, respectively.
-
For rotation angle variables, transient time < 0.2 s.
Thus, in the absence of interference, the controller under consideration ensures that the system adheres to the set value with good quality.
-
In the case of noise affecting the object during operation.
Considering that there is no interference, the Quadrotor moves from the original position ξ 0 = 0.3   m 0.2   m 0   m to ξ r = 0.5   m 0.5   m 0.2   m
The noise is assumed as follows:
Ax = 0.1 at a time t1 = 2 s;
Ay = 0.1 at a time t2 = 4 s;
Az = 0.1 at a time t3 = 6 s.
The results obtained from the simulation are shown in Figure 10 and Figure 11 below.
The article examines the performance of an optimal H controller combined with a predictive controller for trajectory tracking of a Quadrotor UAV. On page 21, Figure 9 and Figure 10 present simulation results of the position and orientation tracking errors with the proposed controller configuration in the absence of disturbances.
Figure 10. Quadrotor angles in the absence of noise (phase angle graph [φ θ Ψ]).
Figure 10. Quadrotor angles in the absence of noise (phase angle graph [φ θ Ψ]).
Applsci 14 02414 g010
Figure 11. Position along the axes of the Quadrotor in the presence of noise (graph of position x,y,z).
Figure 11. Position along the axes of the Quadrotor in the presence of noise (graph of position x,y,z).
Applsci 14 02414 g011
The position tracking errors in Figure 9 remain within ±0.005 m for the x, y, and z axes. The peak errors are all below 0.002 m, demonstrating high-accuracy tracking of the desired 0.5 m sinusoidal trajectory. Similarly, the orientation tracking errors in Figure 10 stay within ±0.05 radians for roll, pitch, and yaw angles. This verifies that the controller can precisely follow the given 0.5 rad/s trajectory.
When noise is introduced on page 22, Figure 11 and Figure 12 show the controller response. Any noise-induced errors are attenuated rapidly, with errors decreasing to less than 0.001 m and 0.01 rad for position and orientation, respectively, within 0.2 s. This confirms the strong noise rejection of the integrated H-infinity and predictive controller structure.
To further quantify stability, no overshoot is observed in any of the response curves in Figure 9, Figure 10, Figure 11 and Figure 12. Settlement times are less than 0.2 s, indicating the controller damps the system response well without instability or oscillatory behavior.
In summary, based directly on the simulation data provided in Figure 9, Figure 10, Figure 11 and Figure 12, the proposed controller achieves errors less than 0.005 m and 0.05 rad for the test trajectory. It also rejects noise within 0.2 s, exhibits no overshot, and settles the system in under 0.2 s. This quantitatively demonstrates the controller’s high precision, robustness, and stability according to the metrics presented in the research.
Figure 12. Quadrotor phase angles in the presence of noise (phase angle graph [φ θ Ψ]).
Figure 12. Quadrotor phase angles in the presence of noise (phase angle graph [φ θ Ψ]).
Applsci 14 02414 g012
In the case of taking into account the noise acting on the Quadrotor system, with the predictive controller ESSPC in the outer loop combined with the optimal controller H in the inner loop, the closed system can follow the set value with a short transient time. At times of interference, the signals also very quickly return to the set value after a very short time (for position variables, it is 0.2 s, and for angle variables, it is 0.1 s). The overshoot, in this case, is negligible. Through this, it can be said that the controller designed on the Quadrotor system has handled the effect of noise and helped keep the set value well.
Combined with previous research [45,46], it can be observed that the proposed controller in the paper demonstrates higher performance and accuracy compared to other controllers, such as PID and LQR. This indicates its suitability when applied to unmanned aerial vehicles, with a high level of stability.

4.5. Evaluating Quadrotor Controller Robustness to Disturbances in Maritime Environments

Controller Evaluation Methodology: To evaluate robustness, simulations are run with the controller tracking a reference trajectory under different wind disturbances. Disturbances are produced by the above models configured to ISO sea states [47], generating turbulence intensities and gust scales as per Table 2.
Quantitative metrics are used to compare controller performance across sea states. These include the Integral of Time-multiplied Absolute value of Error (ITAE), Integral of Squared Error (ISE), and maximum position/attitude errors. Trends in these metrics indicate the controller’s ability to reject disturbances of increasing magnitude. The following is a simulation of the disturbance and the proposed controller when operating under the influence of the proposed disturbance (Figure 12 and Figure 13). The simulation presented was conducted with the input signal set to 1, and the parameters of the LQR controller were referenced from document [48].
The dots in Figure 13 represent the effects of signal noise, and the different colors make it easier for readers to see and read the diagram. Through the simulation presented in Figure 13, it can be observed that within the first 10 s of the simulation duration, the noise signal exerts a substantial impact, resulting in an expanded and uneven operational range position. Regarding Figure 14, it is discernible that the proposed controller achieves stability marginally sooner, albeit insignificantly, in terms of the time required to attain a steady state. However, in terms of amplitude, the control oscillations exhibit a diminished amplitude error, which is readily noticeable.
This research paper’s analysis highlights the broad applicability of advanced UAV control technology in various industries. Its precision and robustness against disturbances make it ideal for precision agriculture, enhancing crop monitoring, and pesticide application. In disaster management, its reliable data collection capabilities are crucial for effective rescue operations. The technology’s stable and precise flight patterns are essential for surveillance tasks, including border and sensitive area monitoring. In urban planning, its utility extends to high-precision mapping and infrastructure inspection, while in environmental monitoring, its ability to navigate challenging terrains is invaluable. These applications underscore the technology’s enhanced precision, stability, and reliability, demonstrating its significant potential for industries that demand high accuracy and adaptability.
In this research, computational time is not a significant concern with the model predictive control (MPC) technique despite it being a common issue in Quadrotor control methods. This can be attributed to advancements in computational power and algorithms, making MPC more efficient for real-time applications. The integration of advanced predictive algorithms possibly optimizes computation, allowing for quick response without compromising the control system’s accuracy or stability. Thus, the innovative approach effectively manages the computational demands typically associated with MPC in Quadrotor UAV control.

5. Conclusions

In conclusion, the research advances Quadrotor UAV control systems by introducing a highly sophisticated controller that harmonizes an optimal H∞ controller with an integral predictive controller, further augmented by the implementation of a Kalman filter. The control architecture is ingeniously layered, with the state–space predictive controller operating in the outer loop to maintain the set trajectory and mitigate system noise. The integral component of the predictive controller is pivotal in enhancing trajectory tracking and noise resilience, ensuring the system’s robust response to environmental disturbances.
The inner loop’s optimal H∞ controller confers additional stability to the Quadrotor, with its noise attenuation capabilities being supplemented by the integration of angular difference measurements. It is this strategic layering of control elements that allows for a comprehensive handling of noise and model errors, which is evident in the simulation results showcasing the UAV’s adherence to its set trajectory with remarkable precision.
The Kalman filter’s role is central to the system’s efficacy, serving as a dynamic estimator that continuously refines the UAV’s state predictions in the presence of process and measurement noise. This integration elevates the control system’s ability to distinguish between actual system dynamics and noise-induced data, enabling more accurate and reliable control actions.
The optimal controller H-inf combined with the integral predictive controller mentioned above is used to handle two problems: setting value and minimizing the influence of noise.
Firstly, the state–space prediction controller for translational motion is placed in the outer loop, which helps to keep the set value well; besides, to eliminate noise affecting the system, the integral of the error displacement has also been added.
Second, the optimal controller H infinitely helps to stabilize the Quadrotor in the inner loop, which also eliminates noise (with the addition of angular difference integration).
The simulation results above show that the output follows the set trajectory very well, and at the same time, it has completely eliminated the unwanted noise from the environment as well as the model error. Adding the error integral into the control calculation also contributes significantly to increasing the accuracy of the control signal calculation.
This fusion of predictive control, H∞ methodology, and Kalman filtering culminates in a robust control solution that significantly improves the precision of control signal calculations. The success of the simulations attests to the system’s capability to eliminate unwanted noise while precisely following the desired trajectory, marking a substantial enhancement in the control and stability of Quadrotor UAVs. The adoption of this comprehensive control solution is poised to propel UAV technology to new heights, particularly in applications where precision and noise mitigation are paramount.
The distributed framework, pivotal in Quadrotor UAV operations, enables a decentralized yet cohesive control architecture. This framework underpins the UAVs’ ability to autonomously make decisions, share data, and execute complex tasks in a coordinated manner. We delve into the predictive control mechanism, highlighting its crucial role in forecasting future states. By leveraging advanced algorithms, predictive control adapts to real-time changes, ensuring optimal UAV performance. H-infinity control techniques are scrutinized for their robustness in managing uncertainties and external disturbances, which is essential for maintaining UAV stability and efficiency. Lastly, the Kalman filter’s application in enhancing navigational accuracy is dissected. This filter, adept at state estimation and noise reduction, is instrumental in ensuring the UAV’s effective operation in dynamic environments.

Author Contributions

D.-A.P.: formal analysis, software, resources, data curation, writing—original draft preparation, data collected and analyzed, visualization; S.-H.H.: supervision, project administration, writing—review and editing. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the research grant of the Gyeongsang National University in 2024.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data presented in this study are available on request from the corresponding author Seung-Hun Han due to legal agreements. Please contact corresponding author via email to request the data.

Conflicts of Interest

The authors declare no conflict of interest.

Nomenclature

UAVUnmanned Aerial Vehicle
E-SSPCError model State Space Predictive Controller
MPCEnergy of a system
AIArtificial Intelligence

References

  1. Moon, J.S.; Kim, C.; Youm, Y.; Bae, J. UNI-Copter: A portable single-rotor-powered spherical unmanned aerial vehicle (UAV) with an easy-to-assemble and flexible structure. J. Mech. Sci. Technol. 2018, 32, 2289–2298. [Google Scholar] [CrossRef]
  2. Cheng, E. Aerial Photography and Videography Using Drones; Peachpit Press: Berkeley, CA, USA, 2015. [Google Scholar]
  3. Shah, T.A.; Ullah, I.; Khan, M.A.; Lorenz, P.; Innab, N. An Efficient Certificateless Forward-Secure Signature Scheme for Secure Deployments of the Internet of Things. J. Sens. Actuator Netw. 2023, 12, 10. [Google Scholar] [CrossRef]
  4. Choi, C.H.; Jang, H.J.; Lim, S.G.; Lim, H.C.; Cho, S.H.; Gaponov, I. Automatic wireless drone charging station creating essential environment for continuous drone operation. In Proceedings of the 2016 International Conference on Control, Automation and Information Sciences (ICCAIS), Ansan, Republic of Korea, 27–29 October 2016. [Google Scholar]
  5. Ganji, E.; Grenzdörffer, G.; Andert, S. Estimating the Reduction in Cover Crop Vitality Followed by Pelargonic Acid Application Using Drone Imagery. Agronomy 2023, 13, 354. [Google Scholar] [CrossRef]
  6. Li, J.; Lan, Y.; Shi, Y. Research progress on airflow characteristics and field pesticide application system of rotary-wing UAV. Trans. Chin. Soc. Agric. Eng. 2018, 34, 104–118. [Google Scholar]
  7. Pirker, D.; Fischer, T.; Lesjak, C.; Steger, C. Global and secured uav authentication system based on hardware-security. In Proceedings of the 2020 8th IEEE International Conference on Mobile Cloud Computing, Services, and Engineering (MobileCloud), Oxford, UK, 3–6 August 2020. [Google Scholar]
  8. Yang, G.; Lin, X.; Li, Y.; Cui, H.; Xu, M.; Wu, D.; Rydén, H.; Redhwan, S.B. A telecom perspective on the internet of drones: From LTE-advanced to 5G. arXiv 2018, arXiv:1803.11048. [Google Scholar]
  9. Mo, H.; Ghulam, F. Nonlinear and adaptive intelligent control techniques for quadrotor uav—A survey. Asian J. Control 2019, 21, 989–1008. [Google Scholar] [CrossRef]
  10. Ducard, G.J.J.; Allenspach, M. Review of designs and flight control techniques of hybrid and convertible VTOL UAVs. Aerosp. Sci. Technol. 2021, 118, 107035. [Google Scholar] [CrossRef]
  11. Liu, Z.; He, Y.; Yang, L.; Han, J. Control techniques of tilt rotor unmanned aerial vehicle systems: A review. Chin. J. Aeronaut. 2017, 30, 135–148. [Google Scholar] [CrossRef]
  12. Pham, D.-A.; Han, S.-H. Design of Combined Neural Network and Fuzzy Logic Controller for Marine Rescue Drone Trajectory-Tracking. J. Mar. Sci. Eng. 2022, 10, 1716. [Google Scholar] [CrossRef]
  13. Qian, L.; Liu, H.H.T. Path-Following Control of A Quadrotor UAV With A Cable-Suspended Payload Under Wind Disturbances. IEEE Trans. Ind. Electron. 2020, 67, 2021–2029. [Google Scholar] [CrossRef]
  14. Welch, G.F. Kalman filter. In Computer Vision: A Reference Guide; Springer: Boston, MA, USA, 2020; pp. 1–3. [Google Scholar]
  15. Maybeck, P.S. The Kalman filter: An introduction to concepts. In Autonomous Robot Vehicles; Springer: New York, NY, USA, 1990; pp. 194–204. [Google Scholar]
  16. Kim, K.J. Dynamic virtual work principle versus virtual power principle for systems with non-holonomic constraints. J. Mech. Sci. Technol. 2022, 36, 2239–2257. [Google Scholar] [CrossRef]
  17. Yan, J.; Wang, X.; Yu, Y. Distance-based Formation Control for Fixed-wing UAVs Subject to Positive Minimum Linear Velocity Constraints. In Proceedings of the 2022 41st Chinese Control Conference (CCC), Hefei, China, 25–27 July 2022. [Google Scholar]
  18. Nascimento, T.P.; Dórea, C.E.T.; Gonçalves, L.M.G. Nonholonomic mobile robots’ trajectory tracking model predictive control: A survey. Robotica 2018, 36, 676–696. [Google Scholar] [CrossRef]
  19. Elijah, T.; Jamisola, R.S., Jr.; Tjiparuro, Z.; Namoshe, M. A review on control and maneuvering of cooperative fixed-wing drones. Int. J. Dyn. Control 2021, 9, 1332–1349. [Google Scholar] [CrossRef]
  20. Gul, F.; Alhady, S.S.N.; Rahiman, W. A review of controller approach for autonomous guided vehicle system. Indones. J. Electr. Eng. Comput. Sci. 2020, 20, 552–562. [Google Scholar]
  21. Castillo, R.L.G.; Lospez, A.E.D.; Lozano, R.; Pégard, C. Quadrotorcraft Control; Springer: London, UK, 2013. [Google Scholar]
  22. Fantoni, I.; Lozano, R. Non-Linear Control for Underactuated Mechanical Systems; Springer: London, UK, 2002. [Google Scholar]
  23. Omar, H.M.; Mukras, S.M.S. Integrating anti-swing controller with px4 autopilot for quadrotor with suspended load. J. Mech. Sci. Technol. 2022, 36, 1511–1519. [Google Scholar] [CrossRef]
  24. Lee, C.; An, D. Reinforcement learning and neural network-based artificial intelligence control algorithm for self-balancing quadruped robot. J. Mech. Sci. Technol. 2021, 35, 307–322. [Google Scholar] [CrossRef]
  25. Castillo, P.; Lozano, R.; Dzul, A. Stabilization of a mini rotorcraft with four rotors. IEEE Control Syst. Mag. 2005, 25, 45–55. [Google Scholar]
  26. Raffo, G.V.; Ortega, M.G.; Rubio, F.R. Backstepping/nonlinear H control for path tracking of a quadrotor unmanned aerial vehicle. In Proceedings of the 2008 American Control Conference, Seattle, WA, USA, 11–13 June 2008; pp. 3356–3361. [Google Scholar]
  27. Raffo, G.V.; Ortega, M.G.; Rubio, F.R. An integral predictive/nonlinear H control structure for a quadrotor helicopter. Automatica 2010, 46, 29–39. [Google Scholar] [CrossRef]
  28. Rossiter, J.A. Model-Based Predictive Control: A Practical Approach; CRC Press: New York, NY, USA, 2003. [Google Scholar]
  29. Yang, G.-H.; Wang, J.L.; Soh, Y.C. Reliable H controller design for linear systems. Automatica 2001, 37, 717–725. [Google Scholar] [CrossRef]
  30. Van der Schaft, A. L2-Gain and Passivity Techniques in Nonlinear Control; Springer: Berlin/Heidelberg, Germany, 2000. [Google Scholar]
  31. Kühne, F.; Lages, W.F.; Mahony, R. Point stabilization of mobile robots with nonlinear model predictive control. In Proceedings of the IEEE International Conference Mechatronics and Automation, Niagara Falls, ON, Canada, 29 July–1 August 2005; Volume 3, pp. 1163–1168. [Google Scholar]
  32. van der Schaft, A. L2-gain analysis of nonlinear systems and nonlinear state feedback HI control. IEEE Trans. Autom. Control. 1992, 37, 770–784. [Google Scholar] [CrossRef]
  33. Beng, W.F.; Postlethwaite, I. Robust non-linnear H∞/adaptive control of robot manipulator motion. Sage J. 1994, 208. [Google Scholar] [CrossRef]
  34. Ortega, M.G.; Vargas, M.; Vivas, C.; Rubio, F.R. Robustness Improvement of a Non-linear H Controller for Robot Manipulatiors via Saturation Function. J. Robot. Syst. 2005, 22, 421–437. [Google Scholar] [CrossRef]
  35. Camacho, E.; Bordons, C. Model Predictive Control; Springer: New York, NY, USA, 1998. [Google Scholar]
  36. Olfati-Saber, R. Nonlinear Control of Underactuated Mechanical Systems with Application to Robotics and Aerospace Vehicles. Ph.D. Thesis, Massachusetts Institute of Technology, Cambridge, MA, USA, 2001. [Google Scholar]
  37. Ezequiel, C.A.F.; Cua, M.; Libatique, N.C.; Tangonan, G.L.; Alampay, R.; Labuguen, R.T.; Favila, C.M.; Honrado, J.L.E.; Caños, V.; Devaney, C.; et al. UAV aerial imaging applications for post-disaster assessment, environmental management and infrastructure development. In Proceedings of the 2014 International Conference on Unmanned Aircraft Systems (ICUAS), Orlando, FL, USA, 27–30 May 2014. [Google Scholar]
  38. Huang, T.; Huang, D.; Wang, Z.; Shah, A. Robust tracking control of a quadrotor UAV based on adaptive sliding mode controller. Complexity 2019, 2019, 7931632. [Google Scholar] [CrossRef]
  39. Mann, J. The spatial structure of neutral atmospheric surface-layer turbulence. J. Fluid Mech. 1994, 273, 141–168. [Google Scholar] [CrossRef]
  40. Kolmogorov, A.N. The local structure of turbulence in incompressible viscous fluid for very large Reynolds’ Numbers. Dokl. Akad. Nauk SSSR 1941, 30, 301. [Google Scholar]
  41. Bhumralkar, C.M. Parameterization of the planetary boundary layer in atmospheric general circulation models. Rev. Geophys. 1976, 14, 215–226. [Google Scholar] [CrossRef]
  42. Isaac, O.; Atkins, E.M. Qualitative failure analysis for a small quadrotor unmanned aircraft system. In Proceedings of the AIAA Guidance, Navigation, and Control (GNC) Conference, Boston, MA, USA, 19–22 August 2013. [Google Scholar]
  43. Fakharzadeh J., A. Finding the optimum domain of a nonlinear wave optimal control system by measures. J. Appl. Math. Comput. 2003, 13, 183–194. [Google Scholar] [CrossRef]
  44. Ujević, N. Error inequalities for an optimal quadrature formula. J. Appl. Math. Comput. 2007, 24, 65–79. [Google Scholar] [CrossRef]
  45. 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]
  46. Massé, C.; Gougeon, O.; Nguyen, D.-T.; Saussié, D. Modeling and control of a quadcopter flying in a wind field: A comparison between LQR and structured H control techniques. In Proceedings of the 2018 International Conference on Unmanned Aircraft Systems (ICUAS), Dallas, TX, USA, 12–15 June 2018. [Google Scholar]
  47. Walt, M.; Butterfield, S. Future for Offshore Wind Energy in the United States; No. NREL/CP-500-36313; National Renewable Energy Lab.: Golden, CO, USA, 2004. [Google Scholar]
  48. Kiernozek, J.M. Controlling a Drone Using the LQR Method; Instytut Techniki Lotniczej i Mechaniki Stosowanej: Warsaw, Poland, 2023. [Google Scholar]
Figure 1. Quadrotor’s structure and operation.
Figure 1. Quadrotor’s structure and operation.
Applsci 14 02414 g001
Figure 2. The corresponding torque controls the angles (a) yaw, (b) pitch, and (c) roll.
Figure 2. The corresponding torque controls the angles (a) yaw, (b) pitch, and (c) roll.
Applsci 14 02414 g002
Figure 3. Diagram of Quadrotor.
Figure 3. Diagram of Quadrotor.
Applsci 14 02414 g003
Figure 4. The control structure of the Quadrotor.
Figure 4. The control structure of the Quadrotor.
Applsci 14 02414 g004
Figure 7. Control structure in Simulink.
Figure 7. Control structure in Simulink.
Applsci 14 02414 g007
Figure 8. Comparison of measured, true, and Kalman-filtered states.
Figure 8. Comparison of measured, true, and Kalman-filtered states.
Applsci 14 02414 g008
Figure 9. Position along the axes of the Quadrotor in the absence of noise (graph of position x,y,z).
Figure 9. Position along the axes of the Quadrotor in the absence of noise (graph of position x,y,z).
Applsci 14 02414 g009
Figure 13. Simulation of the impact of interference for a simulation time of 10 s in high wind conditions.
Figure 13. Simulation of the impact of interference for a simulation time of 10 s in high wind conditions.
Applsci 14 02414 g013
Figure 14. Comparison of the control of velocities of two LQR controllers and proposed controllers. (a) Control signal (x); (b) control signal (y); (c) control signal (z); (d) control signal (phi); (e) control signal (theta); (f) control signal (psi).
Figure 14. Comparison of the control of velocities of two LQR controllers and proposed controllers. (a) Control signal (x); (b) control signal (y); (c) control signal (z); (d) control signal (phi); (e) control signal (theta); (f) control signal (psi).
Applsci 14 02414 g014
Table 1. The parameters of the Quadrotor used in the simulation.
Table 1. The parameters of the Quadrotor used in the simulation.
ParametersValueUnit
Mass (m)1.74kg
Length from wing to center (l)0.21m
Second-level heading9.81m/s2
Ixx0.004kgm2
Iyy0.004kgm2
Izz0.0084kgm2
Table 2. Simulated sea states and disturbance parameters.
Table 2. Simulated sea states and disturbance parameters.
Sea StateTurbulence Intensity (%)Gust Scales (m/s)
Calm5±1
Moderate10±2
Rough15±3
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

Pham, D.-A.; Han, S.-H. Critically Leveraging Theory for Optimal Control of Quadrotor Unmanned Aircraft Systems. Appl. Sci. 2024, 14, 2414. https://doi.org/10.3390/app14062414

AMA Style

Pham D-A, Han S-H. Critically Leveraging Theory for Optimal Control of Quadrotor Unmanned Aircraft Systems. Applied Sciences. 2024; 14(6):2414. https://doi.org/10.3390/app14062414

Chicago/Turabian Style

Pham, Duc-Anh, and Seung-Hun Han. 2024. "Critically Leveraging Theory for Optimal Control of Quadrotor Unmanned Aircraft Systems" Applied Sciences 14, no. 6: 2414. https://doi.org/10.3390/app14062414

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