Next Article in Journal
Monitoring the Impact of Urban Development on Archaeological Heritage Using UAV Mapping: A Framework for Preservation and Urban Growth Management
Previous Article in Journal
Review of Hybrid Aerial Underwater Vehicle: Potential Applications in the Field of Underwater Marine Optics
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Adaptive Robust Optimal Control for UAV Taxiing Systems with Uncertainties

College of Aerospace Science and Engineering, National University of Defense Technology, Changsha 410073, China
*
Author to whom correspondence should be addressed.
Drones 2025, 9(10), 668; https://doi.org/10.3390/drones9100668
Submission received: 13 August 2025 / Revised: 16 September 2025 / Accepted: 22 September 2025 / Published: 23 September 2025

Abstract

The ground taxiing phase is a crucial stage for the autonomous takeoff and landing of fixed-wing unmanned aerial vehicles (UAVs), and its trajectory tracking accuracy and stability directly determine the success of the UAV’s autonomous takeoff and landing. Therefore, researching the adaptive robust optimal control technology for UAV taxiing is of great significance for enhancing the autonomy and environmental adaptability of UAVs. This study integrates the linear quadratic regulator (LQR) with sliding mode control (SMC). A compensation control signal is generated by the SMC to mitigate the potential effects of uncertain parameters and random external disturbances, which is then added onto the LQR output to achieve a robust optimal controller. On this basis, through ANFIS (Adaptive Neuro-Fuzzy Inference System), the nonlinear mapping relationship between multiple state parameters such as speed, lateral/heading deviation and the weight matrix of the LQR controller is learned, realizing a data-driven adaptive adjustment mechanism for controller parameters to improve the tracking accuracy and anti-interference stability of the UAV’s taxiing trajectory.

1. Introduction

The ground taxiing phase is a crucial stage for the autonomous takeoff and landing of fixed-wing UAVs, and its trajectory tracking accuracy and stability directly determine the success of the UAV’s autonomous takeoff and landing [1,2,3]. However, the taxiing characteristics of UAVs are complex and significantly different from their flight characteristics in the air. The ground taxiing motion state results from the combined effects of the airframe structure, external excitations (ground reaction forces), and various control systems (main wheel braking, nose wheel steering, rudder deflection), constituting a complex composite motion system. Specific challenges unique to this phase compared to the airborne phase include the following: (1) Complex Force Interactions: During taxiing, UAVs are subjected not only to aerodynamic forces (e.g., crosswind disturbances) but also significantly to ground reaction forces (such as uneven ground normal forces due to runway irregularities, longitudinal/lateral friction forces sensitive to varying surface friction coefficients) and braking forces, compounded by the influence of ground effect on aerodynamic characteristics. This strong coupling among aerodynamics, mechanics, and ground interactions makes modeling and control more complex than in the airborne phase. (2) Higher Disturbance Sensitivity and Safety Risks: External disturbances like crosswinds and runway unevenness, coupled with factors like unbalanced ground forces or non-ideal initial touchdown conditions, readily cause lateral deviation and yaw angle errors. Due to direct physical contact with the ground and the critical alignment between the velocity vector and the fuselage, these deviations can easily lead to severe incidents like sideslip, rollover, wingtip ground contact, or runway excursions, offering a much lower safety margin and fault tolerance than flight. (3) High Model Uncertainty: Nonlinear stiffness/damping of the landing gear suspension, complex and variable tire-ground friction models, and factors like changing mass distribution contribute to significant uncertainties in the ground taxiing model, making it difficult to develop a perfect model replicating true dynamics. (4) Different Actuators and Constraints: Lateral deviation correction relies primarily on nose wheel steering (NWS), differential braking, and the rudder. Their effectiveness, response characteristics, and constraints (e.g., NWS angle limits, braking force saturation) differ from airborne control surfaces. Consequently, traditional control methods struggle to achieve high-precision correction under these conditions and may even introduce safety risks such as sideslip and rollover. Currently, the main correction methods for fixed-wing UAVs include nose wheel steering, differential braking of main wheels, and rudder correction, and the main control methods include MPC control, LQR control [4], SMC control [5], and H∞ control [6].
LQR is an optimal control method characterized by its fast response and high accuracy, and it is widely employed in the control systems of various aircraft, including UAVs [7], helicopters [8], and satellites [9]. LQR designs the state feedback control law by minimizing the quadratic cost function of the state and control input, to comprehensively balance the dynamic response performance of the system and the control energy consumption, thereby achieving the optimal asymptotic stability control of the system state. However, this method is highly dependent on the accuracy of system model. Therefore, how to improve the robustness of the control system in the presence of model deviations and external disturbances has always been a research challenge.
Some studies have adopted DOB (Disturbance Observer) to enhance the system’s robustness [10]. However, this method is still affected by model deviations (the accuracy of disturbance estimation is highly dependent on the accuracy of the nominal model, and DOB may cause incorrect compensation when the model deviation is large). There are also studies that use SMC to improve system robustness. On the basis of LQR state feedback control, a sliding mode control compensation term is superimposed to form a composite control law. SMC designs a sliding surface and dynamically adjusts the control quantity based on the distance between the system state and the sliding surface, forcibly pulling the system trajectory back to the sliding surface, thereby suppressing the influence of model deviations and disturbances. This method has strong robustness and fast dynamic response. The drawback is that it may cause high-frequency chattering, but methods such as the boundary layer method can be used to suppress the chattering.
Recently, more advanced algorithms like finite-time control, reinforcement learning (RL), and other intelligent methods have emerged, demonstrating significant potential in handling complex nonlinear systems. Finite-time control techniques, including terminal sliding mode control and fixed-time control, can guarantee system state convergence within a predetermined time, providing superior transient performance and robustness against disturbances [11]. Reinforcement learning, particularly deep RL frameworks such as Deep Deterministic Policy Gradient (DDPG) and Proximal Policy Optimization (PPO), has shown remarkable capabilities in learning optimal control policies directly from interaction with the environment without requiring precise system models [12,13]. These methods can handle high-dimensional state spaces and adapt to various operating conditions through continuous learning. Additionally, other intelligent approaches like neural adaptive control [14] and fuzzy logic systems [15] have been successfully applied to handle model uncertainties and nonlinearities in UAV control.
However, for the safety-critical, low-level ground taxiing control problem, these advanced methods often face substantial challenges. The implementation of finite-time control typically requires precise system models and may involve complex Lyapunov function designs [11], while RL approaches demand extensive training data that could be impractical or risky to collect in real-world taxiing scenarios [12,13]. Furthermore, both methods exhibit high computational complexity that may exceed the processing capabilities of standard UAV flight controllers. Most importantly, providing formal guarantees of stability and safety for these learning-based controllers remains theoretically challenging, particularly under all possible edge cases encountered during ground operations where real-time performance and reliability are critical. These limitations may restrict their practical application in this scenario where reliability and certifiability are paramount.
Therefore, instead of pursuing overly complex architectures, this study combines the LQR with SMC, generating a compensation control quantity via SMC to address potential influences of uncertain parameters and random external disturbances, which is then added onto the LQR output to achieve a robust optimal controller.
The performance of LQR is significantly influenced by control parameters, which are typically obtained through empirical tuning or parameter optimization [16,17]. Since the control parameters are constant, the control system usually fails to adapt to tracking control under different motion states. Some studies have adopted fuzzy algorithms to adaptively adjust parameters. For instance, Wang et al. [18] designed a fuzzy adaptive LQR controller based on sideslip angle and yaw rate, achieving dynamic adjustment of control parameters. However, this approach did not fully consider the impact of speed changes and other state coupling relationships on parameter variations, and the completeness of fuzzy rules might be limited, making it difficult for the controller to simultaneously adapt to the multiple coupled states and multi-parameter dynamic adjustment requirements during taxiing. Therefore, this study uses ANFIS (Adaptive Neuro-Fuzzy Inference System) to learn the nonlinear mapping relationship between multiple state parameters such as speed, lateral/heading deviation during the taxiing of UAVs and the weight matrix of the LQR controller, thereby realizing a data-driven adaptive adjustment mechanism for controller parameters to enhance the tracking accuracy and anti-interference stability of the taxiing trajectory of UAVs.
The main contributions of this paper are summarized as follows:
  • Compared to the classical LQR controller [19,20] which requires an accurate model, the proposed composite scheme maintains satisfactory performance under model uncertainties and external disturbances. Furthermore, unlike the DOB-based methods [10] whose estimation accuracy is highly sensitive to the nominal model, the proposed approach is less dependent on the precise model and demonstrates superior robustness under large parameter perturbations. While traditional SMC [21] offers robustness, it suffers from inherent chattering issues that can excite unmodeled dynamics and cause actuator wear; our method effectively suppresses chattering through boundary-layer compensation while preserving robustness by integrating the optimal control effort of LQR with the robust compensation of SMC. Additionally, in contrast to LQR with Integral action (LQI) [22], which improves steady-state error tracking but exhibits limited robustness against time-varying disturbances and model uncertainties, our approach provides enhanced transient performance and consistent tracking accuracy across a wider range of operational conditions.
  • Unlike the manual parameter tuning [16,17] which is tedious and subjective, our approach provides an automated and optimal solution. Compared to the fuzzy adaptive LQR in [18] which relies on limited empirical rules and a few states, our PSO-ANFIS framework captures the complex nonlinear coupling between multiple states (e.g., speed, lateral and heading deviations), leading to more comprehensive and superior adaptive rules. Moreover, unlike online adaptive strategies that may incur computational burdens, our offline-trained ANFIS ensures high computational efficiency during real-time operation.
  • The proposed adaptive robust optimal controller is validated through simulations under diverse conditions, including model parameter deviations and random friction disturbances. Compared to conventional controllers, the proposed method demonstrates superior tracking accuracy and anti-interference stability, offering a more reliable solution for safe autonomous taxiing of fixed-wing UAVs.

2. Three-Dimensional Dynamic Model of Ground Taxiing

2.1. Model Setting

2.1.1. Model Simplification and Parameter Setting

The key difference between the taxiing model and the conventional six-degree-of-freedom dynamics model of UAVs lies in the ground interaction. The ground force acting on the landing gear includes the support force and the friction force. Referring to Ref. [23], for the convenience of analysis and calculation, the dynamics model of the UAV landing gear in this paper is established based on the following simplified conditions:
(1)
The longitudinal dynamics of the landing gear is simplified as a spring-damper system, and an oil-gas shock absorber model is established, which is related to the ground constraint through the compression amount.
(2)
The landing gear and the airframe are rigidly connected, and except for the spring extension and contraction motion of the buffer model, the deflection deformation of the support structure and other minor deformations (such as the elastic deformation of the tires) are ignored.
(3)
The lateral dynamics of the landing gear is simplified as a three-wheel cart model, with the nose gear being steerable and the main landing gear rigidly connected to the airframe.
The longitudinal and lateral simplified diagrams of the landing gear are shown in Figure 1 and Figure 2. According to the geometric parameter definitions, the relative positions of the front and main wheels to the center of gravity in the aircraft coordinate system can be expressed as
r f , b   =   l f 0 h f b , r b l , b   =   l b 0.5 d b h b l b , r b r , b   =   l b 0.5 d b h b r b
In the formula, l f represents the distance from the nose landing gear to the center of gravity, l b represents the distance from the main landing gear to the center of gravity, d b is the main wheel track, h b is the height of the main landing gear, h f is the height of the nose landing gear, and r i , j represents the relative position vector of the tire. The first subscript i indicates that f is the nose landing gear, b l is the left main landing gear, and b r is the right main landing gear; the second subscript j indicates that b is the body coordinate system and g is the inertial coordinate system.
Figure 1. Longitudinal dynamics model of landing gear.
Figure 1. Longitudinal dynamics model of landing gear.
Drones 09 00668 g001
Figure 2. Lateral dynamics model of landing gear.
Figure 2. Lateral dynamics model of landing gear.
Drones 09 00668 g002

2.1.2. Simulation Friction Model

To address the issue of simulating static friction in digital simulation processes, this paper proposes an approximate calculation method related to the relative motion velocity and based on the following assumptions:
  • A small quantity v t 0 + is set as the static/dynamic transition velocity, and static friction is approximated as a continuous function of velocity;
  • The Stribeck effect [24] is considered, and an exponentially decreasing term is added during the static/dynamic friction transition process.
The approximate mathematical expression is:
μ t ( v )   =   sgn ( v ) μ s   +   1 v / v t 1 , | v | v t sgn ( v ) μ c   +   μ s μ c e k | v | | v | , | v | > v t
Comparison of speed changes in the physical model and the simulation model of the deceleration process as shown in Figure 3. The variation trend of the approximate friction coefficient with speed is shown in Figure 4. Although this model has minor differences from the actual physical process during aircraft takeoff, it has the following advantages throughout the entire taxiing simulation process:
  • By using a speed function to continuously convert the static/dynamic friction process, the zero-speed oscillation phenomenon is avoided. The comparison effect with the conventional model is shown in Figure 3.
  • A function relationship between static friction and speed is established, making the movement trend quantifiable and allowing the approximate calculation of the magnitude of static friction force.
  • In the calculation of side force, the friction coefficient is calculated based on the lateral speed, which has a wider application range compared to the small-angle assumption.
Figure 3. Comparison of speed changes in the physical model and the simulation model of the deceleration process.
Figure 3. Comparison of speed changes in the physical model and the simulation model of the deceleration process.
Drones 09 00668 g003
Figure 4. Simulation approximate friction model.
Figure 4. Simulation approximate friction model.
Drones 09 00668 g004

2.2. Analysis of Ground Acting Forces

2.2.1. Modeling of Ground Constraint and Support Force

Based on the simplified assumptions of the landing gear’s spring-damper system in the previous text, the ground contact conditions can be established based on the following constraints:
  • Ground Constraint: First, assume that both the front and main wheels of the landing gear have made contact with the ground. Through the constraint relationship between the relative positions of the tires and the absolute position of the center of gravity, the compression amount can be calculated.
  • Non-negative Compression Constraint: If the compression amount obtained based on Constraint 1 is negative, it indicates that the wheel is not in contact with the ground, and the compression amount is zero.
Referring to Ref. [23], the compression amount of the landing gear can be obtained as:
h f   =   h f 0 h r w , f   +   l f sin θ cos ϕ cos θ h h l   =   h h b 0 h r w , b l b sin θ   +   0.5 d b sin ϕ cos θ cos ϕ cos θ h h r   =   h b 0 h r w b l b sin θ 0.5 d b sin ϕ cos θ cos ϕ cos θ
h is the height of the center of gravity in the inertial system, r w , i is the tire radius (here it is assumed that the radii of the left and right main wheels are the same, while the radii of the front and main wheels may be different), h i represents the actual length of the landing gear in the axial direction. And it satisfies the non-negative condition, that is h f , h b l , h b r 0 . Further, by differentiating the above equation, the rate of change in the compression amount can be obtained as
h f   =   h ˙ cos ϕ cos θ   +   l f   +   h r w , f sin θ θ ˙ cos ϕ   +   h r w , f   +   l f sin θ ϕ ˙ sin ϕ cos θ cos 2 ϕ cos 2 θ h b l   =   0.5 d b ϕ ˙ cos 2 θ   +   h r w , b θ ˙ sin θ   +   h ˙ cos θ l b θ ˙ cos ϕ   +   h r w , b l b sin θ ϕ ˙ sin ϕ cos θ cos 2 ϕ cos 2 θ h b r   =   0.5 d b ϕ ˙ cos 2 θ   +   h r w , b θ ˙ sin θ   +   h ˙ cos θ l b θ ˙ cos ϕ   +   h r w , b l b sin θ ϕ ˙ sin ϕ cos θ cos 2 ϕ cos 2 θ
According to the air elasticity and damping characteristics of the oil-gas shock absorber, the axial force of the landing gear can be obtained as
n G i   =   F a , i   +   F h , i   +   c i h ˙ i , i   =   f , b l , b r
In the formula: F a , i represents the air spring force, and F h , i represents the oil damping force. To simplify the subsequent formula representation, if not otherwise specified, the subscripts i all indicate the nose landing gear f , left main landing gear b l , and right main landing gear b r , respectively. The calculation formulas for air spring force and oil damping force can be specifically referred to in Ref. [23].
Taking all factors into account, the support force of the ground on the landing gear is perpendicular to the ground and upward. Consequently, the ground support force vector can be expressed in the inertial coordinate system as
N i , g   =   0 0 n i , g
Through the rotational matrix and the equilibrium relationship of the landing gear axial force, it can be obtained that
n i , g   =   n G i cos ϕ cos θ
Substituting into Equation (6) yields the vector form of the support force.

2.2.2. Modeling of Friction Force

Based on the approximate friction model and relative velocity, the friction force vectors of each tire in the body axis system can be obtained as
f f , b   =   f x , f f y , f f z , f b   =   R z θ w T R b ψ T μ f , l o n v x , f n f , g μ f , l a t v y , f n f , g 0 ψ , f
f i , b   =   f x , i ^ f y , i ^ f z , i ^ b   =   R b ψ T μ i ^ , l o n v x , i ^ n i ^ , g μ i ^ , l a t v y , i ^ n i ^ , g 0 ψ
In the formula, μ i , l o n v x , i and μ i , l a t v x , i represent the longitudinal and lateral friction coefficients of the tire, respectively.

2.3. Three-Dimensional Dynamic Model

Based on the discussion and analysis in Section 2.1 and Section 2.2, the vector form of the ground forces and moments acting on the landing gear is
F w h e e l , b   =   N G f , b   +   N G b l , b   +   N G b r , b   +   f f , b   +   f b l , b   +   f b r , b M w h e e l , b   =   r f , b w   ×   N f , b   +   f f , b   +   r b l , b w   ×   N b l , b   +   f b l , b   +   r b r , b w   ×   N b r , b   +   f b r , b
In the formula, F w h e e l , b is the resultant force vector of the landing gear acting on the ground in the body axis system, M w h e e l , b is the resultant moment vector, and r i , b w is the position vector of the tire contact point relative to the center of gravity, which can be expressed as
r i , b w   =   r f , b   +   R g b 0 0 r w , i
Further substituting into the six-degree-of-freedom dynamic equation [10] yields
V ˙ c , b   =   ω b   ×   V c , b   +   1 m F w h e e l , b   +   F a e r o , b   +   F g r a , b   +   F t r u , b ω ˙ b   =   J 1 ω b   ×   J ω b   +   M w h e e l , b   +   M a e r o , b
In the equation, V ˙ c , b   =   u , v , w T represents the velocity vector of the aircraft’s center of gravity in the body axis system, ω b   =   [ p , q , r ] T represents the angular velocity vector of the aircraft in the body axis system, F a e r o , b , F g r a , b , F t r u , b respectively represent the aerodynamic force, gravitational force and engine thrust vectors in the body axis system, M a e r o , b represents the aerodynamic moment, and J is the aircraft’s moment of inertia tensor.

3. Robust Optimal Path Tracking Controller for UAV Taxiing

The overall structure of the path tracking controller is shown in Figure 5. Firstly, based on the path tracking model, an LQR controller is designed as the main part of the path tracking controller to make the UAV basically follow the target path. However, due to the sensitivity of the LQR method to parameter uncertainties and external disturbances, on this basis, the sliding mode control is adopted as the angle compensation to suppress parameter disturbances and random interferences, enhance the robustness of the controller, and eliminate the possible steady-state error caused by system simplification [16]. Finally, based on the offline training of ANFIS, a fuzzy mapping rule of state-parameters is established to achieve the adaptive dynamic adjustment of the controller parameters according to the taxiing state (such as speed and lateral deviation). The design of the robust optimal path tracking controller mainly includes the following steps:
(1)
Based on the standard model, ignoring the uncertainty terms in the state equation (Equation (23)), the initial control quantity u * is obtained by using the LQR optimal controller.
(2)
According to the initial optimal controller, the integral sliding surface s and the sliding mode control law ρ ( x ) sgn ( s ) are designed, so that the uncertain system always operates on the integral sliding surface, and when operating on the integral sliding surface, the dynamic characteristics of the uncertain system are independent of parameter changes and external random disturbances.
(3)
The particle swarm optimization algorithm is used to generate the LQR optimal parameter dataset under multiple working conditions in the simulation, and ANFIS is trained offline based on this dataset to adaptively adjust the weight parameter matrix Q , R of the LQR controller.
Figure 5. Block diagram of path tracking controller.
Figure 5. Block diagram of path tracking controller.
Drones 09 00668 g005

3.1. Design of LQR Controller Based on Standard Model

3.1.1. 2-DOF Landing Gear Simplified Model

The nonlinear characteristics of the aforementioned simulation model are relatively strong. To obtain the state space equation shown in Equation (21) and apply it to the design of the LQR control law. Therefore, it is necessary to simplify the above model. It is assumed that the side-slip stiffness of the left and right main wheels is the same and geometrically symmetrical. Under the condition of the UAV traveling at a constant speed in a straight line or with a small steering angle, the vertical load and lateral force of the left and right main wheels are approximately symmetrical. Therefore, the left and right main wheels of the UAV can be combined to obtain the single-track 2-DOF landing gear model as shown in Figure 6.
When the speed of the UAV is relatively low, the influence of aerodynamic forces can be disregarded. By analyzing the lateral and directional forces acting on the UAV, it can be concluded that
m a y   =   F y f   +   F y b I z r ˙   =   l f F y f l b F y b
Under normal operating conditions with lower speeds and smaller front wheel angles, it can be assumed that the lateral force acting on the front/main wheels is linearly related to the slip angle:
F y f   =   c f β f F y b   =   2 c b β b β f   =   δ f v y   +   l f r v x β b   =   v y l b r v x
Among them, the front wheel side slip stiffness c f , each main wheel side slip stiffness c b , and the equivalent total main wheel side slip stiffness are expressed as 2 c b , where v x , v y are the longitudinal and lateral velocities of the UAV, respectively. c f , c b represent the side slip stiffness of the front and main wheels, β f , β b represent the side slip angles of the front and main wheels, δ f represents the front wheel rotation angle, and r represents the yaw rate.
Substituting Equation (14) into Equation (13), the lateral dynamic model of the UAV can be obtained:
v ˙ y   =   v x   +   c f l f 2 c b l b m v x r c f   +   2 c b m v x v y   +   c f m δ f r ˙   =   c f l f 2   +   2 c b l b 2 I z v x r c f l f 2 c b l b I z v x v y   +   c f l f I z δ f

3.1.2. Path Tracking Model

Lateral deviation e y and heading deviation e ψ can be used as performance indicators for UAV path tracking. As shown in the following figure, the shortest distance between the UAV’s center of mass and the target path is defined as e y , and the angle between the UAV’s heading angle ψ and the reference heading angle ψ d e s is defined as e ψ . The path tracking model is shown in Figure 7.
Assuming that the heading deviation is relatively small, the heading deviation and the lateral velocity deviation can be obtained:
e ψ   =   ψ ψ d e s
e ˙ y   =   v y   +   v x e ψ
Assuming the turning radius of the reference path is R , the reference lateral acceleration of the vehicle can be obtained as
a y d e s   =   v x 2 R   =   v x r ˙ d e s
The actual lateral acceleration of the UAV is
a y   =   v ˙ y   +   v x r
Combining Equations (18) and (19), the lateral acceleration deviation can be obtained as
e ¨ y   =   v ˙ y   +   v x ψ ˙ ψ ˙ d e s
Combining Equations (16)–(20), the following state space equation is obtained.
X ˙   =   A X   +   B U
Among them,
A   =   0 1 0 0 0 c f   +   2 c b m v x c f   +   2 c b m c f l f 2 c b l b m v x 0 0 0 1 0 c f l f 2 c b l b I z v x c f l f 2 c b l b I z c l l l 2   +   2 c b l b 2 I z v x X   =   e y e y e ψ e ˙ ψ ; B   =   0 c f m 0 c f l f I z ; U   =   δ f

3.1.3. Uncertainty Analysis of Path Tracking Model

In fact, the path tracking model is a typical uncertain system, where uncertainties not only include external random disturbances but also internal parameter perturbations, imprecise side-slip stiffness, and other issues. In this paper, when establishing the path tracking model, some ideal assumptions were made to simplify the calculation, and the influences of ψ ˙ d e s and ψ ¨ d e s were ignored at the end, which might cause steady-state errors.
Therefore, considering these uncertainties, the path tracking model can be rewritten in the following form:
X ˙   =   ( A   +   A ) X   +   ( B   +   B ) U   +   d
In the equation, A , B represents the unknown time-varying function matrix of parameter uncertainty, and d is the external disturbance corresponding to the random road.

3.1.4. Design of LQR Controller

In this section, the design of the LQR controller is based on the standard model (Equation (21)), ignoring the influence of parameter uncertainties and external disturbances, that is, A , B , d both are 0.
The purpose of the LQR controller is not only to reduce the path tracking deviation of the UAV, but also to keep the control input as small as possible to ensure the stability of the UAV’s taxiing. Therefore, the following objective function is defined:
J ( x )   =   t   =   0 x T Q x   +   u T R u
Based on the principle of the LQR controller, the following initial optimal control law is designed to minimize the optimal objective function (as shown in Equation (24)):
u *   =   K x
where K is the feedback control gain, which is obtained from the following equation:
K   =   R 1 B T P
P is the solution to the following Riccati equation:
P   =   A T P B R   +   B T P B 1 B T P A   +   A T P A   +   Q
Substituting Equations (25) and (26) into Equation (21), the closed-loop dynamic system is obtained as
x ˙   =   ( A B R 1 B T P ) x

3.2. Design of Integral Sliding Mode Controller

According to the LQR optimal control theory, the optimal controller u * can make the system asymptotically stable and satisfy the optimality of Equation (24). However, for the system (Equation (23)) with parameter uncertainties and external disturbances, the LQR controller may produce steady-state errors or even fail to converge. Inspired by Ref. [16], the following integral sliding mode controller is designed to ensure that the dynamic response of the uncertain UAV taxiing system is the same as that of the expected standard system.

3.2.1. Design of Integral Sliding Mode Surface

Firstly, the following integral sliding surface is designed:
s ( t )   =   H x ( t )   +   ϕ ( x ( t ) , u * ( t ) )
ϕ ˙ ( t )   =   H [ ( A B R 1 B T P ) x ( t ) ]
Here, H is a given constant matrix that satisfies H B 0 .
The integral sliding mode surface is designed such that the system is on the sliding mode surface ( s ( 0 )   =   0 ) at the initial moment, eliminating the reaching phase of the traditional SMC. While retaining the strong robustness of the traditional sliding mode control, it effectively solves the core problems such as insufficient steady-state accuracy, excessive chattering.
In the case of a real taxiing of the UAV, all the A , B , d in Equation (23) are bounded, and the following equation can be obtained:
A ( x , t )   =   B A ˜ ( x , t ) B ( x , t )   =   B B ˜ ( x , t ) d ( x , t )   =   B d ˜ ( x , t )
The physical significance of this equation lies in that if both the parameter uncertainty and the external disturbance are bounded, then the influence of the two can be counteracted or weakened by adopting an appropriate control strategy, thereby enhancing the robustness of the closed-loop system.
Based on the above assumptions, the total sum of the uncertainty and disturbance η ( x , t ) is defined as follows:
η ( x , t )   =   A ˜ ( x , t ) x ( t )   +   B ˜ ( x , t ) u ( t )   +   d ˜ ( x , t ) .
Each part of η ( x , t ) is bounded, and so is η ( x , t ) . Therefore, the following equation can be obtained:
η ( x , t ) σ 1 x ( t )   +   σ 0
Here, σ 0 , σ 1 are normal constants.
Theorem 1. 
For the uncertain system as shown in Equation (23), when the sliding mode surface is designed as in Equations (29) and (30), the dynamic characteristics of the controlled system are independent of the external random disturbances and parameter uncertainties when the system state operates on this sliding mode surface.
Proof of Theorem 1. 
According to Equations (29) and (30), we can obtain s ˙ ( t )
s ˙ ( t )   =   H x ˙ ( t ) H A B R 1 B T P x ( t ) =   H { [ A   +   A ] x ( t )   +   [ B   +   B ] u ( t )   +   d B u ( t ) } H A x ( t )   +   H B R 1 B T P x ( t ) =   H A x ( t )   +   H A x ( t )   +   H B u ( t )   +   H B u ( t ) +   H d B u ( t ) H A x ( t )   +   H B R 1 B T P x ( t ) =   H B u ( t )   +   H A x ( t )   +   H B u ( t )   +   H d ( x , t )   +   H B R 1 B T P x ( t )
Letting s ˙ ( t )   =   0 , the equivalent control term u e q can be obtained as
u e q   =   H B   +   B 1 H B R 1 B T P   +   A x ( t )   +   H d ( x , t )
Substituting Equation (35) into Equation (23), we obtain
x ˙ ( t )   =   [ A   +   A ] x ( B   +   B ) [ H ( B   +   B ) ] 1 ×   H B R 1 B T P x   +   H A x   +   H d ( x , t )   +   d ( x , t ) =   ( A   +   B A ˜ ) x ( B   +   B ˜ ) [ H ( B   +   B B ˜ ) ] 1 ×   H B R 1 B T P x   +   H B A x   +   H B d ˜ ( x , t )   +   B d ˜ ( x , t ) =   ( A B R 1 B T P ) x
The final result is the same as Equation (28), and the proof is complete. □

3.2.2. Design of Sliding Mode Control Law

Theorem 2. 
For the uncertain system in Equation (23), if the sliding surface is designed as shown in Equations (29) and (30), and the sliding mode controller is designed as in Equations (37) and (38), then the state trajectory of the controlled system will reach the specified integral sliding surface within a finite time and will continue to move along the integral sliding surface.
u   =   u * ρ ( x ) sgn ( s )
ρ ( x )   =   ( H B ) 1 σ   +   σ 0 H B   +   σ 1 H B x
Among them, σ is a normal constant.
Proof of Theorem 2. 
To conduct the Lyapunov stability proof, define the Lyapunov function as follows:
V   =   1 2 s 2
Obtainable:
V ˙   =   s s ˙ =   s H x ˙ H A B R 1 B T P x =   s H [ ( A   +   A ) x   +   ( B   +   B ) u   +   d ] s H A B R 1 B T P x =   s H B u   +   H A x   +   H B u   +   H d   +   H B R 1 B T P x
Substituting Equations (37) and (38) into Equation (40), we obtain
V ˙   =   s H B R 1 B T P x s H B H B 1 σ   +   σ 0 H B   +   σ 1 H B x s g n s +   s H B η   +   H B R 1 B T P x =   s σ s g n s s σ 0 H B   +   σ 1 H B x s g n s   +   s H B η
V ˙ s σ s g n s s σ 0 H B   +   σ 1 H B x s g n s +   s H B ( σ 1 x ( t )   +   σ 0 ) σ s 0
According to the Lyapunov stability proof, the system is asymptotically stable. □

3.3. Design of ANFIS-LQR Controller

The LQR controller contains two weight matrices, Q and R, which are expressed as follows:
Q   =   d i a g ( [ q 1 , q 2 , q 3 , q 4 ] ) R   =   [ r ]
Among them, q 1 , q 2 , q 3 , q 4 are the weight parameters of lateral deviation, lateral velocity deviation, heading deviation, and heading angular velocity deviation, respectively; r is the weight parameter of the front wheel steering angle.
And Q, R are the error weight matrix and control weight matrix, respectively. The larger the weight parameters, the stronger the constraint on the corresponding variables. The larger the error weight parameters, the higher the control accuracy; the larger the control weight parameters, the greater the control amount of the front wheel steering angle, and the better the stability of the UAV during taxiing.
In the actual taxiing scenario of UAVs, complex environmental dynamics (such as speed fluctuations and lateral/longitudinal deviations) can significantly interfere with the performance of the path tracking controller. Traditional LQR controllers with fixed weights are limited in their effectiveness due to their inability to dynamically respond to state changes, while conventional fuzzy control is difficult to precisely handle multi-state coupling problems and relies on empirical rule bases. Therefore, this study proposes an LQR weight parameter adaptive strategy based on ANFIS, which optimizes control parameters in real time to adapt to different working conditions, thereby enhancing the tracking robustness of the UAV under complex conditions.

3.3.1. Dataset Construction Based on PSO

To address the issue of the difficulty in obtaining the massive data required for ANFIS training through actual experiments, this paper uses the PSO (Particle Swarm Optimization) algorithm for multi-condition simulation to construct a dataset with the UAV’s speed and initial lateral/longitudinal deviations as inputs and the optimal LQR weight parameters as outputs. This method replaces physical experiments with numerical simulations to generate a sample library covering different driving scenarios at low cost, providing reliable data support for subsequent ANFIS model training.
The selection of PSO hyperparameters is based on the classic parameter combinations proposed in Ref. [25] and empirical adjustments, aiming to strike a balance between computational efficiency and solution quality, thereby adapting to our specific problem. The values were chosen as follows: a swarm size of 50 was selected to ensure adequate exploration of the search space without excessive computational cost; cognitive c 1 and social c 2 learning factors were both set to 1.5 to maintain a balance between individual particle experience and swarm collaboration; and the inertia weight ω was linearly decreased from 0.9 to 0.4 over the course of the optimization to transition from global exploration to local exploitation. The maximum number of iterations was set to 200, which was determined to be sufficient for convergence based on preliminary trials where the best fitness value was observed to stabilize. The PSO parameter setting table is shown in Table 1.
The input/output parameters of the dataset are shown in Table 2.
The optimization scenario is shown in Figure 8. Given the initial lateral/heading deviation, the UAV tracks the target trajectory at a constant longitudinal speed:
The optimization objective is as shown in Equation (44): throughout the entire process where the deviation converges completely to 0, the cumulative lateral/heading deviation and the energy consumption of the steering control are minimized.
J   =   t   =   0 t e k 1 e y 2   +   k 2 e ψ 2   +   k 3 u 2 d t
Here, t e represents the time for the complete convergence of the UAV’s lateral/heading deviation, and k 1 , k 2 , k 3 are fixed parameters.
The weighting coefficients k 1 , k 2 , k 3 in the PSO optimization objective (Equation (44)) critically influence the balance between path-tracking accuracy and control effort in the resulting optimal parameters. To determine these coefficients systematically, Bryson’s principle [26] was first applied to provide nondimensionalization and an initial setting. This rule suggests setting each weight as the reciprocal of the square of the maximum acceptable value of the corresponding variable:
k 1 1 e y , max 2 k 2 1 e ψ , max 2 k 3 1 u max 2
where e y , max and e ψ , max denote the maximum tolerable lateral and heading deviations, respectively, and u max represents the maximum expected control input. These values were estimated from system constraints and preliminary simulations. This initial scaling ensures that all terms in the cost function are of comparable numerical magnitude, thereby preventing any single term from dominating the optimization process purely due to differences in scale.
Subsequently, the coefficients were further refined through manual tuning to achieve the desired performance trade-off aligned with the UAV taxiing requirements. A sensitivity analysis was performed by varying these coefficients around their selected values. The following results demonstrate that the optimization outcome remains robust under small perturbations in the weights, confirming the validity of the selected parameters.
Performance comparison of different weighting coefficient sets in the PSO optimization is shown in Figure 9. This figure compares three sets of weighting coefficients for the PSO optimization objective. The Initial Parameters, set using Bryson’s principle, provide a balanced baseline. The Higher-Accuracy Parameters prioritize tracking precision by increasing the weights on path deviation terms, while the Energy-Saving Parameters reduce control effort by increasing the penalty on actuator usage. The results show that the higher-accuracy parameters yield faster convergence at the cost of introducing minor oscillations, while the energy-saving parameters produce smoother responses but converge more slowly. All three parameter sets, however, ultimately achieve convergence. These outcomes demonstrate the inherent design trade-off between accuracy and energy consumption, confirming the robustness of our method across different performance objectives.

3.3.2. ANFIS Network Structure

Based on the ANFIS, the parameter dataset generated by PSO is trained to construct an intelligent mapping model with speed and lateral/heading deviation as inputs and LQR optimal weight parameters (Q/R) as outputs, achieving adaptive matching of control parameters and dynamic conditions.
ANFIS combines the advantages of FLS (Fuzzy Logic System) and ANN (Artificial Neural Network), training the model’s antecedent and consequent parameters using the least squares method and gradient descent algorithm. Through the fuzzy algorithm process (fuzzification, fuzzy inference, defuzzification), it outputs results close to the actual values, adaptively learning the input-output relationship. Meanwhile, the fuzzy rules can be obtained through the consequent parameters and mapping relationship of the fuzzy neural network, constructing a “IF-THEN” form of parameter adjustment knowledge base. This provides interpretable guidance suggestions for manual parameter adjustment in UAV taxiing tests. The ANFIS network structure is shown in Figure 10.
Layer 1, the membership degree layer, represents the fuzzification of input variables. If a variable x i is described by m i fuzzy terms, then there are i   =   1 n m i x i nodes in the membership degree layer. The output of each node in the membership degree layer is calculated as
O i , j 1   =   μ A i , j x i , i   =   1 , 2 , , n , j   =   1 , 2 , , m i
The rule layer (Layer 2) realizes the connection between the preceding variables and calculates the triggering intensity of each rule. The calculation of the rule layer nodes is as follows:
O k 2   =   w k   =   A i , j μ A i , j x i , A i , j A k , k   =   1 , 2 , , K
In the formula, K represents the number of rules, w k represents the trigger strength of the k rule, and A k represents the membership degree of the precondition in the k rule.
The normalization layer (Layer 3) performs a normalization operation on the rule trigger strength, and its node calculation is as follows:
O k 3   =   w ¯ k   =   w k / k   =   1 K w k
The conclusion layer (Layer 4) performs the calculation of the linear combination of the input in the conclusion part of the TSK fuzzy rule. The calculation method of its nodes is as follows:
O k 4   =   y k   =   w ¯ k c k , 0   +   c k , 1 x 1   +   c k , i x i   +   c k , n x n   =   w ¯ k c k x
In the formula, c k , i represents the linear parameter of the k rule, and y k represents the conclusion value of the k rule.
The summary layer (Layer 5) sums up all the conclusion variables in the rules.
O 5   =   k   =   1 K w ¯ k c k x
To prevent overfitting and ensure the generalization capability of the ANFIS model, a structured data management strategy was implemented. The dataset generated through offline PSO simulations was partitioned into three distinct subsets: a training set (70%) used for model parameter learning, a validation set (15%) employed for hyperparameter tuning and early stopping monitoring, and a test set (15%) reserved exclusively for final performance evaluation. Additionally, the complexity of the ANFIS architecture was constrained by limiting the number of membership functions and fuzzy rules. During the training process, the validation error was continuously monitored, and early stopping was triggered when the validation performance ceased to improve for a predetermined number of consecutive epochs. This comprehensive approach effectively prevents the model from memorizing noise in the training data while ensuring robust performance on unseen data.
Prior to integrating the trained ANFIS model into the closed-loop controller, its predictive performance was rigorously evaluated on the held-out test set (15% of the total data) using standard regression metrics. The Root Mean Square Error (RMSE) quantifies the average magnitude of prediction errors, while the Coefficient of Determination (R2) represents the proportion of variance in the target variable explained by the model. The performance metrics for each output parameter are summarized in Table 3.
The high R2 values (all exceeding 0.91) and low RMSE values demonstrate that the ANFIS model has successfully learned the underlying nonlinear mapping from the UAV states to the optimal controller parameters with high accuracy and strong generalization capability. This confirms the model’s reliability and justifies its integration into the adaptive control framework.
The robust optimal path tracking controller proposed in this paper is divided into three parts: 1. Initial standard optimal LQR controller, 2. Sliding mode controller, 3. ANFIS adaptive adjustment of LQR weight parameters. The initial optimal control makes the system (Equation (21)) have satisfactory optimal control performance. The sliding mode control can suppress uncertainties and disturbances, ensuring that the uncertain system (Equation (23)) operates on the specified integral sliding mode surface (Equation (29)) under uncertain conditions. When the uncertain system operates on the specified integral sliding mode surface, the dynamic trajectory of the uncertain path tracking system is the same as the expected optimal trajectory of the standard system, thereby achieving the optimal control goal. The closed-loop system is stable. ANFIS adaptively adjusts the LQR weight parameters according to the current state, enhancing the robustness of the path tracking of the UAV in complex situations. The variables used in this article are summarized in two symbol tables, as shown in Appendix A.

4. Results

To verify the performance of the designed robust optimal controller for the UAV taxiing, simulations were conducted on the MATLAB R2022a platform. The object under study is a certain type of fixed-wing UAV independently developed by the research group. The research content focuses on the lateral-directional trajectory tracking control of the UAV during low-speed taxiing. The main relevant parameters of the UAV are listed in Table 4 and Table 5. (as the aerodynamic force is a minor factor during low-speed taxiing, meaning the aerodynamic parameter table is not presented here):
In accordance with the physical limitations of our self-developed UAV system, the front wheel was subject to both angle and rate constraints during all simulations. The maximum steering angle was limited to δ max   =   ± 45 , and the maximum steering rate was constrained to δ ˙ max   =   ± 60 / s . To accurately simulate the actual system’s dynamic response, a first-order filter was incorporated with appropriate frequency characteristics to smooth the steering commands, while the control system maintained an operating frequency of 25 Hz. These constraints were implemented through a comprehensive simulation architecture including saturation blocks and rate limiters, ensuring that all control signals generated by the evaluated controllers remained within physically realizable limits throughout all simulation scenarios. Monitoring confirmed that no controller violated these constraints in any of the reported results, ensuring the practical relevance and implementation feasibility of our control approach.

4.1. Simulation of ANFIS Adjusting the Weight Parameters of LQR

The simulation verifies the path tracking effect of ANFIS adaptive adjustment of LQR weight parameters. Based on the LQR controller, the simulation effects of three methods, namely fixed weights, fuzzy adjustment of weights, and ANFIS adjustment of weights, are verified under different working conditions. The longitudinal velocity is controlled by PID.

4.1.1. Algorithm Setting

The parameters of ANFIS are set as follows: the input variables are longitudinal velocity v x , lateral deviation e y , and heading deviation e ψ , the output variable is the LQR weight parameters q 1 , q 2 , q 3 , q 4 , r 1 . Each variable corresponds to five fuzzy words, and the membership function is Gaussian. The consequent parameters are linear. The membership function parameters are adjusted by the gradient descent method, and the linear parameters of the consequent are adjusted by the least squares method.
To assess the impact of membership function choice on model performance, a comparative study was conducted using RMSE and R2 metrics. Table 6 shows the performance comparison between Gaussian and triangular membership function models (both with five fuzzy subsets per input variable) evaluated on a standardized test set:
The results indicate that both membership function types achieve statistically similar performance levels across all output parameters, with differences in RMSE and R2 values being marginal (less than 3% relative difference). This analysis confirms that the model performance is robust to the choice between these membership function types for this particular application. The Gaussian functions were ultimately selected to maintain consistency with the reference implementation [18] used for comparative analysis.
The training dataset is generated through the particle swarm algorithm. The number of samples in the training set is 1000, and the training rounds are 50.
The fuzzy algorithm is set as follows: referring to the Ref. [18], q 2 , q 3 , q 4 is set as fixed value, and q 1 , r 1 are adaptively adjusted through the change in speed. The input variable of the fuzzy adjustment is the speed v x , and the output variable is the adjustment amount of the control coefficient q 1 , r 1 .
The fuzzy language variable set is divided into five fuzzy subsets: negative large (NB), negative small (NS), zero (O), positive small (PS), and positive large (PB). The membership function is a Gaussian function, and the defuzzification method adopts the center of gravity method. The input and output membership functions and fuzzy rules are shown in the Figure 11 and Table 7.

4.1.2. Initial 2 m Lateral Deviation Condition at 10 m/s Taxiing Speed

The taxiing speed of the UAV is set at 10 m/s, with an initial lateral deviation of 2 m, and it tracks a straight path. The simulation results are shown in Figure 12.
Figure 12a shows the taxiing trajectories of the UAV under different control methods. It can be seen that all methods can track the expected trajectory, but the overshoot of ANFIS-LQR is smaller than that of the other methods. Figure 12b shows the variation curve of the front wheel angle of the UAV with time. Figure 12c,d, respectively, show the variation curves of the lateral and heading deviations of the UAV with time. All subsequent simulation results in this paper are in this form. The specific simulation results are shown in Table 8.
It can be seen that under this working condition, the ANFIS-LQR method has the highest tracking accuracy and the best stability, with the maximum front wheel angle and the maximum lateral/heading deviation both being smaller than those of the other two methods. Among them, the tracking accuracy of the Fuzzy-LQR is even lower than that of the fixed-weight LQR, indicating that merely adjusting the LQR state parameters based on speed is not sufficient and may even have a counterproductive effect.

4.1.3. Initial 2 m Lateral Deviation Condition at 15 m/s Taxiing Speed

The taxiing of the UAV is set at 15 m/s, with an initial lateral deviation of 2 m, and it tracks a straight path. The simulation results are shown in Figure 13 and Table 9.
According to the parameter settings of the fuzzy algorithm, the optimal parameters are achieved when the UAV speed is 15 m/s. Under this condition, compared with the fixed-weight LQR, the Fuzzy-LQR shows significant improvements in tracking accuracy and stability. However, it is still slightly inferior to the ANFIS-LQR. This discrepancy arises because the conventional fuzzy algorithm solely accounts for velocity variations, while neglecting the coupled influence between speed, lateral deviation, and heading deviation on the optimal weight parameters. Moreover, there may be limitations in the completeness of the fuzzy rules.

4.1.4. Circular Trajectory Tracking at 5 m/s Taxiing

The taxiing trajectory of the UAV in the airport runway scenario only needs to track straight line segments or quarter circular arc segments (turning segments). Therefore, the following working conditions are designed: the taxiing speed of the UAV is set at 5 m/s, with no initial lateral or longitudinal deviation. After tracking the quarter circular arc of the turning segment, it tracks the straight path. The simulation results are shown in Figure 14 and Table 10.
Neither LQR nor Fuzzy-LQR can track the circular route well. The lateral deviation increases over time. Although the maximum front wheel angle of the ANFIS-LQR method is greater than that of the other two methods, it still has a relatively high stability (acceptable) of the UAV when turning at a low speed of 5 m/s. Moreover, both the maximum lateral heading deviation and the steady-state value are smaller, demonstrating the superiority of this method.

4.2. Simulation of Compensation Effect of Sliding Mode Control

To verify the robustness and superiority of the designed robust optimal controller, a simulation comparison analysis was conducted. A sliding mode compensation control was added on the basis of the ANFIS-LQR controller. The parameters of the sliding mode controller are shown in Table 11.

4.2.1. Non-Interference Condition

The working conditions are divided into straight sections and turning sections, which are the same as those described in Section 4.1.2 and Section 4.1.4. The simulation results under the non-interference condition are consistent with those of LQR, Fuzzy-LQR, and ANFIS-LQR in Section 4.1.2 and Section 4.1.4. On this basis, the simulation results of ANFIS-SMC-LQR are added for comparison, mainly to verify the improvement in the anti-interference performance of the controller after the addition of sliding mode control. Readers can focus on the comparison of the results between ANFIS-SMC-LQR and ANFIS-LQR. The simulation results are shown in Figure 15 and Figure 16 and Table 12 and Table 13.
For the undisturbed working condition, the performance characteristics differ between straight-line and circular trajectory tracking. In straight-line tracking, the addition of sliding mode control maintains superior tracking accuracy and stability compared to the ANFIS-LQR method, though with slightly slower response speed. However, in circular trajectory tracking, the ANFIS-LQR method demonstrates better tracking accuracy as evidenced by its smaller maximum heading deviation (3.74° vs. 5.01° in Table 13). This difference arises from the control smoothing strategy employed in our SMC design: to suppress the high-frequency chattering inherent in sliding mode control, a saturation function is used to smooth the control signal, which reduces the high-frequency control bandwidth and sacrifices some response speed. While this trade-off results in marginally reduced tracking performance for high-curvature trajectories under ideal conditions, it enables significantly superior performance in realistic operational scenarios with disturbances and model uncertainties, particularly in maintaining stability and consistency across varying taxiing conditions.
To quantitatively assess these performance characteristics and provide a comprehensive comparison of the controllers’ dynamic response, we evaluated standard performance metrics including rise time, settling time, and steady-state error under both straight-line and circular trajectory tracking scenarios. The results are summarized in Table 14.
The quantitative performance metrics presented in Table 14 provide detailed insight into the response characteristics of each controller under different tracking scenarios. For straight-line tracking, while the ANFIS-SMC-LQR controller exhibits a longer rise time (20.1 s) compared to ANFIS-LQR (11.2 s), it achieves a shorter settling time (30.5 s vs. 32.1 s) while maintaining zero steady-state error for both controllers. This indicates that although the initial response is slower due to the control smoothing strategy, the SMC-based controller reaches stable tracking more quickly.
For circular trajectory tracking, the ANFIS-SMC-LQR demonstrates superior performance with both a shorter settling time (1.63 s vs. 2.21 s) and reduced steady-state error (0.07 m vs. 0.11 m) compared to the ANFIS-LQR controller. This performance advantage is particularly valuable for curved path tracking where maintaining precise trajectory following is challenging.
These results demonstrate that while the SMC smoothing strategy moderately increases initial response time in straight-line tracking, it provides significant benefits in achieving faster overall stabilization and improved tracking accuracy, especially in curved trajectories. This trade-off is particularly beneficial for UAV taxiing operations where precise path tracking and stable control are prioritized over minimal initial response times.

4.2.2. Model Bias Condition

The LQR controller relies on an accurate mathematical model and is greatly affected by parameter uncertainties. To verify the robustness and anti-interference performance of the robust optimal controller after adding sliding mode control, the UAV model is perturbed based on the non-interference working condition. The specific perturbation parameters are shown in Table 15.
The simulation results of the tracking straight line segment are shown in Figure 17 and Figure 18 and Table 16 and Table 17.
The simulation results show that LQR and Fuzzy-LQR have completely lost control, and ANFIS-LQR also has relatively obvious oscillations. However, after adding the sliding mode control algorithm, the influence of model deviation on the control effect has been well suppressed, and the expected trajectory is tracked smoothly and with high precision. Moreover, the simulation results change little under both no disturbance and model deviation conditions, which proves the robustness of this method.

4.2.3. Friction Coefficient Disturbance Condition

Considering the uncertainty of the friction coefficient due to various road conditions such as wet and dry, cement and asphalt in reality, the random disturbance of the friction coefficient is introduced for simulation verification.
The variation graph of the sliding/rolling friction coefficient with longitudinal displacement is shown in Figure 19.
The simulation results are Figure 20 and Figure 21 and Table 18 and Table 19.
Similarly to the model bias condition, under the condition of adding random disturbances to the friction coefficient, the fixed-weight LQR, and Fuzzy-LQR out of control, the ANFIS-LQR generates oscillations with a relatively large steady-state error. The ANFIS-slide-LQR effectively suppresses the influence of random disturbances in the friction coefficient on the control effect, achieving stable and high-precision tracking of the expected trajectory.

5. Conclusions

In response to the insufficiency in balancing the optimality and robustness of the controller and the imperfection of the adaptive adjustment mechanism of the controller parameters, this study combines LQR optimal control with SMC to achieve a robust optimal controller, significantly enhancing the tracking accuracy and anti-interference ability of the controller. On this basis, by using ANFIS to learn the nonlinear mapping relationship between multiple state parameters such as speed, lateral/heading deviation during the taxiing process of the UAV and the weight matrix of the LQR controller, an adaptive adjustment mechanism of the controller parameters based on data-driven is realized to improve the tracking accuracy and anti-interference stability of the UAV taxiing.
The main contributions and conclusions of this study are summarized as follows:
  • Balancing optimality and robustness, a robust optimal controller considering parameter uncertainties is designed by adding sliding mode control to compensate for the control quantity on the basis of the LQR controller, solving the problem that the traditional LQR controller relies on an accurate model and improving the tracking accuracy and anti-interference stability of the UAV taxiing.
  • Through the particle swarm optimization algorithm, a dataset of LQR optimal parameters under multiple working conditions is generated in the simulation, and the fuzzy mapping rules between states and parameters are established based on ANFIS offline training, achieving the adaptive dynamic adjustment of the controller parameters according to the real-time state and avoiding the inefficiency of traditional manual trial-and-error parameter adjustment and the subjectivity of the adaptive method based on empirical rules.
  • The efficacy of the proposed robust optimal controller was validated through extensive simulations under various conditions. Under different working conditions such as model parameter deviation and random disturbance of friction coefficient, the control effect of the adaptive robust optimal controller proposed in this paper was significantly improved compared with that of the traditional controller.
While this study has demonstrated the effectiveness of the proposed adaptive robust optimal control framework for fixed-wing UAV ground taxiing, several promising directions warrant further investigation. First, the proposed control architecture could be extended to integrated lateral-directional flight control across various flight phases, where similar challenges of model uncertainty and disturbance rejection exist. Second, future work will focus on the implementation and validation of the proposed method through hardware-in-the-loop simulations and experimental taxiing tests to verify its practical efficacy. Additionally, we plan to explore the application of this framework to other UAV types and operational scenarios with high uncertainties and demanding robustness requirements, such as tilt-rotor UAV mode transition, multi-rotor UAV near-ground maneuvering, and flight under complex meteorological conditions or partial faults. Further improvements could include developing online learning mechanisms to allow continuous adaptation of the ANFIS network under varying conditions and investigating multi-UAV cooperative taxiing control schemes for swarm operations.

Author Contributions

Conceptualization, E.W.; methodology, P.W.; software, E.W.; validation, E.W. and P.W.; formal analysis, P.W.; resources, P.W.; data curation, P.W.; writing—original draft preparation, E.W.; writing—review and editing, E.W.; visualization, E.W.; supervision, P.W. and Z.G.; project administration, P.W.; funding acquisition, P.W. and Z.G. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Data Availability Statement

The original contributions presented in this study are included in the article. Further inquiries can be directed to the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

Appendix A

Table A1. Variable summary for landing gear dynamics modeling.
Table A1. Variable summary for landing gear dynamics modeling.
VariableDescriptionDimensionality
m Mass of the UAVkg
J x Moment of inertia about the x-axiskg · m2
J y Moment of inertia about the y-axiskg · m2
J z Moment of inertia about the z-axiskg · m2
J x z Product of inertia for the xz-planekg · m2
S Wing aream2
b Wingspanm
c Mean aerodynamic chordm
f Front landing gear-(dimensionless)
b l Left main landing gear-
b r Right main landing gear-
b Body coordinate system-
g Inertial coordinate system-
h f Front wheel heightm
h b Main wheel heightm
l f Distance from the center of gravity to the front wheelm
l b Distance from the center of gravity to the main wheelm
d b Main wheel widthm
r w f Front wheel radiusm
r w b Main wheel radiusm
k f Front landing gear stiffnessN/m
k b Main landing gear stiffnessN/m
c f Front landing gear damping coefficient-
c b Main landing gear damping coefficient-
C f Front wheel cornering stiffnessN/rad
C b Main wheel cornering stiffnessN/rad
v Relative velocitym/s
v x Longitudinal velocitym/s
v y Lateral velocitym/s
μ s Static friction coefficient-
μ c Coulomb friction coefficient-
ϕ Rollrad
θ Pitchrad
ψ Yawrad
F a , i Air spring forceN
F h , i Oil damping forceN
n G , i Axial force of the landing gearN
β f Side slip angles of the front wheelrad
β b side slip angles of the main wheelrad
δ f Front wheel rotation anglerad
r Yaw raterad/s
e y Lateral deviationm
e ψ Heading deviationrad
Table A2. Variable summary for controller design.
Table A2. Variable summary for controller design.
VariableDescription
X State vector
A System matrix
B Input matrix
U Input vector
d External disturbance
J Objective function
Q State weighting matrix
R Control weighting matrix
K Feedback control gain
P Riccati equation
s Integral sliding mode surface
H Constant matrix
η Total sum of the uncertainty and disturbance
V Lyapunov function

References

  1. Zhang, X.; Li, G.W. Research on the Ground Integrated Control Technology of Taxiing. J. Proj. Rocket. Missiles Guid. 2022, 42, 106–113. [Google Scholar]
  2. Wang, Y.; Wang, Y.X. Lateral Deviation Correction Control for UAV Taxiing. Acta Aeronaut. Astronaut. Sin. 2008, 29 (Suppl. S1), 142–149. [Google Scholar]
  3. Zhu, C.C.; Wang, B.W.; Liu, X.C. Research Statusand Prospect of Landing Gear Dynamics in Complex Environment. Aeronaut. Sci. Technol. 2023, 34, 1–11. [Google Scholar]
  4. Bai, R.; Wang, H.B. Robust Optimal Control for the Vehicle Suspension System with Uncertainties. IEEE Trans. Cybern. 2022, 52, 9263–9273. [Google Scholar] [CrossRef] [PubMed]
  5. Tourajizadeh, H.; Zare, S. Robust and Optimal Control of Shimmy Vibration in Aircraft Nose Landing Gear. Aerosp. Sci. Technol. 2016, 50, 1–14. [Google Scholar] [CrossRef]
  6. Wang, H.B.; Hu, C.L.; Cui, W. Multi-objective Comprehensive Control of Trajectory Tracking for Four-In-Wheel-Motor Drive Electric Vehicle with Differential Steering. IEEE Access 2021, 9, 62137–62154. [Google Scholar] [CrossRef]
  7. Elkhatem, A.S.; Engin, S.N. Robust LQR and LQR-PI Control Strategies Based on Adaptive Weighting Matrix Selection for a UAV Position and Attitude Tracking Control. Alex. Eng. J. 2022, 61, 6275–6292. [Google Scholar] [CrossRef]
  8. Nkemdirim, M.; Dharan, S.; Chaoui, H.; Miah, S. LQR Control of a 3-DOF Helicopter System. Int. J. Dyn. Control 2022, 10, 1084–1093. [Google Scholar] [CrossRef]
  9. Khosravi, M.; Azarinfar, H.; Sabzevari, K. Design of Infinite Horizon LQR Controller for Discrete Delay Systems in Satellite Orbit Control: A Predictive Controller and Reduction Method Approach. Heliyon 2024, 10, e24265. [Google Scholar] [CrossRef]
  10. Li, S.Q.; Qiu, J.; Ji, H.; Zhu, K.; Li, J. Piezoelectric Vibration Control for All-Clamped Panel Using DOB-Based Optimal Control. Mechatronics 2011, 21, 1213–1221. [Google Scholar] [CrossRef]
  11. Zhang, H.F.; Wei, X.J.; Han, J.J.; Hu, X.; Han, J. Finite-time control for systems subject to multiple disturbances. J. Control Decis. 2025, 12, 142–149. [Google Scholar] [CrossRef]
  12. Ekechi, C.C.; Elfouly, T.; Alouani, A.; Khattab, T. A survey on UAV control with multi-agent reinforcement learning. Drones 2025, 9, 484. [Google Scholar] [CrossRef]
  13. Wang, Y.N.; Hua, H. Performance function-guided deep reinforcement learning control for UAV swarm. Zidonghua Xuebao Acta Autom. Sin. 2025, 51, 905–916. [Google Scholar]
  14. Mahmood, A.; Rehman, U. Neural adaptive sliding mode control for camera positioner quad-rotor UAV. Int. J. Aeronaut. Space Sci. 2025, 26, 733–747. [Google Scholar] [CrossRef]
  15. Korobiichuk, I.; Shevchuk, L. Synthesis of an intelligent UAV control system based on fuzzy logic in external disturbance conditions. J. Autom. Mob. Robot. Intell. Syst. 2020, 14, 3–9. [Google Scholar] [CrossRef]
  16. Wang, L.; Zhang, Z.; Zhu, Q.; Wen, Z. Longitudinal Automatic Carrier-Landing Control Law Rejecting Disturbances and Coupling Based on Adaptive Dynamic Inversion. Bull. Pol. Acad. Sci. Tech. Sci. 2021, 69, e136217. [Google Scholar] [CrossRef]
  17. Reddy, M.M.; Varma, P.S.; Lenine, D. Improving Gain of Real Time PI Controller Using Particle Swarm Optimization in Active Power Filter. Microprocess. Microsyst. 2023, 97, 104760. [Google Scholar] [CrossRef]
  18. Wang, B.H.; Zhang, J.C.; Zhang, Y. The Direct Yaw-moment Control Based on Adaptive Fuzzy LQR for Distributed Drive Electric Vehicles. Adv. Mech. Eng. 2024, 16, 12. [Google Scholar] [CrossRef]
  19. Gaikwad, P.; Mukhopadhyay, A.; Muraleedharan, A.; Mitra, M.; Biswas, P. Developing a computer vision based system for autonomous taxiing of aircraft. Aviation 2023, 27, 248–258. [Google Scholar] [CrossRef]
  20. Nkemdirim, C.M.; Alzayed, M.; Chaoui, H. Linear quadratic Gaussian control of a 6-DOF aircraft landing gear. Energies 2023, 16, 6902. [Google Scholar] [CrossRef]
  21. Zhang, P.F.; Wang, Z.L.; Zhu, Z.W.; Liang, Q.; Luo, J. Enhanced multi-UAV formation control and obstacle avoidance using IAAPF-SMC. Drones 2024, 8, 514. [Google Scholar] [CrossRef]
  22. Saleem, O.; Kazim, M.; Iqbal, J. Robust position control of VTOL UAVs using a linear quadratic rate-varying integral tracker: Design and validation. Drones 2025, 9, 73. [Google Scholar] [CrossRef]
  23. Xin, H.B.; Chen, Q.Y.; Wang, P. 3D Dynamic Modelling and Constraints Analysis of Taxiing Deviation Correction Control. Chin. J. Aeronaut. 2024, 45, 277–294. [Google Scholar]
  24. Bo, L.C.; Pavelescu, D. The Friction-Speed Relation and Its Influence on the Critical Velocity of Stick-Slip Motion. Wear 1982, 82, 277–289. [Google Scholar]
  25. Liu, X.F.; Chen, T. Study on Convergence Analysis and Parameter Choice of Particle Swarm Optimization. Comput. Eng. Appl. 2007, 439, 14–17. [Google Scholar] [CrossRef]
  26. Bryson, A.E.; Ho, Y.-C. Applied Optimal Control, Optimization, Estimation, and Control; John Wiley & Sons: New York, NY, USA, 1975; pp. 1–481. [Google Scholar]
Figure 6. 2-DOF landing gear lateral model.
Figure 6. 2-DOF landing gear lateral model.
Drones 09 00668 g006
Figure 7. Path tracking model.
Figure 7. Path tracking model.
Drones 09 00668 g007
Figure 8. PSO-optimized dataset generation scenarios.
Figure 8. PSO-optimized dataset generation scenarios.
Drones 09 00668 g008
Figure 9. Performance comparison of different weighting coefficient sets in the PSO optimization.
Figure 9. Performance comparison of different weighting coefficient sets in the PSO optimization.
Drones 09 00668 g009
Figure 10. The structure of ANFIS network.
Figure 10. The structure of ANFIS network.
Drones 09 00668 g010
Figure 11. Input and output membership functions: (a) Membership function of v x ; (b) Membership function of q 1 ; (c) Membership function of r 1 .
Figure 11. Input and output membership functions: (a) Membership function of v x ; (b) Membership function of q 1 ; (c) Membership function of r 1 .
Drones 09 00668 g011
Figure 12. Simulation results of the 10 m/s taxiing speed and initial 2 m lateral deviation condition: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Figure 12. Simulation results of the 10 m/s taxiing speed and initial 2 m lateral deviation condition: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Drones 09 00668 g012
Figure 13. Simulation results of the 15 m/s taxiing speed and initial 2 m lateral deviation condition: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Figure 13. Simulation results of the 15 m/s taxiing speed and initial 2 m lateral deviation condition: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Drones 09 00668 g013
Figure 14. Simulation results of circular trajectory tracking during turning at a taxiing speed of 5 m/s: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Figure 14. Simulation results of circular trajectory tracking during turning at a taxiing speed of 5 m/s: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Drones 09 00668 g014
Figure 15. Simulation results of straight trajectory tracking under non-interference conditions: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Figure 15. Simulation results of straight trajectory tracking under non-interference conditions: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Drones 09 00668 g015
Figure 16. Simulation results of circular trajectory tracking under non-interference conditions: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Figure 16. Simulation results of circular trajectory tracking under non-interference conditions: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Drones 09 00668 g016
Figure 17. Simulation results of straight trajectory tracking under model bias conditions: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Figure 17. Simulation results of straight trajectory tracking under model bias conditions: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Drones 09 00668 g017
Figure 18. Simulation results of circular trajectory tracking under model bias conditions. (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Figure 18. Simulation results of circular trajectory tracking under model bias conditions. (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Drones 09 00668 g018
Figure 19. The sliding/rolling friction coefficient varies with the forward distance: (a) Sliding friction coefficient; (b) Rolling friction coefficient.
Figure 19. The sliding/rolling friction coefficient varies with the forward distance: (a) Sliding friction coefficient; (b) Rolling friction coefficient.
Drones 09 00668 g019
Figure 20. Simulation results of straight trajectory tracking under friction coefficient disturbance conditions: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Figure 20. Simulation results of straight trajectory tracking under friction coefficient disturbance conditions: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Drones 09 00668 g020
Figure 21. Simulation results of circular trajectory tracking under friction coefficient disturbance conditions: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Figure 21. Simulation results of circular trajectory tracking under friction coefficient disturbance conditions: (a) The taxiing trajectories of the UAV under different control methods; (b) The variation curve of the front wheel angle of the UAV with time; (c) The variation curves of the lateral deviations of the UAV with time; (d) The variation curves of the heading deviations of the UAV with time.
Drones 09 00668 g021
Table 1. PSO hyperparameters.
Table 1. PSO hyperparameters.
HyperparameterValue
Swarm size N 50
Cognitive factor c 1 1.5
Social Factor c 2 1.5
Inertia Weight ω 0.9 0.4
Maximum Iterations200
Table 2. Input/output parameters.
Table 2. Input/output parameters.
Input Output
v x /m/s r 1
e y /m q 1
e ψ /(kg · m2) q 2
q 3
q 4
Table 3. ANFIS model performance metrics on test set.
Table 3. ANFIS model performance metrics on test set.
Output ParameterRMSER2
q 1 0.0780.943
q 2 0.1150.928
q 3 0.0920.937
q 4 0.1210.919
r 1 0.0850.951
Table 4. UAV geometric parameters.
Table 4. UAV geometric parameters.
ParameterValue
Mass m/kg19.66
Inertia moment Jx/(kg · m2)3.70
Inertia moment Jy/(kg · m2)6.45
Inertia moment Jz/(kg · m2)3.20
Inertia moment Jxz/(kg · m2)0.04
Wing area S/m20.85
Wingspan b/m3.2
Mean aerodynamic chord c/m0.33
Table 5. Landing gear parameters.
Table 5. Landing gear parameters.
ParameterValue
Front wheel height hf/m0.379
Main wheel height hb/m0.391
Distance from the center of gravity to the front wheel lf/m0.504
Distance from the center of gravity to the main wheel lb/m0.118
Main wheel width db/m0.54
Front wheel radius rwf/m0.035
Main wheel radius rwb/m0.0437
Front landing gear stiffness kf/N/m1000
Main landing gear stiffness kb/N/m1500
Front landing gear damping coefficient cf20
Main landing gear damping coefficient cb30
Front wheel cornering stiffness Cf/N/rad100
Main wheel cornering stiffness Cb/N/rad150
Table 6. Performance comparison of different membership functions.
Table 6. Performance comparison of different membership functions.
Output ParameterGaussian MFTriangular MF
RMSER2RMSER2
q 1 0.0780.9430.0810.939
q 2 0.1150.9280.1190.924
q 3 0.0920.9370.0950.934
q 4 0.1210.9190.1240.916
r 1 0.0850.9510.0880.948
Table 7. Fuzzy algorithm settings.
Table 7. Fuzzy algorithm settings.
VariableFuzzy Subset
v x NBNSOPSPB
q 1 PBPSONSNB
r 1 NBNSOPSPB
Table 8. Simulation results of the 10 m/s taxiing speed and initial 2 m lateral deviation condition.
Table 8. Simulation results of the 10 m/s taxiing speed and initial 2 m lateral deviation condition.
Control MethodMaximum Front Wheel Angle/DegreesLateral Deviation OvershootMaximum Heading Deviation/Degrees
LQR22.218.3%17.7
Fuzzy-LQR28.025.1%18.8
ANFIS-LQR20.44.2%16.2
Table 9. Simulation results of the 15 m/s taxiing speed and initial 2 m lateral deviation condition.
Table 9. Simulation results of the 15 m/s taxiing speed and initial 2 m lateral deviation condition.
Control MethodMaximum Front Wheel Angle/DegreesLateral Deviation OvershootMaximum Heading Deviation/Degrees
LQR22.424.1%15.2
Fuzzy-LQR21.913.1%14.3
ANFIS-LQR20.58.6%14.0
Table 10. Simulation results of circular trajectory tracking during turning at a taxiing speed of 5 m/s.
Table 10. Simulation results of circular trajectory tracking during turning at a taxiing speed of 5 m/s.
Control MethodMaximum Front Wheel Angle/DegreesLateral Deviation OvershootMaximum Heading Deviation/Degrees
LQR26.80.314.12
Fuzzy-LQR22.30.525.62
ANFIS-LQR32.00.163.74
Table 11. Sliding mode control parameters.
Table 11. Sliding mode control parameters.
ParameterValue
H [1,1,1,1]
σ 5
σ 0 0.1
σ 1 0.1
Table 12. Simulation results of straight trajectory tracking under non-interference conditions.
Table 12. Simulation results of straight trajectory tracking under non-interference conditions.
Control MethodMaximum Front Wheel Angle/DegreesLateral Deviation OvershootMaximum Heading Deviation/Degrees
LQR22.218.3%17.7
Fuzzy-LQR28.025.1%18.8
ANFIS-LQR20.44.2%16.2
ANFIS-SMC-LQR22.12.1%10.5
Table 13. Simulation results of circular trajectory tracking under non-interference conditions.
Table 13. Simulation results of circular trajectory tracking under non-interference conditions.
Control MethodMaximum Front Wheel Angle/DegreesLateral Deviation OvershootMaximum Heading Deviation/Degrees
LQR26.80.314.12
Fuzzy-LQR22.30.525.62
ANFIS-LQR32.00.163.74
ANFIS-SMC-LQR32.00.155.01
Table 14. Quantitative performance comparison of controller response characteristics.
Table 14. Quantitative performance comparison of controller response characteristics.
Control MethodTrajectoryRise Time/sSettling Time/sLateral Steady-State Error/m
ANFIS-LQRStraight-line11.232.10
ANFIS-SMC-LQRStraight-line20.130.50
ANFIS-LQRCircular/2.210.11
ANFIS-SMC-LQRCircular/1.630.07
Table 15. Model parameter bias table.
Table 15. Model parameter bias table.
ParameterBias Value
Cf/N/rad+20%
Cb/N/rad−20%
m/kg+10%
Jz/(kg · m2)−10%
Table 16. Simulation results of straight trajectory tracking under model bias conditions.
Table 16. Simulation results of straight trajectory tracking under model bias conditions.
Control MethodMaximum Front Wheel Angle/DegreesLateral Deviation OvershootMaximum Heading Deviation/Degrees
LQR45//
Fuzzy-LQR45//
ANFIS-LQR21.328.1%29.2
ANFIS-SMC-LQR13.73.2%13.5
Table 17. Simulation results of circular trajectory tracking under model bias conditions.
Table 17. Simulation results of circular trajectory tracking under model bias conditions.
Control MethodMaximum Front Wheel Angle/DegreesLateral Deviation OvershootMaximum Heading Deviation/Degrees
LQR45//
Fuzzy-LQR45//
ANFIS-LQR25.10.427.12
ANFIS-SMC-LQR32.00.163.76
Table 18. Simulation results of straight trajectory tracking under friction coefficient disturbance conditions.
Table 18. Simulation results of straight trajectory tracking under friction coefficient disturbance conditions.
Control MethodMaximum Front Wheel Angle/DegreesLateral Deviation OvershootMaximum Heading Deviation/Degrees
LQR45//
Fuzzy-LQR45//
ANFIS-LQR3122.5%27.3
ANFIS-SMC-LQR34.9024.8
Table 19. Simulation results of circular trajectories tracking under friction coefficient disturbance conditions.
Table 19. Simulation results of circular trajectories tracking under friction coefficient disturbance conditions.
Control MethodMaximum Front Wheel Angle/DegreesLateral Deviation OvershootMaximum Heading Deviation/Degrees
LQR31.1//
Fuzzy-LQR28.9//
ANFIS-LQR450.4113.8
ANFIS-SMC-LQR36.30.4110.7
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

Wu, E.; Wang, P.; Guo, Z. Adaptive Robust Optimal Control for UAV Taxiing Systems with Uncertainties. Drones 2025, 9, 668. https://doi.org/10.3390/drones9100668

AMA Style

Wu E, Wang P, Guo Z. Adaptive Robust Optimal Control for UAV Taxiing Systems with Uncertainties. Drones. 2025; 9(10):668. https://doi.org/10.3390/drones9100668

Chicago/Turabian Style

Wu, Erdong, Peng Wang, and Zheng Guo. 2025. "Adaptive Robust Optimal Control for UAV Taxiing Systems with Uncertainties" Drones 9, no. 10: 668. https://doi.org/10.3390/drones9100668

APA Style

Wu, E., Wang, P., & Guo, Z. (2025). Adaptive Robust Optimal Control for UAV Taxiing Systems with Uncertainties. Drones, 9(10), 668. https://doi.org/10.3390/drones9100668

Article Metrics

Back to TopTop