Next Article in Journal
Atmospheric Aircraft Conceptual Design Based on Multidisciplinary Optimization with Differential Evolution Algorithm and Neural Networks
Previous Article in Journal
A General Method for Pre-Flight Preparation in Data Collection for Unmanned Aerial Vehicle-Based Bridge Inspection
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Improved Nonlinear Model Predictive Control Based Fast Trajectory Tracking for a Quadrotor Unmanned Aerial Vehicle

1
Institute of Logistics Science and Engineering, Shanghai Maritime University, Shanghai 201306, China
2
Beijing Institute of Spacecraft System Engineering, Beijing 100194, China
*
Author to whom correspondence should be addressed.
Drones 2024, 8(8), 387; https://doi.org/10.3390/drones8080387
Submission received: 26 June 2024 / Revised: 6 August 2024 / Accepted: 7 August 2024 / Published: 9 August 2024

Abstract

:
This article studies a nonlinear model predictive control (NMPC) scheme for the trajectory tracking efficiency of a quadcopter UAV. A cost function is first proposed that incorporates weighted increments of control forces in each direction, followed by a weighted summation. Furthermore, a contraction constraint for the cost function is introduced based on the numerical convergence of the system for the sampling period of the UAV control force. Then, an NMPC scheme based on improved continuous/generalized minimum residuals (C/GMRES) is proposed to obtain acceptable control performance and reduce computational complexity. The proposed control scheme achieves efficient and smooth tracking control of the UAV while guaranteeing the closed-loop stability of the system. Finally, simulation results are presented to illustrate the effectiveness and superior performance of the proposed NMPC control scheme.

1. Introduction

Recently, unmanned aerial vehicles (UAVs) have aroused great interest and attention in civilian fields, including aerial photography, cargo transportation, and rescue missions [1,2,3,4]. Many studies have been conducted to explore the motion control of UAVs. The trajectory tracking problem of UAVs is one of the typical motion control problems. In particular, a UAV is a 6-degree of freedom, nonlinear, underdriven, strongly coupled system. Hence, the design of a stable and efficient trajectory-tracking controller holds high practical significance [5].
As is well known, PID controllers remain a widely utilized class of algorithms. Gao et al. [6] used cascaded PID control with a Kalman filter to remove noise. However, parameter tuning often needs more comprehensive theoretical guidance and is time-consuming. Robust control can address parameter uncertainty [7,8]. Although it effectively suppresses external disturbances during the control process, its exclusive focus on worst-case scenarios may diminish overall control performance. Sliding mode control exhibits reduced dependency on parameters and demonstrates rapid responsiveness, as the state trajectory swiftly reaches and then remains on the sliding surface in finite time [9]. Li et al. [10] designed a finite-time extended state observer based on terminal sliding mode to estimate and compensate for system faults or uncertainties in the aggregate system. Reference [11] designed a new sliding mode observer based on specified fixed-time sliding mode variables and adaptive techniques to estimate external disturbances within a specified stable time. Huang et al. [12] proposed a non-singular terminal sliding mode control method to address errors and external disturbances in UAV modeling. Using disturbance observers, they effectively mitigated vibration issues commonly associated with sliding mode control. Although these algorithms can achieve optimal control strategies [13], the challenge lies in their computational burden, making it difficult to design and implement. Model predictive control (MPC) is an optimal feedback control technology. MPC can iteratively compute optimal control inputs using a rolling optimization strategy, while also satisfying nonlinear/linear constraints on system states and control increments of UAVs.
References [14,15,16,17] conducted research on MPC in the context of trajectory tracking. Wei et al. [18] developed a distributed MPC using Lyapunov theory, which allowed an autonomous underwater vehicle to maintain a desired formation and track a reference trajectory, even in the presence of external disturbances. Mohammadi et al. [19] utilized linear MPC to track the trajectory of the UAV on a ground platform, which was a straight line, and the direction of the UAV remained essentially constant. However, the limitations of linear MPC become apparent when the tracked trajectory deviates from a straight line. Vlanis et al. [20] designed an NMPC controller that considers real-time constraints, including the UAV’s flight capability and collision avoidance requirements. The controller solves the constraint optimization problem online, ensuring the UAV operates effectively and safely. Pedro et al. [21] proposed a multi-model solution-based for altitude and yaw control of a quadrotor transporting an unknown constant load. Yan et al. [22] developed a multi-constraint MPC control strategy by integrating a Kalman-consistent filter with a fixed-time perturbation observer. This integration aims to enhance the applicability and robustness of the control algorithm in complex environments and improve computational efficiency. Zhang et al. [23] proposed a self-triggered adaptive MPC approach for constrained discrete-time nonlinear systems, effectively addressing challenges related to parameter uncertainties and additive disturbances. Said et al. [24] designed two optimal controllers based on linear quadratic Gaussian and MPC algorithms for a quadrotor, enabling it to autonomously track a moving platform from any initial position and achieve precise landings. Wu et al. [25] proposed a synthesis method for generating collision avoidance trajectories by categorizing trajectory planning into macro-planning and micro-planning and using model prediction to control the final arrival at the specified position within the target area.
The above analysis needs to consider improving computational efficiency and accuracy within the constraints of actual physical conditions. It also needs to address the extensive number of iterations required to solve the optimization problem. The continuous/generalized minimum residuals (C/GMRES) algorithm computes optimal parameter estimates by minimizing the residual norm. It continuously updates parameter estimates and adjusts them to minimize residuals, thereby achieving a better fit to the data [26]. However, due to its inability to handle inequality constraints, C/GMRES cannot be used in isolation. Toshiyuki [27] proposed a program based on the standard C/GMRES algorithm for automatically generating numerical solutions. Shen et al. [28] introduced a modified C/GMRES (mC/GMRES) that uses initial values based on a logarithmic barrier function, facilitating rapid convergence to the optimum. Nonetheless, this approach did not consider terminal state constraints. Wang et al. [29] incorporated a penalty term into the cost function while considering the initial optimum and analyzing its convergence and stability. However, their model was specific to certain instances and lacked applicability in practical scenarios. To address these limitations, we propose an improved NMPC solution.
(1)
Considering the actual quadrotor model, we propose an improved NMPC control scheme to achieve more precise and rapid position tracking. This improvement aims to enhance the generality and applicability control.
(2)
Compared with mC/GMRES in [28], this study enhances control stability and computational efficiency in NMPC by incorporating a weighted sum of control increments into the cost function to solve the new optimization problem.
(3)
The Lyapunov-based shrinkage constraints are added according to the optimal solution, and the set of two stabilization domains is found to ensure numerical convergence and trajectory stability throughout the entire simulation process.

2. System Description

The design of a quadrotor UAV involves both position and attitude control. The structure of the quadrotor is illustrated in Figure 1. The origin O b is the center of the quadrotor UAV. The roll and pitch angles ( ϕ , θ ) are coupled to the global position ( x , y ) . To move in the x e or y e direction, it is usually necessary to adjust the pitch or roll angle ( θ , ϕ ) , while the yaw angle ( ψ ) changes the direction of the UAV’s travel. Additionally, let X = x , y , z T represent the center of position of the quadrotor.
The quadrotor UAV dynamics model is established as follows [13]:
m X ¨ + m g e 3 = R ( Θ ) U
J Θ Θ ¨ + C Θ , Θ ˙ Θ ˙ = τ
with
R Θ = C ψ C θ C ψ S θ S ϕ S ψ C ϕ C ψ S θ C ϕ + S ψ S ϕ S ψ C θ S ψ S θ S ϕ + C ψ C ϕ S ψ S θ C ϕ C ψ S ϕ S θ C θ S ϕ C θ C ϕ
where e 3 = 0 , 0 , 1 T ; m is the mass of the quadrotor UAV; g is the gravitational constant; U = 0 , 0 , f T is the total thrust vector; τ R 3 is the moment input by the attitude system. S · is the sine function sin ( · ) and C · is the cosine function cos ( · ) . The positive definite diagonal matrix I = diag [ I 11 , I 22 , I 33 ) . The symmetry matrix J Θ R 3 × 3 and matrix C Θ , Θ ˙ R 3 × 3 are given by
J Θ = I 11 0 I 11 S θ 0 I 22 C 2 ϕ + I 33 S 2 ϕ I 22 I 33 C ϕ S ϕ C θ I 11 S θ I 22 I 33 C ϕ S ϕ C θ I 11 S 2 θ + I 22 S 2 ϕ C 2 θ + I 33 C 2 ϕ C 2 θ
C Θ , Θ ˙ = c 11 c 12 c 13 c 21 c 22 c 23 c 31 c 32 c 33
with
c 11 = 0 , c 12 = I 22 I 33 θ ˙ C ϕ S ϕ + ψ ˙ S 2 ϕ C θ ψ ˙ C 2 ϕ C θ I 11 ψ ˙ C θ , c 13 = I 22 I 33 ψ ˙ C ϕ S ϕ C 2 θ , c 21 = I 33 I 22 θ ˙ C ϕ S ϕ + ψ ˙ S 2 ϕ C θ ψ ˙ C 2 ϕ C θ + I 11 ψ ˙ C θ , c 22 = I 33 I 22 ϕ C ϕ S ϕ , c 23 = I 11 ψ ˙ S θ C θ + I 22 ψ ˙ S 2 ϕ C θ S θ + I 33 ψ ˙ C 2 ϕ S θ C θ , c 31 = I 33 I 22 ψ ˙ C ϕ S ϕ S θ I 11 θ ˙ C θ , c 32 = I 33 I 22 ψ ˙ C ϕ S ϕ S θ ϕ ˙ S 2 ϕ C θ ϕ ˙ C 2 ϕ C θ + I 11 ψ ˙ S θ C θ = I 22 ψ ˙ S 2 ϕ C θ S θ I 33 ψ ˙ C ϕ S θ C θ , c 33 = I 33 I 22 ϕ C ϕ S ϕ C 2 θ I 22 θ ˙ S 2 ϕ C θ S θ I 33 θ ˙ C 2 ϕ S θ C θ = + I 11 θ ˙ S θ C θ .
This paper addresses the trajectory tracking problem for UAVs using NMPC with the dynamic model of the UAV described above. To ensure the UAV’s control smoothness requirements, control increments are weighted in the cost function. Thus, Δ u = u i u i 1 0 ( i = 1 , 2 , 3 , ) is reached when t . The C/GMRES method is employed to reduce the computational burden of NMPC. The barrier methods are used to transform the original optimization problem into an unconstrained one. Additionally, the algorithm’s attraction domain intersects with a Lyapunov-based control method to ensure the system’s closed-loop stability. The system is divided into inner-loop and outer-loop control, as shown in Figure 2. The outer-loop position controller uses the improved C/GMRES method to efficiently solve the nonlinear optimization problem, allowing for real-time adjustment of the system’s position and ensuring accurate trajectory tracking. The inner-loop attitude controller uses a PID control strategy to quickly adjust the attitude and stabilize the system’s flight state.

3. Trajectory Tracking Controller Design

3.1. Brief Description of NMPC Controller

Assuming that the reference trajectory is appropriate and does not violate the physical limits of the UAV [30]. We consider both the UAV’s force constraints and the constraints on the rate of change simultaneously. The cost function is constructed based on the UAV’s position dynamics model as follows:
min u ^ · t t + T x ˜ ^ s Q 2 + u ^ s R 2 d s + x ˜ ^ t + T P 2 s . t . x ^ ˙ s = f x ^ s , u ^ s , s t , t + T x ^ t = x t , u ^ t = u t u ^ s u max , s t , t + T
where T is the prediction horizon; x ^ ( s ) represents the current state; x r ( s ) represents the reference state; u ^ ( t ) represents the control sequence; x ˜ ^ s = x ^ s x r s represents the error in predicted tracking; u max and Δ u max denote the maximum magnitudes of control input and control variations, respectively; Q , R , S are positive definite weighting matrices. x ˜ ^ ( s ) Q 2 = x ˜ ^ T ( s ) Q x ˜ ^ ( s ) , u ^ ( s ) R 2 = u ^ T ( s ) R u ^ ( s ) and x ˜ ^ ( t + T ) P 2 = x ˜ ^ ( t + T ) T P x ˜ ^ ( t + T ) .
The C/GMRES-based method is computed and implemented using a discrete-time formulation but remains based on continuous time t. Therefore, the discretization problem must be addressed at each continuous time t, ensuring the stability and accuracy of the discretization process. Assuming a prediction interval of N steps, the step size is δ = T / N , which is referred to as the sampling period. The discretization of the above equation is as follows:
P 1 ( x ) : min u ^ i J = i = 0 N 1 x ˜ i Q 2 + u ^ i R 2 δ + x ˜ N P 2 s . t . x ^ ˙ s = f x ^ s , u ^ s , s t , t + T x ^ t = x t , u ^ t = u t u ^ s u max , s t , t + T
with the guarantee that the system is differentiable and the constraints hold, the Karush–Kuhn–Tucker (KKT) condition [31] provides a first-order necessary condition for the optimal solution U * of the optimization problem P 1 ( x ) . Sequential quadratic programming and the interior point method can be used to solve the KKT condition for P 1 ( x ) . However, these methods rely on continuous linearization. To address this, the C/GMRES numerical algorithm will be used to speed up the numerical computation of NMPC, considering both the onboard computational burden and computational efficiency. The standard C/GMRES can only solve optimization problems with equality constraints. Then, we relax this restriction and propose an improved strategy to compute the optimal solution under the inequality constraints, which leads to a smoother and globally stabilized control process.

3.2. Improved Efficient NMPC

This section introduces a smoothing constraint on the control increment and a contraction constraint to improve the smoothness of the control process and ensure global convergence. Finally, an efficient NMPC algorithm is proposed to ensure that the solution obtained during the optimization process satisfies the conditions and constraints.

3.2.1. Smoothness Constraint Term for Control Increments

The rate of change of the control input must be considered in the actual control process. Otherwise, excessive changes in the control strategy can lead to violent system oscillations. In addition, the optimization algorithm might produce significant control input variations between successive steps, which could result in an unstable system response.
Firstly, the control sequence is defined as u ^ i * i = 0 N , where u i is the ith control input component at the current time step, and u i 1 is the corresponding control input component at the previous time step. The sum of squares of control increments is introduced to address potential numerical instability in the search for an optimal solution to an optimization problem. When the control inputs change significantly between time steps, the penalty function penalizes these changes. This function finds a solution that satisfies the constraints during the optimization process. As a result, the final solution meets the requirements. The constraint with the penalty term is then defined as follows:
ϑ u ^ i = ρ · i = 1 N Δ u ^ i 2
where Δ u ^ i = u ^ i * u ^ i 1 * , and the penalty factor ρ is introduced to emphasize the impact of ϑ u ^ i . A larger value of ρ causes ϑ u ^ i to Δ u ^ i more significantly, while a smaller ρ reduces this penalty. The parameter ρ is introduced to balance the attainment of an optimal solution with the satisfaction of constraints, thereby preventing the imposition of excessively stringent conditions. To facilitate the optimization process, it is typically necessary to fine-tune the value of ρ , ensuring a more effective and efficient solution. The modified optimal control problem (OCP) ( P 2 ( x ) ) , with the penalty term incorporated into the cost function, can be formulated as follows:
P 2 ( x ) : min u ^ i J = i = 0 N 1 x ˜ ^ i Q 2 + u ^ i R 2 + ε · ϑ u ^ i δ + x ˜ ^ N P 2 s . t . x ^ i + 1 = f x ^ i , u ^ i + x ^ i x ^ 0 = x t u ^ s u max , s t , t + T
where ϑ u ^ i represents a soft constraint on the control input Δ u ^ i . It can moderately violate the constraints in the optimization process, making it more flexible. Especially when the constraints are difficult to handle, a feasible solution can be obtained by appropriately adjusting the strength of the penalty term, thus adapting to the different needs of the problem. The impact of different parameter values ε in (10) on numerical convergence should be discussed. Utilizing the C/GMRES method for approximate computation of solutions in P 2 ( x ) , the following assumptions and lemmas are made within the context of practical applications:
Assumption 1 
([32]). For each ε = ε d > 0 , there exists a bounded solution U n .
The C/GMRES method is based on the conditions required for solving Pontryagin’s Maximum Principle (PMP) to attain the optimal solution for P 2 ( x ) , rather than the KKT conditions. Therefore, the sufficiency of PMP for addressing the KKT conditions is explored first.
Lemma 1 
([28]). A point satisfies the PMP condition of P 2 ( x ) , sufficiently solving its KKT conditions.
Proof. 
The proof of Lemma 1 is presented in Appendix A.1. □
Lemma 2. 
Assume Assumption 1 holds, and 0 < ε n + 1 < ε n is a solution to P 2 ( x ) with optimal solutions U ¯ n + 1 and U ¯ n . Then, the following inequalities can hold as follows:
J ¯ U ¯ n + 1 , ε n + 1 J ¯ U ¯ n , ε n
J ¯ U ¯ n + 1 J ¯ U ¯ n , ϑ U ¯ n ϑ U ¯ n + 1
Proof. 
The proof of Lemma 2 is presented in Appendix A.2. □
Lemma 3 
([29]). ε n n = 1 N is a decreasing sequence satisfying 0 < ε n + 1 < ε n , and when n + , there exists ε n sufficiently small. Based on Assumption 1, U n converges to U * .
Lemma 4 
([29]). Consider Lemmas 1 and 3. P 2 ( x ) is the optimal solution. Then, the above approximately solves P 1 ( x ) with a sufficiently little ε in P 2 ( x ) .

3.2.2. C/GMRES Algorithm

For P 2 ( x ) , the Hamiltonian function is defined as follows:
H x , u , κ = x x r Q 2 + u R 2 + ϑ u , u max + κ T f x , u
where κ represents the costate [28], and u ^ i * i = 0 N 1 is the global optimal solution to P 2 ( x ) . The costate sequence κ i i = 1 N satisfies x ^ i + 1 = f x ^ i , u ^ i + x ^ i and x ^ 0 = x t , and the following conditions:
x ^ i + 1 = x i + f x i , u i δ
κ N = x ˜ N P 2 x
κ i = κ i + 1 + H x x ^ i , u ^ i * , κ i + 1 , ε δ
H u x ^ i , u ^ i * , κ i + 1 , ε = 0
Equations (11) and (13) represent recursive relationships, while x ^ 0 = x t and (12) serve as boundary conditions. H x and H u are the partial derivatives of the Jacobian matrix H with respect to x and u , respectively. The sequence u ^ i * i = 1 N 1 is determined by (14). Starting from x ^ 0 = x t and iterating through (11), Equations (12) and (13) are processed in reverse order of time. The state sequence x ^ i i = 0 N 1 and the costate sequence κ i i = 1 N are explicit functions of U ˙ * . We then substitute these into (14) to construct the system of equations:
F U ˙ * , x , ε = H u x ^ 0 , u ^ * 0 , κ 1 , ε H u x ^ 1 , u ^ * 1 , κ 2 , ε H u x ^ 2 , u ^ * 2 , κ 3 , ε H u x ^ N 1 , u ^ * N 1 , κ N , ε
To solve (15) at time t, standard approaches involve computing the Jacobian matrix, Hessian matrix, and their inverses using iterative methods. However, this process is computationally expensive and time-consuming. Instead, numerical continuum methods and forward difference generalized minimum residuals (FDGMRES) avoid the need to compute matrix inverses. The FDGMRES method, which combines forward difference approximation combined with GMRES, is described as follows:
U ^ ˙ = FDGMRES U ^ , x , x ˙ , U ^ ˙ ˜ , k max , ε
where x ˙ is approximated as x ˙ t = x t + δ x t / δ ; k max represents the maximum number of iterations; U ^ ˙ ˜ is the initial feasible value; U ^ is a feasible initial control input sequence [27]. ( P 2 ( x ) ) can be solved efficiently by applying C/GMRES. Algorithm 1 summarizes the FDGMRES algorithm for solving U ˙ * :
Algorithm 1: FDGMRES algorithm for U ˙ *
1. Initialize  t = 0 , l = 0 , x 0 = x ( 0 ) , n = n + 1 ;
2. Get  U ^ ˙ ˜ by F U ^ 0 , x t 0 , 0 = 0 ;
3. Get F from (14) and partial derivative F d ;
4. b = A F ( 1 / h ) F , r ^ = b F d U * , x + h x ˙ , U ^ ˙ ˜ , zeros ( n X , 1 ) , v 1 = r ^ / r ^ ;
5. while  k < k m a x  do
6.     get x k + 1 = x t + δ and x ˙ k = ( x k + 1 x k ) / δ ;
7.     v k + 1 = F d U * , x + h x ˙ , v k ( n U , N ) , zeros ( n X , 1 ) ;
8.     For  j = 1 : 1 : k
9.        h j , k = v k T v k ;
10.        v k + 1 = v k + 1 h j , k v k ;
11.    End for
12.     h k + 1 , k = v k + 1 ; v k + 1 = v k + 1 / v k + 1 ; e = [ 1 , zeros ( k , 1 ) ] ;
13.     h ^ k = h k ( 1 : k + 1 , 1 : k ) ; m k = ( h ^ k ) 1 r ^ e ; ρ = r ^ e h ^ k m k ;
14.    If  ρ < tol
15.       break;
16.    End if
17. End While
18. U ˙ * = U ^ ˙ * + v k m k ;
19. t = t + δ , k = k + 1 .

3.2.3. Adding Stability Constraints

Nonetheless, while it is possible to achieve the global optimal solution, the closed-loop stability of the system cannot be assured due to the limited prediction horizon. Therefore, the following solution is needed. Suppose there is a feedback control rule u ( t ) = ζ ( x ( t ) ) , which in some stable region ensures that the control input u satisfies a particular constraint and makes the system asymptotically stable at the origin. According to the inverse Lyapunov theorem [33], this means that we can find some specific type of function γ i ( · ) ( i = 1 , 2 , 3 , 4 ) and a continuously differentiable Lyapunov function V ( x ) such that the system satisfies certain inequalities, thus proving its stability. γ 1 x V ( x ) γ 2 x , V x f ( x , ζ ( x ) ) γ 3 x , V ( x ) x γ 4 x . For all x O R n , where O is an open neighborhood of the origin, we denote the region Ω O O as the stability region of the closed-loop system under control u = ζ ( x ) [34].
Since the system uses only the first column of the control sequence U * obtained from the prediction sequence [ t , t + δ ] , only the first prediction interval is considered.
P 3 ( x ) : min u ^ i J = i = 0 N 1 x ˜ ^ i Q 2 + u ^ i R 2 + ε · ϑ u ^ i δ + x ˜ ^ N P 2 s . t . x ^ i + 1 = f x ^ i , u ^ i + x ^ i x ^ 0 = x t u ^ s u max , s t , t + T V x f x t , u t V x f x ^ t , ζ ( x ^ ( t ) )
where V · is the Lyapunov function and designed in Section 3.2.4; ζ · is the auxiliary control law based on the Lyapunov function. When t [ t , t + δ ) , the optimal solution of the optimization problem is U * . The constraints V x f x t , u t V x f x ^ t , ζ ( x ^ ( t ) ) ensure that the time derivative V ( x ) of the Lyapunov function at time t is less than or equal to the value of the nonlinear control law u = ζ ( x ) . This holds when the control law is applied in a sample-and-hold fashion within a closed-loop system. Using the state measurements obtained at each synchronized sampling time, it can be demonstrated that the control law designed in this paper inherits the stability and robustness of the Lyapunov-based control law ζ ( x ) . This is true provided that system data loss is not considered [35]. One of the main properties of stability constraints is that they have the same stability domain as the nonlinear control law ζ ( x ) . That means the system is stable when the sampling time and the upper limit of perturbation are small enough [36,37]. In P 3 ( x ) , without compromising the stability of the tracking control, a component that adaptively adjusts the prediction horizon is added to P 2 ( x ) , which reduces the inconvenience caused by adjusting the parameters. Meanwhile, the adaptive adjustment of the prediction horizon can reduce the optimization scale of the NMPC.

3.2.4. Lyapunov-Based Auxiliary Control Law Design

The Lyapunov-based control method is widely used in nonlinear UAV systems, as it can demonstrate the global stability of the entire system [36]. Therefore, the fixed-time integral sliding mode control method can be adopted to construct ζ ( x ) . According to [38,39], for system x ˙ t = f x , u , if there exists a Lyapunov function on its domain that satisfies V ˙ x a V x α b V x β . Here, a , b > 0 and 0 < β < 1 < α . Furthermore, the system is globally fixed-time stable, and the stability time is T 1 a ( α 1 ) + 1 b ( β 1 ) .
The position loop system can be written as X ˙ 1 = X 2 = U m g e 3 , where X 2 = [ x ˙ , y ˙ , z ˙ ] T . Then, design a virtual controller [40]: u n o m = k 1 sig p 1 ( X 1 ) k 1 sig q 1 ( X 1 ) k 2 sig p 2 ( X 2 ) k 2 sig q 2 ( X 2 ) . Choose k 1 , k 2 to ensure that the second-order polynomial λ 2 + k 2 λ + k 1 is Hurwitz. And 0 < p 1 < 1 , q 1 = 2 p 1 / ( 1 + p 1 ) , p 2 > 1 , q 2 = 2 p 2 / ( 1 + p 2 ) .
For the error system X ˙ 2 X ¨ 2 r = X ˙ 2 e = ζ m g e 3 X ¨ 2 r , where X 2 r = [ x d , y d , z d ] T and X ¨ 2 r = [ x ¨ d , y ¨ d , z ¨ d ] T . Its Lyapunov candidate function satisfies λ 1 x e 2 V ( x ) λ 2 x e 2 , where λ 1 , λ 2 R . Select the sliding surface as follows:
s = X 2 e X 2 r ( 0 ) + 0 t u n o m m + g e 3 d t
then, taking its derivative yields
s ˙ = X ˙ 2 e u n o m m + g e 3 = ζ m + u n o m m
Theorem 1. 
Considering the dynamic error system X ˙ 2 e = ζ m g e 3 X ¨ 2 r , and selecting surface (18) as the sliding surface, the controller can be designed as follows:
ζ = γ 1 sig b c ( s ) γ 2 sig n m ( s ) + u n o m
where  γ 1 , γ 2  is a positive number and  b < c , n > m  are all positive odd integers, then there exists a fixed time T such that the system converges for  t > T .
Proof. 
The proof of Theorem 1 is presented in Appendix A.3. □
Remark 1. 
According to V x f x t , u t V x f x ^ t , ζ ( x ^ ( t ) ) , after obtaining the virtual control law based on Lyapunov, the intersection of the stability domains of the control law obtained from P 2 ( x ) can be obtained. The final solution obtained at last is also the solution obtained from P 3 ( x ) . The improved NMPC controller in this paper can inherit the stability and robustness of ζ ( x ) [34].
Remark 2. 
Firstly, we use the control force U and the desired ψ d obtained from the previous step to calculate the expected values ϕ d and θ d for the angle. Secondly, we establish the desired values for the required roll and pitch angles, where ϕ d = arcsin U a 1 S ψ d U a 2 C ψ d U a and θ d = arctan U a 1 C ψ d + U a 2 S ψ d U a 3 . In the case of U a = U a 1 , U a 2 , U a 3 T = 1 m U , the obtained expected values of the attitude angles serve as inputs to the attitude controller. Therefore, the attitude controller is designed as τ i = K P i e i + K I i 0 t e i d t + K D i d e i d t , where i { ϕ , θ , ψ } , e i represents the desired value of the angle minus the current value.

3.3. Algorithm Structure

In summary, the controller for the position loop increases the system’s rapidity without compromising the stability of the system’s tracking control. Then, the desired three angle values are obtained by attitude decoupling, and the design of the PID controller for the attitude loop is carried out. The control framework can be seen as follows: Firstly, the desired trajectory ( X , Y , Z ) is predefined and the fundamental cost function of the NMPC is formulated based on the established error model. This cost function comprises the error term, control term, and terminal error. A weighted sum of control increments is incorporated into the cost function to enhance control smoothness. Subsequently, the NMPC problem is solved using the C/GMRES method. A stability constraint is introduced to ensure that the stability region of the entire system is confined within the stability domain derived from Lyapunov’s method. Finally, the resulting control forces are decoupled to determine the desired angles for the PID control. This iterative process is repeated until the trajectory tracking is completed. Algorithm 2 covers the entire process:
Algorithm 2: Efficient-NMPC algorithm for UAV trajectory
1. Initialize  k m a x = 0 , t p r e v = 0 , x 0 = x ( 0 ) , U 0 = u ( 0 ) , N m i n , N m a x , Δ N ;
2. While  k < k m a x  do
3. k = k + 1 ; find U ^ ˙ ˜ by F U ^ 0 , x t 0 , 0 = 0 ;
4. End while;
5. While  t < t e n d  do
6.     x k + 1 = x t + δ and Δ x k = x k + 1 x k ;
7.     U ˙ * = FDGMRES U ^ , x , x / δ , t , U ^ ˙ ˜ , k max , ρ , ε ;
8.     U * = U ^ + U ˙ * δ ;
9.     If  V x f x t , u t V x f x ^ t , ζ ( x ^ ( t ) )
10.        U = U * ; Else  U = ζ ;
11.    End If
12.    Decoupling angel ϕ d = arcsin U a 1 S ψ d U a 2 C ψ d U a , θ d = arctan U a 1 C ψ d + U a 2 S ψ d U a 3 ;
13.    Attitude controller τ i = K P i e i + K I i 0 t e i d t + K D i d e i d t ;
14. End While

4. Simulation

4.1. Parameter Selection

In the simulation process, the mass of the quadrotor is 1.12 kg . Inertia moments are I 11 = 0.01   kg · m 2 , I 22 = 0.0082   kg · m 2 , I 33 = 0.0148   kg · m 2 . The initial position is set as X 0 = [ 0.1 ;   0.01 ;   0.01 ] . The system’s sampling period is t = 0.1 s. The desired trajectory is set as X d = [ 0.5 sin ( 0.3 t ) ; 0.3 sin ( 0.6 t ) ; 0.4 ] . These trajectories are typical tracking control test trajectories with different reference tangential velocities and angular velocities, which pose a challenge to the tracking task. We can choose the following main parameters for the fixed-time integral sliding mode controller γ 1 = 0.02 , γ 2 = 0.02 , b = 3 , c = 2 , n = 4 , m = 3 . Since the initial solution of the FDGMRES function at the previous sampling time is often reasonable, the system can converge when the maximum number of iterations k m a x is reached. The weighting matrices R = diag ( [ 1 , 1 , 1 ] ) , Q = diag ( [ 100 , 100 , 320 , 300 , 340 , 160 ] ) and P = diag ( [ 110 , 130 , 100 , 300 , 80 , 40 ] ) . The coefficient is ω = 0.4 , and the prediction increment is Δ N = 5 .

4.2. Total Trajectory Simulation

When the sampling time t = 0.1 s, the system tracking results are plotted in Figure 3. The blue trajectory represents the improved NMPC algorithm proposed in this paper and the red trajectory represents the algorithm used in reference [28]. The black trajectory represents the desired trajectory. Observing the trajectories at t = 0.6 s, it can be seen that our proposed improved algorithm exhibits a significant improvement in rapidity, tracking the desired trajectory in a shorter time, with better performance and higher accuracy under the same conditions.

4.3. Improved NMPC Tracking Trajectory Performance and Efficiency Comparison

The NMPC algorithm utilizing the Hamiltonian solution method is employed to solve the position trajectory, with a sampling time of t = 0.2 s. The grey trajectory curves for N = 5 and light blue trajectory curves for N = 10 are plotted. For a sampling time of t = 0.1 s and N = 5 , the yellow trajectory curve with d m a x = 1 and the brown trajectory curve with d m a x = 10 are solved using the mC/GMRES method [28]. Additionally, with the same sampling time of t = 0.1 s, the improved NMPC solution proposed in this paper is computed for various values of N and d m a x . In Table 1, it can be seen that the average running time of the algorithms increases as N increases. However, when comparing the two algorithms with the same N, it can be seen that the average solution speed of the improved NMPC proposed in this paper is higher than that of the Hamiltonian-based NMPC. As shown in Figure 4 and Figure 5, the improved NMPC exhibits faster responsiveness and tracking with faster stabilization. As N and d m a x increase, the e x error rapidly converges close to 0. In Figure 4, the C/GMRES method does not achieve a steady-state trend as quickly as the improved NMPC, which can also be observed in e y . It is observed that with the same d m a x , the system response is faster when N = 10 ; however, when both N and d m a x are lower, the tracking effect is not so good. In Figure 5, larger N and d m a x can make the system error smaller and the system response faster. So when N and d m a x exist relatively correctly, the system performance improves more obviously. The response time is shorter and the system error is smaller. It can be synthesized that the proposed improved NMPC demonstrates better overall performance within the tracking system, but comparisons reveal that different values of N and d m a x still result in slight variations in tracking effectiveness.

4.4. Performance under Wind Disturbance

When the system faces irregular and sudden wind disturbances during flight, its ability to recover quickly and accurately is essential for stability. To evaluate this recovery capability, wind disturbances of d s = [ 2 ; 0.1 ; 1 ]  m/s lasting for 0.2 s are applied at 10 s, 15 s, and 20 s, respectively. As shown in Figure 6, the mC/GMRES method demonstrates poor recovery performance in response to wind disturbances, while the improved NMPC proposed in this paper recovers more rapidly.
When subjected to smaller wind disturbances of d s = [ 0.2 ; 0.1 ; 0.3 ]  m/s, lasting 0.2 s at 10 s, 15 s, and 20 s, respectively, the recovery performance and the magnitude of the resulting errors are compared. This comparison includes cases where d m a x for the mC/GMRES method is 1 and 10, and where d m a x for the improved NMPC method varies. As shown in Figure 7, the improved NMPC proposed in this paper handles wind disturbances more effectively and recovers to stable values more quickly. Figure 8 illustrates that the error in the solution process of the improved NMPC is smoother and converges faster in response to disturbances compared to the mC/GMRES algorithm. In summary, the improved NMPC significantly enhances perturbation resistance and stability compared to the mC/GMRES method. Additionally, Figure 9 shows the variation in linear velocity under different algorithms.

4.5. Attitude Trajectory and Error Simulation

Given the decoupling of the three attitude angles, which are obtained under conditions of rapidity and stability in the position loop, the expected values also adhere to physical characteristics and exhibit strong continuity and stability. Based on this, PID control is employed for the UAV’s attitude loop, ensuring more accurate control with enhanced stability. In the absence of external wind disturbances, Figure 10, Figure 11 and Figure 12 illustrate the images for different angular velocities and error values, respectively. It can be seen that the error ϕ e , θ e , and ψ e can quickly reach a steady state. The entire trajectory tracking simulation can be viewed at this link (https://github.com/MHY-design/Dissertation-Video-Verification/blob/main/Real-time%20UAV%20trajectory.gif, accessed on 5 August 2024). It demonstrates that the UAV can track the entire trajectory in real time, achieve a stable state quickly, and maintain stable control performance.

5. Conclusions

An improved NMPC control algorithm is proposed for a quadrotor UAV under practical conditions. This algorithm simultaneously considers inequality constraints, control variation increments, and time constraints. A fixed-time integral sliding mode controller is employed as an auxiliary controller for stability constraints to ensure closed-loop system stability. Simulations using algorithms with varying numerical values to track the reference trajectory indicate that the improved NMPC proposed in this paper is more suitable for efficiently tracking quadrotors. The simulation experiments clearly show that the parameters significantly impact the system’s performance.

Author Contributions

Conceptualization, H.M.; methodology, H.M.; software, Y.G.; validation, H.M., Y.G. and S.X.; formal analysis, S.X.; investigation, H.M.; resources, S.X. and Y.Y.; data curation, Y.G.; writing—original draft preparation, H.M.; writing—review and editing, Y.G.; visualization, S.X.; supervision, Y.G. and Y.Y.; project administration, S.X.; funding acquisition, S.X. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported in part by the National Natural Science Foundation of China (Grant Number 62073212), and in part by the Natural Science Foundation of Shanghai (Grant Number 23ZR1426600).

Data Availability Statement

The data presented in this study are available on request from the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

Appendix A

Appendix A.1

Proof of Lemma 1. 
The detailed derivation of the KKT conditions for P 2 ( x ) is provided below [28]:
J ¯ = i = 0 N 1 X x i , u i , p i δ + X N x N , p N + i = 0 N 1 κ ¯ j + 1 T × f d x j , u j , p j x j + 1 = + i = 0 N 1 ε · ϑ u i , U max i δ + κ ¯ 0 T x t 0 x 0
where f d x i , u i , p i = x i + f x i , u i , p i δ , and the Hamiltonian sequence formula is defined as H i = X x i , u i , p i δ + κ ¯ i + 1 T f d x i , u i , p i + ε · ϑ u i , U max i δ , and then simplifying J ¯ to J ¯ = X N x N , p N κ ¯ N T x N + i = 0 N 1 H i κ ¯ i T x i + H 0 + κ ˜ 0 T x t 0 x 0 .
If X = c o l x 0 , , x N holds true, then J ¯ = 0 is equivalent to d J ¯ = J ¯ X d X + J ¯ U ¯ d U ¯ = 0 . After simplifying d J ¯ , we can obtain the following:
d J ¯ = X N X κ ¯ N T d X + i = 0 N 1 H i x i κ ¯ i T d x i + H i u i d u i = + H 0 x 0 d x 0 + H 0 u 0 d u 0 κ ˜ 0 T d x 0 = 0
if the selected costate is
κ ¯ i T H i x i = 0
X N X κ ¯ N T = 0
given x 0 = x t 0 , then d J ¯ = 0 is equivalent to
d J ¯ = i = 0 N 1 H i u i d u i = 0
In this context, we can see that Equations (A3a) and (A3b) are equal to Equations (13) and (12), and (14) is sufficient to solve (A4). Currently, the sufficiency of the PMP in addressing the KKT conditions has been proven.
Let U ¯ n represent the solution to P 2 ( x ) when ε = ε n , then P 2 ( x ) can be expressed as follows:
J ¯ U ¯ n , ε n = J U ¯ n + ε n · ϑ U ¯ n δ

Appendix A.2

Proof of Lemma 2. 
[29] When ε n + 1 < ε n , combining with Equation (A5), we have
J ¯ U ¯ n + 1 , ε n + 1 J ¯ U ¯ n + 1 + ε n · ϑ U ¯ n + 1 δ = J ¯ U ¯ n + 1 , ε n
J ¯ U ¯ n + 1 , ε n + 1 J ¯ U ¯ n , ε n + 1
similarly, we have
J ¯ U ¯ n + 1 , ε n J ¯ U ¯ n , ε n
from Equations (A6a) and (A7), we can derive
J ¯ U ¯ n + 1 , ε n + 1 J ¯ U ¯ n , ε n
substituting (A5) into (A6b) and (A7), we obtain
J ¯ U ¯ n + 1 U ¯ n ε n + 1 ϑ U ¯ n ϑ U ¯ n + 1
J ¯ U ¯ n + 1 U ¯ n ε n ϑ U ¯ n ϑ U ¯ n + 1
combining (A9) and (A10), we obtain
ε n ε n + 1 ϑ U ¯ n ϑ U ¯ n + 1 0
therefore, we can obtain
ϑ U ¯ n ϑ U ¯ n + 1
when 0 < ε n + 1 < ε n holds, substituting (A12) into (A9) yields
J ¯ U ¯ n + 1 J ¯ U ¯ n

Appendix A.3

Proof of Theorem 1. 
Constructing the Lyapunov candidate function as V = 1 2 s 2 , its derivative can be obtained:
V ˙ = s s ˙ = s m ( ζ u n o m ) = s m ( γ 1 sig b c ( s ) γ 2 sig n m ( s ) ) 1 m ( γ 1 s b + c c + γ 2 s n + m m ) β 1 2 γ ^ 1 V γ ^ 1 β 2 2 γ ^ 2 V γ ^ 2
where β 1 = γ 1 m , β 2 = γ 2 m , γ ^ 1 = b + c 2 c , γ ^ 2 = n + m 2 m . The system trajectory is fixed-time stable. Moreover, it can converge within time T 1 β 1 2 γ ^ 1 ( 1 γ ^ 1 ) + 1 β 2 2 γ ^ 2 ( γ ^ 2 1 ) . This means that the sliding variable s remains within a small boundary of zero, which ensures the true sliding mode. As a result, the state variables of the position system will converge to the origin along the sliding surface [41]. □

References

  1. Zuo, Z. Trajectory tracking control design with command-filtered compensation for a quadrotor. IET Control Theory Appl. 2010, 4, 2343–2355. [Google Scholar] [CrossRef]
  2. Cho, S.W.; Park, H.J.; Lee, H.; Shim, D.H.; Kim, S.Y. Coverage path planning for multiple unmanned aerial vehicles in maritime search and rescue operations. Comput. Ind. Eng. 2021, 161, 107612. [Google Scholar] [CrossRef]
  3. Shao, X.; Liu, J.; Cao, H.; Shen, C.; Wang, H. Robust dynamic surface trajectory tracking control for a quadrotor UAV via extended state observer. Int. J. Robust Nonlinear Control 2018, 28, 2700–2719. [Google Scholar] [CrossRef]
  4. Chen, T.; Shan, J. A novel cable-suspended quadrotor transportation system: From theory to experiment. Aerosp. Sci. Technol. 2020, 104, 105974. [Google Scholar] [CrossRef]
  5. He, Y.; Zhang, S. Trajectory tracking control for quad-rotor system in the presence of velocity constraint. Int. J. Adv. Robot. Syst. 2020, 17, 1729881420931682. [Google Scholar] [CrossRef]
  6. Gao, p.; Liu, y.; Zhang, H.; Wang, l. Quadrotor helicopter Attitude Control using cascade PID. In Proceedings of the 28th Chinese Control and Decision Conference, CCDC 2016, Yinchuan, China, 28–30 May 2016; pp. 5158–5163. [Google Scholar]
  7. Li, C.; Jing, H.; Bao, J.; Sun, S.; Wang, R. Robust H fault tolerant control for quadrotor attitude regulation. Proc. Inst. Mech. Eng. Part I J. Syst. Control. Eng. 2018, 232, 1302–1313. [Google Scholar] [CrossRef]
  8. Rekabi, F.; Shirazi, F.A.; Sadigh, M.J.; Saadat, M. Nonlinear H Measurement Feedback Control Algorithm for Quadrotor Position Tracking. J. Frankl. Inst. 2020, 357, 6777–6804. [Google Scholar] [CrossRef]
  9. Li, B.; Liu, H.; Ahn, C.K.; Wang, C.; Zhu, X. Fixed-Time Tracking Control of Wheel Mobile Robot in Slipping and Skidding Conditions. IEEE/ASME Trans. Mechatron. 2024, 1–11. [Google Scholar] [CrossRef]
  10. Li, B.; Hu, Q.; Yang, Y. Continuous finite-time extended state observer based fault tolerant control for attitude stabilization. Aerosp. Sci. Technol. 2019, 84, 204–213. [Google Scholar] [CrossRef]
  11. Li, B.; Gong, W.; Yang, Y.; Xiao, B.; Ran, D. Appointed Fixed Time Observer-Based Sliding Mode Control for a Quadrotor UAV Under External Disturbances. IEEE Trans. Aerosp. Electron. Syst. 2022, 58, 290–303. [Google Scholar] [CrossRef]
  12. Huang, Y.; Zhu, M.; Zheng, Z.; Feroskhan, M. Fixed-time autonomous shipboard landing control of a helicopter with external disturbances. Aerosp. Sci. Technol. 2019, 84, 18–30. [Google Scholar] [CrossRef]
  13. Li, B.; Liu, H.; Ahn, C.K.; Gong, W. Optimized intelligent tracking control for a quadrotor unmanned aerial vehicle with actuator failures. Aerosp. Sci. Technol. 2024, 144, 108803. [Google Scholar] [CrossRef]
  14. Hanover, D.; Foehn, P.; Sun, S.; Kaufmann, E.; Scaramuzza, D. Performance, Precision, and Payloads: Adaptive Nonlinear MPC for Quadrotors. IEEE Rob. Autom. Lett. 2022, 7, 690–697. [Google Scholar] [CrossRef]
  15. Zheng, R.; Lyu, Y. Nonlinear tight formation control of multiple UAVs based on model predictive control. Def. Technol. 2023, 25, 69–75. [Google Scholar] [CrossRef]
  16. Xu, Z.; Fan, L.; Qiu, W.; Wen, G.; He, Y. A Robust Disturbance-Rejection Controller Using Model Predictive Control for Quadrotor UAV in Tracking Aggressive Trajectory. Drones 2023, 7, 557. [Google Scholar] [CrossRef]
  17. Yi, F.; Zhang, C.; Rawashdeh, S.; Baek, S. Autonomous Landing of a UAV on a Moving Platform Using Model Predictive Control. Drones 2018, 2, 34. [Google Scholar] [CrossRef]
  18. Wei, H.; Shen, C.; Shi, Y. Distributed Lyapunov-Based Model Predictive Formation Tracking Control for Autonomous Underwater Vehicles Subject to Disturbances. IEEE Trans. Syst. Man Cybern. Syst. 2021, 51, 5198–5208. [Google Scholar] [CrossRef]
  19. Mohammadi, A.; Feng, Y.; Zhang, C.; Rawashdeh, S.; Baek, S. Vision-Based Autonomous Landing Using an MPC-Controlled Micro UAV on a Moving Platform. In Proceedings of the 2020 International Conference on Unmanned Aircraft Systems, ICUAS 2020, Athens, Greece, 1–4 September 2020; pp. 771–780. [Google Scholar]
  20. Vlantis, P.; Marantos, P.; Bechlioulis, C.P.; Kyriakopoulos, K.J. Quadrotor landing on an inclined platform of a moving ground vehicle. In Proceedings of the IEEE International Conference on Robotics and Automation, Seattle, WA, USA, 26–30 May 2015; pp. 2202–2207. [Google Scholar]
  21. Outeiro, P.; Cardeira, C.; Oliveira, P. Multiple-model adaptive control architecture for a quadrotor with constant unknown mass and inertia. Aerosp. Sci. Technol. 2021, 117, 106899. [Google Scholar] [CrossRef]
  22. Yan, D.; Zhang, W.; Chen, H.; Shi, J. Robust control strategy for multi-UAVs system using MPC combined with Kalman-consensus filter and disturbance observer. Isa Trans. 2023, 135, 35–51. [Google Scholar] [CrossRef]
  23. Zhang, K.; Liu, C.; Shi, Y. Self-triggered adaptive model predictive control of constrained nonlinear systems: A min-max approach. Automatica 2022, 142, 110424. [Google Scholar] [CrossRef]
  24. Cengiz, S.K.; Ucun, L. Optimal controller design for autonomous quadrotor landing on moving platform. Simul. Model. Pract. Theory 2022, 119, 102565. [Google Scholar] [CrossRef]
  25. Wu, X.; Xiao, B.; Wu, C.; Guo, Y. Centroidal voronoi tessellation and model predictive control–based macro-micro trajectory optimization of microsatellite swarm. Space Sci. Technol. 2022, 2022, 9802195. [Google Scholar] [CrossRef]
  26. Boyd, S.; Vandenberghe, L. Convex Optimization; Cambridge University Press: Cambridge, UK, 2004. [Google Scholar]
  27. Ohtsuka, T. A tutorial on C/GMRES and automatic code generation for nonlinear model predictive control. In Proceedings of the 2015 European Control Conference, ECC 2015, Linz, Austria, 15–17 July 2015; pp. 73–86. [Google Scholar]
  28. Shen, C.; Buckham, B.; Shi, Y. Modified C/GMRES Algorithm for Fast Nonlinear Model Predictive Tracking Control of AUVs. IEEE Trans. Control Syst. Technol. 2017, 25, 1896–1904. [Google Scholar] [CrossRef]
  29. Wang, D.; Pan, Q.; Shi, Y.; Hu, J.; Records, C.Z. Efficient Nonlinear Model Predictive Control for Quadrotor Trajectory Tracking: Algorithms and Experiment. IEEE Trans. Cybern. 2021, 51, 5057–5068. [Google Scholar] [CrossRef]
  30. Singh, B.K.; Kumar, A. Model predictive control using LPV approach for trajectory tracking of quadrotor UAV with external disturbances. Aircaft Eng. Aerosp. Technol. 2023, 95, 607–618. [Google Scholar] [CrossRef]
  31. Giorgi, G.; Jimenez, B.; Novo, V. Approximate Karush-Kuhn-Tucker Condition in Multiobjective Optimization. J. Optim. Theory Appl. 2016, 171, 70–89. [Google Scholar] [CrossRef]
  32. Lasdon, L.; Waren, A.; Rice, R. An interior penalty method for inequality constrained optimal control problems. IEEE Trans. Autom. 1967, 12, 388–395. [Google Scholar] [CrossRef]
  33. Khalil, K.H. Nonlinear Systems; Prentice-Hall: Hoboken, NJ, USA, 2002. [Google Scholar]
  34. Christofides, P.D.; Jinfeng, L.; de la Peña, D.M. Networked and Distributed Predictive Control: Methods and Nonlinear Process Network Applications; Advances in Industrial Control; Springer: London, UK, 2011. [Google Scholar] [CrossRef]
  35. Munoz de la Pena, D.; Christofides, P.D. Lyapunov-Based Model Predictive Control of Nonlinear Systems Subject to Data Losses. IEEE Trans. Automat. Control 2008, 53, 2076–2089. [Google Scholar] [CrossRef]
  36. Shen, C.; Shi, Y. Distributed implementation of nonlinear model predictive control for AUV trajectory tracking. Automatica 2020, 115, 108863. [Google Scholar] [CrossRef]
  37. Shen, C.; Shi, Y.; Buckham, B. Lyapunov-based model predictive control for dynamic positioning of autonomous underwater vehicles. In Proceedings of the 2017 IEEE International Conference on Unmanned Systems, ICUS 2017, Beijing, China, 27–29 October 2017; pp. 588–593. [Google Scholar]
  38. Ba, D.; Li, Y.X.; Tong, S. Fixed-time adaptive neural tracking control for a class of uncertain nonstrict nonlinear systems. Neurocomputing 2019, 363, 273–280. [Google Scholar] [CrossRef]
  39. Polyakov, A. Nonlinear Feedback Design for Fixed-Time Stabilization of Linear Control Systems. IEEE Trans. Autom. 2012, 57, 2106–2110. [Google Scholar] [CrossRef]
  40. Li, B.; Zhang, H.; Xiao, B.; Wang, C.; Yang, Y. Fixed-time integral sliding mode control of a high-order nonlinear system. Nonlinear Dyn. 2022, 107, 909–920. [Google Scholar] [CrossRef]
  41. Song, T.; Fang, L.; Wang, H. Model-free finite-time terminal sliding mode control with a novel adaptive sliding mode observer of uncertain robot systems. Asian J. Control 2022, 24, 1437–1451. [Google Scholar] [CrossRef]
Figure 1. The structure representation of a quadrotor UAV.
Figure 1. The structure representation of a quadrotor UAV.
Drones 08 00387 g001
Figure 2. The schematic of the control strategy.
Figure 2. The schematic of the control strategy.
Drones 08 00387 g002
Figure 3. Overall trajectory comparison.
Figure 3. Overall trajectory comparison.
Drones 08 00387 g003
Figure 4. Optimal solutions of different algorithms.
Figure 4. Optimal solutions of different algorithms.
Drones 08 00387 g004
Figure 5. Tracking errors under different algorithms.
Figure 5. Tracking errors under different algorithms.
Drones 08 00387 g005
Figure 6. Comparison of tracking images under strong disturbances with different algorithms.
Figure 6. Comparison of tracking images under strong disturbances with different algorithms.
Drones 08 00387 g006
Figure 7. Optimal solutions of different algorithms under interference.
Figure 7. Optimal solutions of different algorithms under interference.
Drones 08 00387 g007
Figure 8. Tracking errors under different algorithms in the presence of disturbances.
Figure 8. Tracking errors under different algorithms in the presence of disturbances.
Drones 08 00387 g008
Figure 9. Linear velocity under different algorithms in the presence of disturbances.
Figure 9. Linear velocity under different algorithms in the presence of disturbances.
Drones 08 00387 g009
Figure 10. Attitude loop ϕ e error and ϕ ˙ .
Figure 10. Attitude loop ϕ e error and ϕ ˙ .
Drones 08 00387 g010
Figure 11. Attitude loop θ e error and θ ˙ .
Figure 11. Attitude loop θ e error and θ ˙ .
Drones 08 00387 g011
Figure 12. Attitude loop ψ e error and θ ˙ .
Figure 12. Attitude loop ψ e error and θ ˙ .
Drones 08 00387 g012
Table 1. The time required for each iteration of different algorithms.
Table 1. The time required for each iteration of different algorithms.
Numerical AlgorithmPrediction HorizonAverage Time (s)
Improved NMPCN = 50.0012
N = 100.0041
N = 150.0065
Hamiltonian-based NMPCN = 50.15
N = 100.19
N = 151.28
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

Ma, H.; Gao, Y.; Yang, Y.; Xu, S. Improved Nonlinear Model Predictive Control Based Fast Trajectory Tracking for a Quadrotor Unmanned Aerial Vehicle. Drones 2024, 8, 387. https://doi.org/10.3390/drones8080387

AMA Style

Ma H, Gao Y, Yang Y, Xu S. Improved Nonlinear Model Predictive Control Based Fast Trajectory Tracking for a Quadrotor Unmanned Aerial Vehicle. Drones. 2024; 8(8):387. https://doi.org/10.3390/drones8080387

Chicago/Turabian Style

Ma, Hongyue, Yufeng Gao, Yongsheng Yang, and Shoulin Xu. 2024. "Improved Nonlinear Model Predictive Control Based Fast Trajectory Tracking for a Quadrotor Unmanned Aerial Vehicle" Drones 8, no. 8: 387. https://doi.org/10.3390/drones8080387

APA Style

Ma, H., Gao, Y., Yang, Y., & Xu, S. (2024). Improved Nonlinear Model Predictive Control Based Fast Trajectory Tracking for a Quadrotor Unmanned Aerial Vehicle. Drones, 8(8), 387. https://doi.org/10.3390/drones8080387

Article Metrics

Back to TopTop