Next Article in Journal
Enhanced Exact Methods for Optimizing Energy Delivery in Preemptive Electric Vehicle Charging Scheduling Problems
Previous Article in Journal
A High-Order Proper Orthogonal Decomposition Dimensionality Reduction Compact Finite-Difference Method for Diffusion Problems
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Unmanned Aerial Vehicle Position Tracking Using Nonlinear Autoregressive Exogenous Networks Learned from Proportional-Derivative Model-Based Guidance

1
Facultad de Ciencias de la Ingeniería e Industrias, Universidad UTE, Quito 170129, Ecuador
2
Engineering Department, Tribologyec, Av. De los Shirys, Quito 170518, Ecuador
3
School of Engineering, Newcastle University, Newcastle Upon Tyne NE1 7RU, UK
*
Authors to whom correspondence should be addressed.
Math. Comput. Appl. 2025, 30(4), 78; https://doi.org/10.3390/mca30040078
Submission received: 23 June 2025 / Revised: 16 July 2025 / Accepted: 17 July 2025 / Published: 24 July 2025
(This article belongs to the Section Engineering)

Abstract

The growing demand for agile and reliable Unmanned Aerial Vehicles (UAVs) has spurred the advancement of advanced control strategies capable of ensuring stability and precision under nonlinear and uncertain flight conditions. This work addresses the challenge of accurately tracking UAV position by proposing a neural-network-based approach designed to replicate the behavior of classical control systems. A complete nonlinear model of the quadcopter was derived and linearized around a hovering point to design a traditional proportional derivative (PD) controller, which served as a baseline for training a nonlinear autoregressive exogenous (NARX) artificial neural network. The NARX model, selected for its feedback structure and ability to capture temporal dynamics, was trained to emulate the control signals of the PD controller under varied reference trajectories, including step, sinusoidal, and triangular inputs. The trained networks demonstrated performance comparable to the PD controller, particularly in the vertical axis, where the NARX model achieved a minimal Mean Squared Error (MSE) of 7.78 × 10 5 and an R 2 value of 0.9852. These results confirm that the NARX neural network, trained via supervised learning to emulate a PD controller, can replicate and even improve classical control strategies in nonlinear scenarios, thereby enhancing robustness against dynamic changes and modeling uncertainties. This research contributes a scalable approach for integrating neural models into UAV control systems, offering a promising path toward adaptive and autonomous flight control architectures that maintain stability and accuracy in complex environments.

1. Introduction

Unmanned Aerial Vehicles (UAVs), including quadcopters, have become indispensable in both industrial and research contexts, offering reliable performance in environments where flexibility, precision, and autonomy are essential. Initially developed for military purposes, UAVs are now central to applications such as precision agriculture, logistics, infrastructure monitoring, and emergency response, due to advances in embedded systems, lightweight structures, and energy-efficient propulsion. UAVs, in particular, have emerged as the most widely adopted UAV type owing to their vertical take-off and landing (VTOL) capability, stable hovering, and high maneuverability in constrained spaces [1,2]. Their four-rotor configuration enables the precise control of position and attitude, making them suitable for data-sensitive operations such as inspection or mapping [3].
Nevertheless, controlling UAVs remains a technical challenge due to their nonlinear, coupled dynamics and sensitivity to disturbances. To address these challenges, this study proposes a hybrid control strategy that integrates traditional proportional-derivative (PD) control with data-driven learning via a recurrent neural network (RNN) based on a NARX architecture [4,5]. A full mathematical model of the UAV is derived and linearized at a hovering equilibrium, facilitating controller design for each axis independently [6]. The chosen quadcopter configuration—with four symmetrically arranged rotors—although not altering the mathematical model, critically shapes how thrust and moments are distributed and controlled. This dual approach leverages the predictability of classical models and the adaptability of neural networks to ensure reliable control across a range of real-world scenarios [7,8].
The core novelty of this work lies in employing a NARX neural network to replicate the behavior of a classical PD controller, establishing a hybrid approach that blends model-based interpretability with adaptive, data-driven flexibility. By designing the PD controller on a linearized quadcopter model and using its response to train the NARX network, this method enables the synthesis of a model-free controller with predictable dynamic behavior and reduced computational demand. Recent studies confirm the effectiveness of neural approximators for control tasks under uncertainty and nonlinearities [1,5,9].
This paper is structured to provide a clear and comprehensive understanding of the methodologies used and the findings. Section 2 reviews the state of the art and discusses UAV control strategies. Section 3 describes the derivation of the mathematical model for the UAV. It also presents the obtained linearized UAV, the developed PD controller, and an NARX-based control for each quadcopter’s available movement axes. Section 4 presents the training process results for each neural network and a comparative analysis between the PD controller and its NARX counterpart using performance metrics such as integral of absolute error (IAE) and graphical representations. Finally, Section 5 presents the conclusions drawn from the comparative analysis of the experimental results, emphasizing the implications and potential applications of the findings in UAV control systems and their respective performances.

2. State of the Art

The growing adoption of UAVs in the private sector is driven by technological advancements and their increasingly diverse applications. This section aims to explore the various facets of UAV technology, particularly UAVs, and to analyze their impact on contemporary industrial practices. By examining the underlying technologies, application areas, and future potential, this research provides a comprehensive overview of how UAVs reshape modern industries and pave the way for future innovations [10].
UAVs exhibit inherently nonlinear dynamics due to their multivariable nature, component uncertainties, and strong sensitivity to external disturbances such as wind [11]. These complexities significantly impact their stability and responsiveness, especially in demanding operational scenarios. As a result, ensuring reliable flight performance requires the implementation of advanced control strategies capable of compensating for both internal nonlinearities and real-time environmental perturbations [12]. Quadcopter systems, in particular, demand controllers that are not only accurate but also robust and adaptive to shifting flight conditions. Addressing these challenges is essential for maintaining safe and precise operation, especially in industrial contexts where consistent maneuverability is critical [13]. Continued research into resilient control frameworks remains vital to unlocking the full potential of UAVs in dynamic and uncertain environments, as demonstrated by recent works incorporating adaptive backstepping and sliding mode strategies with disturbance observers to enhance robustness and reduce computational cost [14].
Table 1 summarizes recent advancements in heuristic methodologies applied to control UAVs. The table highlights key research works, including multiple model approaches, control systems without mathematical models, and hybrid approaches for optimizing control performance. Each study demonstrates the application of different heuristic techniques, such as genetic algorithms, particle swarm optimization, and other meta-heuristic methods, to improve the efficiency and robustness of UAV control systems. The table also indicates whether the studies involved a mathematical model and a heuristic methodology, showcasing a comprehensive overview of the latest trends in advanced control strategies for UAV systems.
Table 2 and Figure 1 present a comprehensive overview of significant research advancements in UAV control using heuristic algorithms. The table highlights key studies emphasizing methodologies such as motion planning algorithms, evolutionary algorithms, and adaptive control strategies while indicating their contributions to UAV navigation and control. For instance, the research in [23] focuses on vehicle routing problems for drone delivery, while Goerzen, C. [24] explores a survey of motion planning algorithms for UAV guidance. The bar graph in Figure 1 visualizes the citation counts of the top 10 cited articles, underscoring these pioneering research efforts’ significant impact and scholarly influence. The citation data was retrieved from the Scopus database on 27 May 2025, ensuring an up-to-date and accurate representation of the current research landscape in UAV control strategies.

3. Methodology

3.1. Mathematical Model of a Quadcopter

The mathematical model of the quadcopter developed in this study aims to capture the essential dynamics that govern its motion in three-dimensional space. The formulation considers both translational and rotational behavior, making it suitable for simulation, control design, and comparative studies between model-based and data-driven strategies. To ensure analytical simplicity while maintaining physical relevance, the model incorporates three fundamental assumptions: (i) the quadcopter is a rigid body, (ii) its structure is symmetric, and (iii) the mass of the vehicle remains constant throughout flight [33,34]. These assumptions allow the derivation of a compact yet accurate representation of the quadcopter’s motion, enabling the effective implementation of control algorithms and neural network training procedures [35,36].
Figure 2 illustrates the two reference frames used in the modeling process. The body-fixed frame is attached to the center of mass of the quadcopter and moves with it, capturing its orientation and angular motion. The inertial frame, on the other hand, is fixed to the Earth and provides a global reference for position and velocity measurements. This dual-frame structure facilitates the transformation between local and global coordinates, which is fundamental for trajectory tracking and stabilization tasks [37]. The definition of both reference frames is essential for interpreting the data typically obtained from onboard sensors such as the inertial measurement unit (IMU) and the global positioning system (GPS). While the IMU provides angular velocities and orientation information with respect to the body frame, the GPS delivers position updates in the inertial frame [38]. Modeling this relationship accurately is vital for state estimation and controller design.
In this study, the set of variables used to describe the UAV’s dynamics—including position, velocity, orientation, angular rates, and their derivatives—is summarized in the Nomenclature section at the end of the manuscript. In addition, Table 3 provides a structured overview of the variables involved in the control architecture and the trajectory tracking optimization problem, categorized by their functional roles within the system. The modeling process follows a structured sequence: first, reference frames and coordinate transformations are defined; second, translational and rotational kinematics are formulated; third, the dynamics are established based on Newton–Euler equations; and finally, the full state vector is constructed to support control-oriented applications. This systematic approach ensures that the model is accurate and practical, making it suitable for implementation in simulation environments and real-time control systems.

3.2. Coordinate Transformation Between Reference Frames

A key step in modeling quadcopter dynamics is defining how its orientation evolves relative to the inertial frame. This is achieved through a series of rotations that transform the body-fixed frame into the Earth-fixed reference frame. The orientation is expressed using Euler angles—roll, pitch, and yaw—applied sequentially following the ZYX convention [40]. This order preserves the geometric interpretation of spatial rotations and ensures compatibility with inertial navigation systems. Each rotation is described by a matrix that updates the vector components along the respective axes. The full rotation matrix R b e is obtained by the ZYX composition of standard Euler rotations, as shown in Equation (1). This composite matrix is central to converting motion and sensor data between frames and supports orientation-dependent computations required for control. Figure 3 illustrates this transformation sequence, offering a visual reference for understanding the rotational framework [40].
R b e = R z · R y · R x

3.3. Kinematic and Dynamic Modeling of Translational and Rotational Motion

To accurately describe the motion of a quadcopter in three-dimensional space, it is essential to establish its kinematic and dynamic equations of motion. The translational kinematics define how linear velocities in the body frame—denoted as u, v, and w—are transformed into inertial frame velocities x ˙ , y ˙ , and z ˙ using the rotation matrix R b e , as shown in Equation (2). This transformation accounts for the UAV’s orientation in space and allows the computation of global positions from locally measured velocities. In the case of rotational kinematics, the angular velocities around the body axes ( p , q , r ) are related to the time derivatives of the Euler angles ( ϕ ˙ , θ ˙ , ψ ˙ ) via the transformation matrix T, whose explicit form is shown in Equation (3) [40]. This matrix reflects the dependency of rotational dynamics on the UAV’s orientation and is derived from the sequence of elementary ZYX rotations introduced earlier.
x ˙ y ˙ z ˙ = R b e u v w
ϕ ˙ θ ˙ ψ ˙ = T p q r
The transformation between body angular velocities and the time derivatives of the Euler angles can be directly obtained by considering the composite rotation matrix constructed from the standard R x , R y , and R z matrices. The resulting expression maps angular velocity components in the body frame to the rates of change of roll, pitch, and yaw, as shown in Equation (4) [40]. Building upon the kinematic foundation, the dynamic model is derived using Newton’s second law to account for the sum of forces acting on the quadcopter. In this context, the total external force acting on the UAV includes gravitational pull and the thrust generated by the four rotors. Rather than detailing each intermediate step, the force balance can be concisely expressed using the transformation into the inertial reference frame, as shown in Equation (5). Here, the thrust vector is rotated from the body frame into the inertial frame using R b e , ensuring consistency in the force summation. This formulation enables the computation of UAV linear accelerations, which are central to position control strategies [41].
ϕ ˙ θ ˙ ψ ˙ = 1 sin ϕ · tan θ cos ϕ · tan θ 0 cos ϕ sin ϕ 0 sin ϕ cos θ cos ϕ cos θ p q r
0 0 m · g + R b e · 0 0 F Thrust = m · x e ¨ y e ¨ z e ¨
Rotational dynamics are governed by the angular momentum relationship, where the torque vector M is expressed as the product of the UAV’s inertia matrix I and its angular velocity vector w. Although this relationship is traditionally expressed in expanded component form and accompanied by the full inertia matrix (as shown in [40,41]), in this study, only the simplified diagonal form is retained, since the quadcopter structure is symmetric and the products of inertia are negligible. This results in a reduced matrix representation, as shown in Equation (7), which significantly lowers the computational burden without compromising model fidelity. The compact formulation shown in Equation (6) is used throughout the controller design and simulation process.
M = I · w
I = I x x 0 0 0 I y y 0 0 0 I z z
The final stage in developing the mathematical model involves constructing the full state vector, which encapsulates the quadcopter’s dynamic and kinematic behavior. As defined in Equation (8) [40], the state vector comprises twelve variables: the UAV’s position ( x e , y e , z e ) and linear velocities ( x ˙ e , y ˙ e , z ˙ e ) in the inertial frame, the orientation angles ( ϕ , θ , ψ ) corresponding to roll, pitch, and yaw, and their time derivatives ( ϕ ˙ , θ ˙ , ψ ˙ ) representing angular rates in the Euler frame. This comprehensive formulation integrates the outcomes of the previous kinematic and dynamic derivations, providing a complete representation of the quadcopter’s motion.
x e y e z e x ˙ e y ˙ e z ˙ e ϕ θ ψ ϕ ˙ θ ˙ ψ ˙ T

3.4. Linearization Around Hover and Decoupled Subsystem Modeling

Designing a linear controller for a quadrotor begins with the linearization of its nonlinear dynamic model around a well-defined operating condition. In this case, the chosen equilibrium point corresponds to hovering at a fixed altitude, where all translational and angular velocities are zero, and the UAV maintains a stable orientation with only a possible yaw angle deviation, as defined in Equation (9). Around this point, a first-order Taylor series expansion is applied to the nonlinear equations of motion, resulting in the linearized dynamic relationships presented in Equation (10). These equations describe how small deviations in thrust and torques produce changes in translational and angular accelerations. Under hovering conditions, the body and inertial frames coincide, simplifying the velocity and attitude relationships, as shown in Equation (11); the equations are found in [42].
x e y e z e 0 0 0 ψ 0 0 0 0 0 T
Δ F z = m · Δ w ˙ + m · g Δ M x = I x x · Δ p ˙ Δ M y = I y y · Δ q ˙ Δ M z = I z z · Δ r ˙
Δ x ˙ = Δ u Δ ϕ ˙ = Δ p Δ y ˙ = Δ v Δ θ ˙ = Δ q Δ z ˙ = Δ w Δ ψ ˙ = Δ r
The resulting linearized model enables the decomposition of the quadcopter’s motion into four independent dynamic subsystems: vertical, directional (yaw), lateral (roll), and longitudinal (pitch). Each subsystem is described by a set of state variables and corresponding control inputs, facilitating separate analysis and controller design. The vertical dynamics, captured by Equation (12), involve vertical displacement and velocity and are governed by the total thrust force, leading to a second-order transfer function in Equation (13). The directional subsystem, shown in Equation (14), includes yaw angle and yaw rate and is driven by the torque around the Z-axis, with its transfer function expressed in Equation (15); the equations are found in the citation [41].
Δ z ˙ Δ w ˙ = 0 1 0 0 Δ z Δ w + 0 0 1 m 1 Δ F z g
G ( s ) = 1 m · s 2
Δ ψ ˙ Δ r ˙ = 0 1 0 0 Δ ψ Δ r + 0 1 I z z Δ M z
G ( s ) = 1 I z z · s 2
Similarly, the lateral subsystem—described in Equation (16)—includes the lateral position, velocity, roll angle, and roll rate, and is affected by torque around the X-axis. Its second-order transfer function is given in Equation (17). Finally, the longitudinal subsystem in Equation (18) models the forward movement and orientation along the pitch axis, including longitudinal position, velocity, pitch angle, and pitch rate, with the corresponding transfer function provided in Equation (19) [41]. This structured linearization and decoupling approach simplifies the control problem by reducing the multivariable dynamics of the UAV into manageable single-input–single-output (SISO) subsystems, each of which can be independently analyzed and tuned. These subsystem models form the foundation for designing classical controllers such as PD or PID or for benchmarking neural control approximations.
Δ y ˙ Δ v ˙ Δ ϕ ˙ Δ p ˙ = 0 1 0 0 0 0 0 0 0 0 0 1 0 0 0 0 Δ y Δ v Δ ϕ Δ p + 0 0 0 1 I x x Δ M x
G ( s ) = 1 I x x · s 2
Δ x ˙ Δ u ˙ Δ θ ˙ Δ q ˙ = 0 1 0 0 0 0 0 0 0 0 0 1 0 0 0 0 Δ x Δ u Δ θ Δ q + 0 0 0 1 I y y Δ M y
G ( s ) = 1 I y y · s 2

3.5. Cascaded Control Architecture and PD-Based Stabilization Strategy

The control strategy adopted for the quadcopter in this study follows a cascaded architecture, comprising two hierarchically organized loops: an external loop responsible for position control and an internal loop dedicated to attitude stabilization. As illustrated in Figure 4, the external loop processes reference signals [ x d , y d , z d ] and compares them with the actual position feedback [ x , y , z ] to compute the desired roll ( ϕ d ) and pitch ( θ d ) angles for horizontal movement and the total thrust F Thrust for vertical displacement. The yaw reference ( ψ d ) is also set independently. These references are then passed to the internal control loop, which is structured as a cascaded PD controller. The first stage stabilizes the attitude angles [ ϕ , θ , ψ ] , while the second stage regulates the angular velocities [ p , q , r ] using the commanded rates derived from angle errors. This structure ensures the fast and accurate tracking of both orientation and trajectory, enabling the UAV to maintain stability during complex maneuvers and disturbances.
The relationship between control inputs and quadcopter motion is governed by the combined effect of total thrust and torque vectors. In the body frame, vertical thrust directly influences acceleration along the main axis, while differential motor forces generate moments around the roll, pitch, and yaw axes. These moments depend on rotor placement and aerodynamic drag. As described in Equation (20) [41], the distribution of motor-generated thrusts determines the UAV’s angular and linear responses. This relationship provides the foundation for assessing control strategies under varying flight conditions and offers a consistent framework for comparing classical and neural-network-based approaches.
F T M x M y M z = F 1 + F 2 + F 3 + F 4 l ( F 2 F 4 ) l ( F 3 F 1 ) d ( F 1 F 2 + F 3 F 4 )
Equations (21)–(23) [41] define the core principles for achieving vertical stability in hovering. The force balance along the vertical axis ensures that the upward thrust compensates exactly for the gravitational force, allowing the UAV to remain suspended. From this condition, the required thrust is computed based on the UAV’s mass and gravity, resulting in a specific value used for hovering control in this study. Altitude is then regulated through a proportional-derivative controller, which adjusts the thrust to correct deviations and stabilize motion. This controller design, captured in Equation (23), enhances system response and suppresses overshoot. Together, these equations support the vertical control loop and provide a reliable foundation for UAV altitude regulation within the cascaded control architecture.
0 0 m · g + 1 0 0 0 0 0 0 0 1 · 0 0 F h o v e r i n g = m · 0 0 0
F h o v e r i n g = m · g = 0.1 × 9.8 = 0.98 N
C ( s ) = K p [ 1 + T d · s ]

3.6. NARX Controller Design and Implementation Details

This study introduces a data-driven control strategy based on an NARX network to emulate the behavior of a classical PD controller for quadcopter stabilization. The NARX architecture is particularly suited for dynamic systems such as UAVs, as it incorporates delayed versions of both input and output signals. This feature enables the network to capture temporal dependencies and utilize system memory, which is essential for representing the nonlinear and time-varying dynamics present in real flight scenarios. The choice of a PD controller, rather than a full PID configuration, was intentional: it avoids the risk of integral windup and reduces computational complexity—both critical factors in aerial robotics where low-latency, real-time control is essential. This simplification supports more responsive and stable behavior, particularly during rapid maneuvers, making PD a practical and efficient baseline for training the neural model. The general architecture of the network is illustrated in Figure 5. It consists of an input layer that receives both the reference signal (position error) and delayed feedback from the system output, a single hidden layer with a nonlinear activation function, and a linear output neuron that generates the control signal. The network was implemented using MATLAB 2024b® Neural Network Toolbox, leveraging the built-in NARX time-series tool.
To train the NARX network, the same inputs supplied to the classical PD controller—namely, the reference trajectory and the measured UAV states—are used as inputs. At the same time, the PD output serves as the supervised target. The objective was to have the network learn the input–output mapping performed by the PD controller. Once trained, the NARX model replaces the PD block, operating as an independent, adaptive controller. The methodology for training and control integration is presented in Figure 6.
The network architecture and training parameters used in this study are detailed in Table 4. The selection of a single hidden layer with a tangent sigmoid activation was based on its proven ability to approximate nonlinear functions efficiently without incurring excessive computational cost. The number of neurons was determined through iterative experimentation, balancing model complexity and generalization performance. Training was conducted using the Levenberg–Marquardt algorithm due to its fast convergence and suitability for function approximation tasks.
To generate the dataset, three independent test flights with distinct reference trajectories were used: step, sinusoidal, and ramp profiles. Each trajectory was sampled at 100 Hz for 5 s, yielding 500 time steps per axis. The dataset was normalized and randomly shuffled prior to training. The division followed a conventional split: 70% for training, 15% for validation (to monitor generalization), and 15% for testing. This formulation enables the NARX controller to learn the control action in a supervised manner, effectively transferring the PD strategy into a learned representation. Moreover, once deployed, the controller operates without reliance on the PD block, offering a model-free, adaptive response to system variations and external disturbances.

3.7. Optimization Problem for Trajectory Tracking

The final part of the proposed methodology frames the control task as a constrained optimization problem to ensure accurate trajectory tracking. The goal is to minimize the cumulative error between the UAV’s actual position and a desired reference over a set time. This tracking error is evaluated continuously and used to guide adjustments in the control input. One of the performance indicators used to quantify tracking quality is the IAE, calculated as shown in Equation (26), which aggregates the absolute position error over the simulation period. The optimization is subject to constraints that capture the system’s nonlinear dynamics and physical limitations. These include the evolution of the quadcopter’s state, restrictions on control effort, and operational safety bounds. Together, these elements ensure the control actions remain both practical and realistic. Solving this problem yields the control inputs that guide the UAV along the target path with minimal deviation. This formulation not only supports traditional model-based controllers but also enables the integration of learning-based strategies, such as NARX networks, within a robust optimization framework.
min u ( t ) J = 0 T e ( t ) 2 d t
e ( t ) = r ( t ) y ( t )
IAE = 0 T | r ( t ) y ( t ) | d t
x ˙ ( t ) = f ( x ( t ) , u ( t ) )
u min u ( t ) u max
x min x ( t ) x max

4. Results and Discussion

The effectiveness of the proposed control strategy was evaluated by training an NARX-based neural network to replicate the behavior of a classical PD controller. The training data encompassed reference trajectories and control signals corresponding to the UAV’s three primary translational axes—X, Y, and Z—enabling the network to learn temporal patterns and dynamic relationships representative of model-based control. To assess the model’s predictive accuracy and generalization capability, two key performance metrics were employed: Mean Squared Error (MSE) and the coefficient of determination ( R 2 ). A lower MSE indicates closer approximation to the target control signals, while a higher R 2 reflects stronger correlation with the original PD controller responses. These metrics were calculated separately for the training, validation, and test datasets to provide a detailed understanding of the network’s learning behavior and to identify any signs of overfitting or underfitting—critical considerations in recurrent neural networks with memory feedback.
The results are summarized in Table 5. During validation, the NARX model achieved an outstanding performance with an R 2 of 0.9958 and an MSE close to zero, demonstrating its ability to generalize to unseen data. While the training phase yielded an R 2 of 0.8339 and a modest MSE of 0.0007, the slightly reduced performance in the test phase ( R 2 = 0.7933 , MSE = 0.0017) suggests that the network retains a stable predictive capability even outside its training conditions. These results affirm the model’s robustness and the effectiveness of the training process in capturing the underlying control dynamics. This preliminary performance validation supports the NARX network’s potential as a viable alternative to classical controllers. In the following subsections, a more detailed axis-wise analysis is presented to evaluate the controller’s response across the X, Y, and Z axes. Particular attention is given to its dynamic behavior, steady-state error characteristics, and integral performance indices to substantiate its real-time applicability.

4.1. Training Evaluation and Axis-Wise Performance of the NARX Controllers

The training performance of the NARX-based controllers was evaluated across the X, Y, and Z displacement axes, exploring three training algorithms and varying the number of hidden neurons. The goal was to identify configurations that balance model accuracy, generalization, and simplicity. As shown in Table 6, Bayesian Regularization with two hidden neurons consistently delivered the best results across all axes, achieving the lowest Mean Squared Error and highest R 2 values. This configuration effectively mitigated overfitting while capturing key nonlinear dynamics, proving particularly suitable for real-time UAV applications where computational efficiency is essential.
The convergence behavior of the selected configurations is illustrated in Figure 7, which presents the evolution of training and testing errors over the training epochs. The network converged after 92 iterations on the X-axis, 149 on the Z-axis, and 264 on the Y-axis, each demonstrating smooth and stable error reduction. Although the Y-axis initially presented greater error, it ultimately achieved high accuracy and reliability. Notably, deeper networks and alternative algorithms such as Levenberg–Marquardt and Scaled Conjugate Gradient introduced greater complexity without measurable performance gains. These findings reaffirm the methodological decision to prioritize lightweight, well-regularized neural architectures for robust and generalizable control across multiple UAV axes.

4.2. Trajectory Tracking Performance Under Diverse Reference Inputs

To comprehensively assess the effectiveness of classical PD and NARX-based controllers in regulating the UAV position, a series of trajectory tracking experiments was conducted. These tests employed three types of reference signals—step, sinusoidal, and triangular—applied independently to the X, Y, and Z axes. The goal was to evaluate the controllers’ ability to manage varying dynamics, from abrupt transitions to smooth oscillations and sharp directional changes.
The performance of each controller was evaluated using the IAE, a standard metric in control theory that quantifies the cumulative deviation between the reference input and the system’s actual response. By integrating the absolute value of the tracking error over time, the IAE captures both transient deviations and steady-state inaccuracies, offering a comprehensive measure of control quality. Lower IAE values indicate a more precise and efficient response. The results obtained for all input types—step, sinusoidal, and triangular—across the X, Y, and Z axes are consolidated in Table 7. These numerical findings are visually supported by the response plots shown in Figure 8, Figure 9 and Figure 10, which illustrate the dynamic behavior of each controller under varying reference signals.
For step inputs in Figure 8, the NARX controller demonstrated fast settling times and smooth transitions, particularly in the Z-axis, where it achieved slightly reduced overshoot compared to the PD controller. However, in the X- and Z-axes, the PD controller delivered lower IAE values, indicating better overall precision. Only in the Y-axis did the neural controller slightly outperform the classical strategy, suggesting its potential adaptability in managing lateral dynamics.
Under sinusoidal excitation in Figure 9, the NARX controller demonstrated superior performance in vertical tracking, closely following the reference trajectory with reduced phase lag and steady-state error. This performance is attributed to the network’s recurrent structure, which effectively models time-dependent behavior. Conversely, the PD controller maintained superior tracking in the X and Y axes, providing smoother responses with fewer oscillations. These results indicate that while neural feedback structures are advantageous in capturing nonlinear vertical dynamics, classical controllers still offer higher consistency in predictable lateral motions.
The triangular input scenario in Figure 10 introduced sharper slope variations, posing a challenge to both controllers. The PD controller handled these abrupt changes more reliably, especially during descending slopes, as evidenced by its significantly lower IAE values in the Z-axis. The NARX controller, while capable of capturing the general trajectory shape, exhibited noticeable overshoot and oscillations across all axes, likely due to limitations in generalizing high-gradient transitions from smoothed training data.
Additionally, a comparative analysis of the IAE, ISE, ITAE, and ITSE indices for both controllers is presented in Figure 11. This figure, organized as three vertically stacked subplots, contrasts the performance of the PD- and NARX-based controllers across step, sinusoidal, and triangular inputs using a logarithmic scale to better visualize the differences in magnitude. The NARX controller consistently outperforms the PD controller in the step and triangular cases, particularly in the ITAE and ITSE metrics, which emphasize time-weighted error. In the sinusoidal case, however, the performance gap narrows, indicating similar steady-state tracking abilities for both approaches.
Overall, these experiments highlight the complementary strengths of each approach. The PD controller exhibits robust, low-error performance in structured and high-slope environments, benefiting from its simplicity and reactive tuning capabilities. The NARX neural controller, by contrast, shows strong adaptability and potential for learning complex mappings, particularly in vertical dynamics and smooth trajectory tracking. However, its sensitivity to rapid directional changes suggests room for improvement—either through enhanced training data diversity or integration with classical strategies in a hybrid control framework. These findings support the feasibility of neural approximators in UAV control, paving the way for future developments that combine model-free learning with model-based reliability.
Taken together, these findings reinforce the complementary nature of the two control strategies. The NARX neural controller demonstrates notable promise, particularly in managing nonlinear behaviors and learning from dynamic datasets. However, its performance is more sensitive to rapid transitions and may benefit from additional training refinements or hybridization with classical control elements. On the other hand, the PD controller continues to offer reliable, low-error tracking across a variety of input types, particularly excelling in conditions that require precise reactivity to rapidly changing inputs.

5. Conclusions and Future Works

This study addressed the challenge of Unmanned Aerial Vehicle (UAV) position tracking by applying artificial neural networks, specifically using a nonlinear autoregressive exogenous (NARX)-based architecture to emulate classical proportional-derivative (PD) control. A key foundation of the methodology was the mathematical modeling and linearization of the quadcopter’s nonlinear dynamics around a hovering equilibrium point, enabling a structured control framework. The NARX model was selected based on its ability to incorporate feedback and capture temporal dependencies, which is critical for replicating time-varying control signals. Prior research supported this choice, highlighting the effectiveness of recurrent neural networks in approximating nonlinear systems like UAVs. Through this integration of modeling, linear control, and data-driven learning, the work demonstrated how a well-trained neural controller can serve as a robust and adaptive alternative to conventional control strategies.
A comprehensive nonlinear model of a quadcopter was developed using Newton–Euler formulations and subsequently linearized around a hovering operating point through a first-order Taylor expansion. This linearization enabled the identification of decoupled dynamics along the X, Y, and Z axes, allowing for the design of independent controllers and transfer functions for each degree of freedom. The mathematical modeling framework established in this work proved instrumental for both classical and data-driven controller design, providing the reference architecture against which the performance of neural controllers could be benchmarked.
This work validated the use of NARX neural controllers as effective surrogates for PD control in UAV position tracking. The best-performing model—Bayesian Regularization with two hidden neurons—achieved high accuracy, notably an R 2 = 0.9852 for vertical control. Trajectory tracking experiments confirmed its strength in reducing overshoot and improving settling time on the Z-axis. However, the classical PD controller consistently yielded lower tracking errors in the lateral axes. These results confirm the viability of neural strategies while pointing to refinement needs for horizontal dynamics.
In conclusion, this study validates the feasibility of employing NARX-based neural network models for controlling UAVs. It demonstrates their strengths in modeling nonlinear dynamics with limited data and computational complexity. Nevertheless, the findings also point to current limitations, particularly in lateral and longitudinal regulation, where classical controllers still exhibit superior consistency and precision. Future work should aim to enhance the generalization capacity and adaptability of neural controllers through enriched training datasets and hybrid control structures. This work lays a promising foundation for integrating learning-based control into UAV systems, aligning with the growing interest in data-driven autonomy and adaptive flight control.
Despite its promising results, the proposed position control scheme has several limitations. First, the NARX controller exhibited reduced performance under rapid directional changes, especially in lateral and longitudinal displacements. Second, its learning-based nature depends heavily on the quality and variety of training data; insufficient data diversity may lead to poor generalization in untrained conditions. Finally, while lightweight, the current architecture lacks mechanisms for online adaptation, making it less responsive to unmodeled disturbances or system degradation. Future work should explore hybrid adaptive solutions to mitigate these issues.

Author Contributions

Conceptualization, W.P.; methodology, W.P. and J.C.; software, J.C., D.G. and A.B.A.-A.; resources, A.B.A.-A.; validation, W.P.; formal analysis, W.P. and J.C.; investigation, W.P. and J.C.; data curation, W.P. and D.G.; visualization, W.P.; writing—original draft preparation, J.C.; writing—review and editing, D.G. and A.B.A.-A.; supervision, W.P. and D.G. All authors have read and agreed to the published version of the manuscript.

Funding

This research was supported by Universidad UTE through a funding grant of 2000 USD.

Data Availability Statement

Data are contained within the article.

Acknowledgments

This paper presents results from a project at UTE, which contributed to heuristic methodologies for system identification. Jorge Chavez is master’s student in electronics and automation, with Wilson Pavon supervising his graduation project.

Conflicts of Interest

The authors declare no conflicts of interest.

Nomenclature

SymbolDescription
x e , y e , z e Position in inertial frame (Earth-fixed).
x b , y b , z b Position in body frame (UAV-fixed).
u , v , w Linear velocities in body frame.
x ˙ , y ˙ , z ˙ Linear velocities in inertial frame.
ϕ , θ , ψ Roll, pitch, and yaw angles (Euler angles).
ϕ ˙ , θ ˙ , ψ ˙ Time derivatives of Euler angles.
p , q , r Roll, pitch, and yaw angular velocity of the body frame (Euler angle rates).
R x , R y , R z Rotation matrices for each axis (roll, pitch, yaw).
R b e Full rotation matrix from body to inertial frame.
T , T 1 Transformation matrix and its inverse for angular velocity conversion.
IInertia matrix of the UAV.
I x x , I y y , I z z Principal moments of inertia.
M x , M y , M z Torques about roll, pitch, and yaw axes.
MTorque vector.
wAngular velocity vector [ p , q , r ] T .
mMass of the quadcopter.
gGravitational acceleration.
F Thrust Total thrust generated by the UAV.
F i Thrust from rotor i, i = 1 , 2 , 3 , 4 .
k i Thrust coefficient for rotor i.
lDistance from UAV center to motor (arm length).
dDrag coefficient of the rotors.
x d , y d , z d Desired position in inertial frame.
ψ d Desired yaw angle.
ϕ d , θ d Desired roll and pitch angles.
F T Commanded total thrust.
ψ ˙ Commanded yaw rate.
C ( s ) Transfer function of PD controller.
K p , T d Proportional gain and derivative time constant.
e ( t ) Tracking error between reference and actual output.
r ( t ) , y ( t ) Desired (reference) signal and actual output.
x ( t ) , u ( t ) State and control input vectors.
f ( x ( t ) , u ( t ) ) UAV nonlinear dynamics function.
u min , u max Lower and upper bounds for control inputs.
x min , x max State constraints for position, velocity, and angles.
JObjective function for trajectory tracking.
MSEMean Squared Error metric.
R 2 Coefficient of determination for model fit.
IAEIntegral of the Absolute Error; measures total accumulated error over time.
ISEIntegral of the Squared Error; penalizes larger errors more heavily.
ITAEIntegral of Time-weighted Absolute Error; emphasizes errors that persist over time.
ITSEIntegral of Time-weighted Squared Error; highlights sustained large errors.

References

  1. Yoon, J.; Doh, J. Optimal PID Control for Hovering Stabilization of Quadcopter Using Long Short Term Memory. Adv. Eng. Inform. 2022, 53, 101679. [Google Scholar] [CrossRef]
  2. Jiang, F.; Pourpanah, F.; Hao, Q. Design, Implementation, and Evaluation of a Neural-Network-Based Quadcopter UAV System. IEEE Trans. Ind. Electron. 2020, 67, 2076–2085. [Google Scholar] [CrossRef]
  3. Pinzón, S.; Pavón, W. Diseño de Sistemas de Control Basados en el Análisis del Dominio en Frecuencia. Rev. Técnica Energía 2019, 15, 76–82. [Google Scholar] [CrossRef]
  4. Wu, Z.; Ye, J.; Song, T. Dynamic Event-Triggered Prescribed Performance Robust Control for Aggressive Quadrotor Flight. Aerospace 2024, 11, 301. [Google Scholar] [CrossRef]
  5. Hadid, S.; Boushaki, R.; Boumchedda, F.; Merad, S. Enhancing Quadcopter Autonomy: Implementing Advanced Control Strategies and Intelligent Trajectory Planning. Automation 2024, 5, 151–175. [Google Scholar] [CrossRef]
  6. Dougherty, S.; Oo, N.L.; Zhao, D. Effects of propeller separation and onset flow condition on the performance of quadcopter propellers. Aerosp. Sci. Technol. 2024, 145, 108837. [Google Scholar] [CrossRef]
  7. Yih, C.-C.; Wu, S.-J. Sliding Mode Path Following and Control Allocation of a Tilt-Rotor Quadcopter. Appl. Sci. 2022, 12, 11088. [Google Scholar] [CrossRef]
  8. Yao, W.-S.; Lin, C.-Y. Dynamic Stiffness Enhancement of the Quadcopter Control System. Electronics 2022, 11, 2206. [Google Scholar] [CrossRef]
  9. Lu, P.; Liu, M.; Zhang, X.; Zhu, G.; Li, Z.; Su, C.-Y. Neural Network Based Adaptive Event-Triggered Control for Quadrotor Unmanned Aircraft Robotics. Machines 2022, 10, 617. [Google Scholar] [CrossRef]
  10. Sheta, A.; Braik, M.; Maddi, D.R.; Mahdy, A.; Aljahdali, S.; Turabieh, H. Optimization of PID Controller to Stabilize Quadcopter Movements Using Meta-Heuristic Search Algorithms. Appl. Sci. 2021, 11, 6492. [Google Scholar] [CrossRef]
  11. Nguyen, A.T.; Xuan-Mung, N.; Hong, S.-K. Quadcopter Adaptive Trajectory Tracking Control: A New Approach via Backstepping Technique. Appl. Sci. 2019, 9, 3873. [Google Scholar] [CrossRef]
  12. Bari, S.; Zehra Hamdani, S.S.; Khan, H.U.; Rehman, M.U.; Khan, H. Artificial Neural Network Based Self-Tuned PID Controller for Flight Control of Quadcopter. In Proceedings of the 2019 International Conference on Engineering and Emerging Technologies, ICEET 2019, Lahore, Pakistan, 21–22 February 2019; pp. 1–5. [Google Scholar] [CrossRef]
  13. Olaz, X.; Alaez, D.; Prieto, M.; Villadangos, J.; Astrain, J.J. Quadcopter neural controller for take-off and landing in windy environments. Expert Syst. Appl. 2023, 225, 120146. [Google Scholar] [CrossRef]
  14. Maaruf, M.; Abubakar, A.N.; Gulzar, M.M. Adaptive Backstepping and Sliding Mode Control of a Quadrotor. J. Braz. Soc. Mech. Sci. Eng. 2024, 46, 630. [Google Scholar] [CrossRef]
  15. Nobahari, H.; Sharifi, A. Multiple model extended continuous ant colony filter applied to real-time wind estimation in a fixed-wing UAV. Eng. Appl. Artif. Intell. 2020, 92, 103629. [Google Scholar] [CrossRef]
  16. Sopov, E. Solving a Problem of the Lateral Dynamics Identification of a UAV using a Hyper-heuristic for Non-stationary Optimization. In Proceedings of the 13th International Joint Conference on Computational Intelligence (IJCCI 2021), Online Streaming, 25–27 October 2021; pp. 107–114. [Google Scholar] [CrossRef]
  17. Maaruf, M.; Hamanah, W.M.; Abido, M.A. Hybrid Backstepping Control of a Quadrotor Using a Radial Basis Function Neural Network. Mathematics 2023, 11, 991. [Google Scholar] [CrossRef]
  18. Filimonov, A.B.; Filimonov, N.B.; Pham, Q.P. Planning of Drones Flight of Routes when Group Patrolling of Large Extended Territories. In Proceedings of the 2023 V International Conference on Control in Technical Systems (CTS), Saint Petersburg, Russia, 21–23 September 2023; pp. 228–231. [Google Scholar] [CrossRef]
  19. Venturini, F.; Mason, F.; Pase, F.; Chiariotti, F.; Testolin, A.; Zanella, A.; Zorzi, M. Distributed Reinforcement Learning for Flexible and Efficient UAV Swarm Control. IEEE Trans. Cogn. Commun. Netw. 2021, 7, 955–969. [Google Scholar] [CrossRef]
  20. Lyu, Z.; Zhu, G.; Xu, J. Joint Maneuver and Beamforming Design for UAV-Enabled Integrated Sensing and Communication. IEEE Trans. Wirel. Commun. 2023, 22, 2424–2440. [Google Scholar] [CrossRef]
  21. Mahmoud, M.S.; Maaruf, M. Robust Adaptive Multilevel Control of a Quadrotor. IEEE Access 2020, 8, 167684–167692. [Google Scholar] [CrossRef]
  22. Li, L.; Chang, T.-H.; Cai, S. UAV Positioning and Power Control for Two-Way Wireless Relaying. IEEE Trans. Wirel. Commun. 2020, 19, 1008–1024. [Google Scholar] [CrossRef]
  23. Dorling, K.; Heinrichs, J.; Messier, G.G.; Magierowski, S. Vehicle Routing Problems for Drone Delivery. IEEE Trans. Syst. Man Cybern. Syst. 2017, 47, 70–85. [Google Scholar] [CrossRef]
  24. Goerzen, C.; Kong, Z.; Mettler, B. A Survey of Motion Planning Algorithms from the Perspective of Autonomous UAV Guidance. J. Intell. Robot. Syst. 2010, 57, 65–100. [Google Scholar] [CrossRef]
  25. Nikolos, I.K.; Valavanis, K.P.; Tsourveloudis, N.C.; Kostaras, A.N. Evolutionary algorithm based offline/online path planner for UAV navigation. IEEE Trans. Syst. Man, Cybern. Part (Cybern.) 2003, 33, 898–912. [Google Scholar] [CrossRef]
  26. Mofid, O.; Mobayen, S. Adaptive sliding mode control for finite-time stability of quad-rotor UAVs with parametric uncertainties. ISA Trans. 2018, 72, 1–14. [Google Scholar] [CrossRef]
  27. Zhao, H.; Wang, H.; Wu, W.; Wei, J. Deployment Algorithms for UAV Airborne Networks Toward On-Demand Coverage. IEEE J. Sel. Areas Commun. 2018, 36, 2015–2031. [Google Scholar] [CrossRef]
  28. Fadlullah, Z.M.; Takaishi, D.; Nishiyama, H.; Kato, N.; Miura, R. A dynamic trajectory control algorithm for improving the communication throughput and delay in UAV-aided networks. IEEE Netw. 2016, 30, 100–105. [Google Scholar] [CrossRef]
  29. Radmanesh, M.; Kumar, M.; Guentert, P.H.; Sarim, M. Overview of Path-Planning and Obstacle Avoidance Algorithms for UAVs: A Comparative Study. Unmanned Syst. 2018, 06, 95–118. [Google Scholar] [CrossRef]
  30. Faiçal, B.S.; Freitas, H.; Gomes, P.H.; Mano, L.Y.; Pessin, G.; de Carvalho, A.C.P.L.F.; Krishnamachari, B.; Ueyama, J. An adaptive approach for UAV-based pesticide spraying in dynamic environments. Comput. Electron. Agric. 2017, 138, 210–223. [Google Scholar] [CrossRef]
  31. Altan, A. Performance of Metaheuristic Optimization Algorithms based on Swarm Intelligence in Attitude and Altitude Control of Unmanned Aerial Vehicle for Path Following. In Proceedings of the 2020 4th International Symposium on Multidisciplinary Studies and Innovative Technologies (ISMSIT), Istanbul, Turkey, 22–24 October 2020; pp. 1–6. [Google Scholar] [CrossRef]
  32. Shetty, V.K.; Sudit, M.; Nagi, R. Priority-based assignment and routing of a fleet of unmanned combat aerial vehicles. Comput. Oper. Res. 2008, 35, 1813–1828. [Google Scholar] [CrossRef]
  33. Yaman, O.; Yol, F.; Altinors, A. A Fault Detection Method Based on Embedded Feature Extraction and SVM Classification for UAV Motors. Microprocess. Microsyst. 2022, 94, 104683. [Google Scholar] [CrossRef]
  34. Labbadi, M.; Cherkaoui, M. Robust adaptive backstepping fast terminal sliding mode controller for uncertain quadrotor UAV. Aerosp. Sci. Technol. 2019, 93, 105306. [Google Scholar] [CrossRef]
  35. Pazmiño, R.; Pavon, W.; Armstrong, M.; Simani, S. Performance Evaluation of Fractional Proportional–Integral–Derivative Controllers Tuned by Heuristic Algorithms for Nonlinear Interconnected Tanks. Algorithms 2024, 17, 306. [Google Scholar] [CrossRef]
  36. Salazar, D.; Pavón, W.; Montalvo, W.; Zambrano, J.C. Heuristic Tuning and Decoupling Strategies for Multivariable Systems: An Integrated TIA Portal and Matlab-Simulink Approach. In Proceedings of the International Conference on Science, Technology and Innovation for Society, Guayaquil, Ecuador, 23–24 October 2024; Springer: Berlin/Heidelberg, Germany, 2024; pp. 395–405. [Google Scholar] [CrossRef]
  37. Islam, S.; Liu, P.X.; El Saddik, A. Nonlinear adaptive control for quadrotor flying vehicle. Nonlinear Dyn. 2014, 78, 117–133. [Google Scholar] [CrossRef]
  38. Santoso, F.; Garratt, M.A.; Anavatti, S.G. Hybrid PD-Fuzzy and PD Controllers for Trajectory Tracking of a Quadrotor Unmanned Aerial Vehicle: Autopilot Designs and Real-Time Flight Tests. IEEE Trans. Syst. Man Cybern. Syst. 2021, 51, 1817–1829. [Google Scholar] [CrossRef]
  39. Etigowni, S.; Hossain-McKenzie, S.; Kazerooni, M.; Davis, K.; Zonouz, S. Crystal (ball): I look at physics and predict control flow! Just-ahead-of-time controller recovery. In Proceedings of the 2018 Annual Computer Security Applications Conference, San Juan, PR, USA, 3–7 December 2018; Association for Computing Machinery: New York, NY, USA, 2018; pp. 553–565. [Google Scholar] [CrossRef]
  40. Lara Sosa, B.M.; Fagua Perez, E.Y.; Salamanca, J.M.; Higuera Martinez, O.I. Diseño e implementación de un sistema de control de vuelo para un vehículo aéreo no tripulado tipo cuadricóptero. Tecnura 2017, 21, 32–46. [Google Scholar] [CrossRef]
  41. Paiva, E.A.; Soto, J.C.; Salinas, J.A.; Ipanaqué, W. Modeling and PID cascade control of a Quadcopter for trajectory tracking. In Proceedings of the 2015 CHILEAN Conference on Electrical, Electronics Engineering, Information and Communication Technologies (CHILECON), Santiago, Chile, 28–30 October 2015; pp. 809–815. [Google Scholar] [CrossRef]
  42. Zekry, O.H.; Attia, T.; Hafez, A.T.; Ashry, M.M. PID Trajectory Tracking Control of Crazyflie Nanoquadcopter Based on Genetic Algorithm. In Proceedings of the 2023 IEEE Aerospace Conference, Big Sky, MT, USA, 4–11 March 2023; pp. 1–8. [Google Scholar] [CrossRef]
Figure 1. Number of citations of the top 10 most cited articles.
Figure 1. Number of citations of the top 10 most cited articles.
Mca 30 00078 g001
Figure 2. Quadcopter body and inertial reference frames used to define translational and rotational motion via Euler angles [39].
Figure 2. Quadcopter body and inertial reference frames used to define translational and rotational motion via Euler angles [39].
Mca 30 00078 g002
Figure 3. The body and inertial frames’ orientation changes are represented by rotation matrices [40].
Figure 3. The body and inertial frames’ orientation changes are represented by rotation matrices [40].
Mca 30 00078 g003
Figure 4. Internal and external control loops of a quadcopter.
Figure 4. Internal and external control loops of a quadcopter.
Mca 30 00078 g004
Figure 5. Architecture of the NARX model replicating PD behavior for UAV control using delayed feedback.
Figure 5. Architecture of the NARX model replicating PD behavior for UAV control using delayed feedback.
Mca 30 00078 g005
Figure 6. Diagram illustrating the methodology for training the NARX network to replicate the control behavior of the PD controller.
Figure 6. Diagram illustrating the methodology for training the NARX network to replicate the control behavior of the PD controller.
Mca 30 00078 g006
Figure 7. Mean Squared Error comparison of training and testing for X, Y, and Z controllers across epochs.
Figure 7. Mean Squared Error comparison of training and testing for X, Y, and Z controllers across epochs.
Mca 30 00078 g007
Figure 8. System behavior with PD and neural network controllers subjected to a sinusoidal signal.
Figure 8. System behavior with PD and neural network controllers subjected to a sinusoidal signal.
Mca 30 00078 g008
Figure 9. System behavior with PD and neural network controllers subjected to a sinusoidal signal.
Figure 9. System behavior with PD and neural network controllers subjected to a sinusoidal signal.
Mca 30 00078 g009
Figure 10. System behavior with PD and neural network controllers subjected to a triangular signal.
Figure 10. System behavior with PD and neural network controllers subjected to a triangular signal.
Mca 30 00078 g010
Figure 11. Log-scale comparison of the performance indices IAE, ISE, ITAE, and ITSE for PD and NARX controllers under step, sinusoidal, and triangular reference signals.
Figure 11. Log-scale comparison of the performance indices IAE, ISE, ITAE, and ITSE for PD and NARX controllers under step, sinusoidal, and triangular reference signals.
Mca 30 00078 g011
Table 1. Summary of heuristic methods in UAV control systems.
Table 1. Summary of heuristic methods in UAV control systems.
Main Author and ReferenceMethodologyMathematical UAV ModelHeuristic Methodology
Nobahari and Sharifi [15]In this study, a multiple-model approach is proposed for the modeling and control of nonlinear systems.XX
Sopov [16]A control system of a UAV is considered in which the PID controller is tuned using heuristic methods.XX
Maaruf et al. [17]This paper proposes a hybrid backstepping control using radial basis function neural network (RBFNN) to track quadrotor position and attitude with uncertainties.XX
Filimonov et al. [18]Currently one of the promising areas of joint development is the creation of intelligent control systems for UAVs using heuristic methods.XX
Venturini et al. [19]Over the past few years, the use of swarms of UAVs in various fields has become increasingly common. This study uses heuristic methods for control. X
Lyu et al. [20]This paper uses heuristic methods without a mathematical model to study the UAV control problem. X
Mahmoud and Maaruf [21]This study presents a multilevel robust adaptive control using RBFNN and observer-based sliding mode techniques.XX
Li et al. [22]This paper considers a UAV control problem using heuristic methods to achieve robustness, setpoint tracking, disturbance rejection, and aggressiveness (RTDA).XX
Table 2. Top 10 papers with methodologies.
Table 2. Top 10 papers with methodologies.
Main AuthorReferenceCitationsMethodology Summary
Dorling[23]956Vehicle routing problems for drone delivery.
Goerzen[24]662Survey of motion planning algorithms for UAV guidance.
Nikolos[25]451Evolutionary-algorithm-based offline/online path planner for UAV navigation.
Mofid[26]361Adaptive sliding mode control for quadrotor UAVs.
Zhao[27]273Deployment algorithms for airborne UAV  networks.
Fadlullah[28]190Dynamic trajectory control algorithm for UAV surveillance.
Radmanesh[29]197Overview of path-planning and obstacle avoidance strategies in UAVs.
Faiçal[30]202Adaptive approach for UAV-based pesticide spraying.
Altan[31]181Performance of metaheuristic optimization algorithms for UAV path planning.
Shetty[32]129Priority-based assignment and routing of UAVs.
Table 3. Summary of variables involved in the UAV control and trajectory optimization strategy. Note: For detailed symbol definitions and units, refer to the Nomenclature section at the end of the paper.
Table 3. Summary of variables involved in the UAV control and trajectory optimization strategy. Note: For detailed symbol definitions and units, refer to the Nomenclature section at the end of the paper.
CategoryVariable/
Parameter
Description
Position References x d , y d , z d Desired position in inertial frame
ψ d Desired yaw angle
Position Feedbackx, y, zMeasured position in inertial frame
x ˙ , y ˙ , z ˙ Linear velocity feedback in inertial frame
Attitude References ϕ d , θ d Desired roll and pitch angles
ψ d Desired yaw angle
F T Total thrust command
Attitude Feedback ϕ , θ , ψ Measured Euler angles from IMU
p, q, rAngular velocity feedback in body frame
Control Inputs ϕ , θ Roll and pitch setpoints from outer loop
ψ ˙ , F T Commanded yaw rate and thrust
Motor and Physical
Parameters
F i , k i Thrust from rotor i and thrust coefficient
l, dArm length and rotor drag coefficient
Controller Parameters K p , T d PD gains: proportional and derivative time
C ( s ) Transfer function of PD controller
Optimization Problem x ( t ) State vector: positions, velocities, angles, rates
u ( t ) Control vector: thrust and torques
f ( x ( t ) , u ( t ) ) Nonlinear system dynamics function
Constraints u min , u max Bounds on control inputs
x min , x max Operating limits on state variables
Table 4. Architecture and training parameters of the NARX network for UAV control.
Table 4. Architecture and training parameters of the NARX network for UAV control.
ParameterValue/Description
Input signalsReference trajectory error and system output
Number of inputs2 (reference, feedback)
Input delay taps1:3
Output delay taps1:3
Hidden layer size15 neurons
Hidden layer activationTangent sigmoid (tansig)
Output layer activationLinear (purelin)
Training algorithmLevenberg–Marquardt (trainlm)
Loss functionMean Squared Error (MSE)
Data set size1500 samples (3 trajectories, 500 points each)
Training/Validation/Test split70%/15%/15%
Stopping criteriaValidation performance or 1000 epochs
RegularizationEarly stopping based on validation error
Table 5. Performance metrics of the NARX network.
Table 5. Performance metrics of the NARX network.
DatasetObservationsMSE R 2
Training7000.00070.8339
Validation1500.00000.9958
Test1500.00170.7933
Table 6. Training results of the neural-network-based controllers for displacement in X, Y, and Z axes. Best-performing configurations are highlighted.
Table 6. Training results of the neural-network-based controllers for displacement in X, Y, and Z axes. Best-performing configurations are highlighted.
AxisTraining AlgorithmNeuronsMSE R 2 Note
ZLavenberg–Marquardt2 3.30 × 10 3 0.8656
4 1.16 × 10 3 0.7929
6 3.61 × 10 3 0.8670
Bayesian Regularization2 7.78 × 10 5 0.9852Best
4 8.58 × 10 4 0.9607
6 1.14 × 10 3 0.9400
Scaled Conjugate Gradient2 4.27 × 10 3 0.7449
4 2.04 × 10 3 0.7721
6 5.70 × 10 3 0.6600
XLavenberg–Marquardt2 4.35 × 10 4 0.9460
4 1.07 × 10 3 0.8051
6 1.42 × 10 3 0.8168
Bayesian Regularization2 5.26 × 10 5 0.9915Best
4 3.81 × 10 4 0.9429
6 1.66 × 10 4 0.9751
Scaled Conjugate Gradient2 8.11 × 10 4 0.8748
4 3.42 × 10 4 0.9150
6 8.63 × 10 4 0.8820
YLavenberg–Marquardt2 1.35 × 10 4 0.8393
4 1.70 × 10 3 0.7876
6 4.59 × 10 4 0.9135
Bayesian Regularization2 9.56 × 10 5 0.9843Best
4 2.68 × 10 4 0.9593
6 1.48 × 10 4 0.9773
Scaled Conjugate Gradient2 1.14 × 10 3 0.8123
4 1.82 × 10 3 0.6932
6 4.27 × 10 4 0.9476
Table 7. IAE performance indices for PD and neural network controllers across all axes and input types. The best result in each case is highlighted.
Table 7. IAE performance indices for PD and neural network controllers across all axes and input types. The best result in each case is highlighted.
AxisInput TypePD ControllerNeural Network
XStep114.47128.08
Sinusoidal2.055.27
Triangular22.6324.07
YStep113.82109.15
Sinusoidal2.014.99
Triangular22.3323.77
ZStep70.96108.52
Sinusoidal11.594.97
Triangular22.3531.41
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

Pavon, W.; Chavez, J.; Guffanti, D.; Asiedu-Asante, A.B. Unmanned Aerial Vehicle Position Tracking Using Nonlinear Autoregressive Exogenous Networks Learned from Proportional-Derivative Model-Based Guidance. Math. Comput. Appl. 2025, 30, 78. https://doi.org/10.3390/mca30040078

AMA Style

Pavon W, Chavez J, Guffanti D, Asiedu-Asante AB. Unmanned Aerial Vehicle Position Tracking Using Nonlinear Autoregressive Exogenous Networks Learned from Proportional-Derivative Model-Based Guidance. Mathematical and Computational Applications. 2025; 30(4):78. https://doi.org/10.3390/mca30040078

Chicago/Turabian Style

Pavon, Wilson, Jorge Chavez, Diego Guffanti, and Ama Baduba Asiedu-Asante. 2025. "Unmanned Aerial Vehicle Position Tracking Using Nonlinear Autoregressive Exogenous Networks Learned from Proportional-Derivative Model-Based Guidance" Mathematical and Computational Applications 30, no. 4: 78. https://doi.org/10.3390/mca30040078

APA Style

Pavon, W., Chavez, J., Guffanti, D., & Asiedu-Asante, A. B. (2025). Unmanned Aerial Vehicle Position Tracking Using Nonlinear Autoregressive Exogenous Networks Learned from Proportional-Derivative Model-Based Guidance. Mathematical and Computational Applications, 30(4), 78. https://doi.org/10.3390/mca30040078

Article Metrics

Back to TopTop