Precision Parameter Identification in Quadcopter UAV Systems Using Particle Swarm Algorithm

Precision Parameter Identification in Quadcopter UAV Systems Using Particle Swarm Algorithm

Hacene Abanou* Moufid Mansour


Corresponding Author Email: 
habanou@usthb.dz
Page: 
141-148
|
DOI: 
https://doi.org/10.18280/jesa.580116
Received: 
29 November 2024
|
Revised: 
4 January 2025
|
Accepted: 
18 January 2025
|
Available online: 
31 January 2025
| Citation

© 2025 The authors. This article is published by IIETA and is licensed under the CC BY 4.0 license (http://creativecommons.org/licenses/by/4.0/).

OPEN ACCESS

Abstract: 

This paper presents a method for precise parameter identification in quadcopter Unmanned Aerial Vehicle (UAV) systems using the Particle Swarm Optimization Algorithm (PSO). Accurate identification of dynamic parameters such as thrust, drag coefficients, and moments of inertia is essential for ensuring stable and responsive flight control. The proposed approach employs the PSO algorithm to optimize these parameters by minimizing model fitting errors, using simulation and experimental data. The identification was conducted under closed-loop conditions, due to the inherent instability of quadcopter UAVs. The performance of this approach was validated using simulations performed on the obtained model of the quadcopter, which were compared with real data obtained from real-world experiments. The results demonstrate significant improvements in model accuracy, with enhanced control precision and trajectory tracking performance. The method shows great potential for UAV system identification and control design.

Keywords: 

Particle Swarm Optimization (PSO), quadcopter drone, system identification

1. Introduction

Over the last years, and particularly over the past ten years, there has been exponential growing development in MEMS technology; therefore, it has resulted in cost reductions and performance improvements. Thus, due to this development widespread interest in several research areas lead to rapid growth such as aeronautics, robotic, electronics, etc.

Nowadays, Unmanned Aerial Vehicles (UAVs) have grown in capability, prevalence, and public awareness. Therefore, they have started to play an increasing number of critical roles and excel in applications where human labor is prohibitively expensive and/or too dangerous for them to perform tasks. Various products and technologies have been developed recently.

Among the most common and probably used, Considerable attention and enormous prominence has been paid on the quadcopter drones structure. Some researchers used available commercial platforms like Parrot AR.drone, OS4 [1, 2], X4-Flyer [2, 3], STARMAC [2], Asctec Pelican, Arducopter or Mikrokopter. Other research projects are based on their own built structures.

Because of its lightweight design, simplicity, cost-effectiveness in manufacturing, as well as its agility and ease of control, the quadcopter platform has recently been increasingly employed for various tasks. It serves as a substitute for ground mobile robots incapable of undertaking specific assignments, such as aerial searches for disaster or sea rescues, inspections of power lines, bridges, and dams, monitoring forests, detecting fires, facilitating express goods delivery for trading companies, and performing military surveillance, monitoring, and espionage operations.

The performance demands associated with these tasks present challenges for control engineering, prompting significant efforts to enhance dynamic control performance.

The Quadcopter drone is characterized by strongly nonlinear, unstable, multivariable, and fully coupled dynamics, and necessitates a robust and stable controller for optimal stabilization. Developing an accurate dynamic model is not a straightforward task, leading researchers to explore various works and techniques in the literature. Researchers employ mathematical models and/or experimental identification methods to achieve precision and reject the model uncertainty that can tolerate the controller performance [4].

Generally speaking, methods for quadcopter model identification can be classified into three main approaches: white-box, grey-box, and black-box identification. the first one called white-box technique relies on direct computation of the quadcopter geometry and/or physical law to determine mathematical models, such as mass, moment of inertia, or motor coefficients to explain its behavior.

The grey-box model approach combines prior knowledge of the system's dynamics with experimental data to estimate unknown coefficients, offering improved forecasting capabilities for thrust and moment models.

In contrast, the black-box model approach uses input-output data to model system dynamics directly without relying on laws based on the first principles of physics. While this approach may lack physical interpretability, it is especially beneficial for modelling unconventional aircrafts whose dynamics are not easily understood or modelled from first principles. Many researchers concentrate on this area of identification due to its applicability in complex or poorly understood systems.

Alkowatly et al. [5] presented the mathematical model of a quadcopter UAV based on a biologically inspired routine. Initial parameters found by using analytical approximations, followed by a refinement process using a constrained Quasi-Newton (QN) optimization algorithm from MATLAB's toolbox. This optimization was performed by adjusting the nonlinear model parameters based on real flight data collected from onboard sensors.

Numerous control strategies have been proposed to address the difficulties raised above. For example, the studies [4-6] discussed the design of a dynamic model of a quadcopter UAV using real input/output measurement sets, in a Subspace identification routine as a black-box identification method. The resulting model is then used in a Linear Quadratic Regulator (LQR) control scheme.

Hoshu et al. [6] introduced a novel system identification method aimed at experimentally estimating the precise dynamic model of a heterogeneous multirotor. The method uses a frequency sampling filter, input excitation signals, and a sophisticated curve-fitting technique to derive transfer functions. Auto-tuned PID controllers were implemented in the obtained transfer functions to validate the accuracy.

While the techniques based on using experimental flight data have yielded satisfactory results, their limitations in handling convergence speed, accuracy, robustness to noise, complexity and nonlinear dynamics have led researchers to explore advanced optimization algorithms like genetic algorithms (GA) [7], gradient-based optimization, least squares techniques and Particle Swarm Optimization (PSO) algorithm.

Researchers in the literature tried to combine different methods to address common difficulties using traditional mathematical models due to model complexity and nonlinearity. Thus, growing interest has been gained in using machine-learning approaches like Neural network, genetic algorithms, and other technics for dynamic system modelling and identification.

PSO algorithm, which is a metaheuristic optimization technique, offers an effective solution for parameter identification. By mimicking the social behavior of particles, PSO algorithm iteratively improves candidate solutions, making it well-suited for optimizing nonlinear and complex systems like quadcopters [8-11].

The literature on PSO shows a variety of approaches and techniques where the studies [12, 13] survey and review investigate the evolution and adaptation of PSO in Swarm Intelligence, a field inspired by the collective behavior of social organisms. The review organizes research from 2017 to 2019 into technical categories, covering advances in PSO methodologies, hybridization techniques [14-16], and varied applications in domains like as healthcare, environmental science, and smart cities. This paper emphasizes both the merits and limits of current studies, providing approaches to resolve issues and identify future research areas in PSO.

In the study of Nabi et al. [17], a novel scheme for modeling and identifying dynamical systems was presented. The approach involves combining a hybrid Artificial Neural Network Autoregressive Moving Average (ANN-ARMA) with metaheuristic algorithms. It is based on artificial neural networks (ANN) and metaheuristic algorithms like Invasive Weed Optimization (IWO), Particle Swarm Optimization (PSO), Imperialist Competitive Algorithm (ICA), and Covariance Matrix Adaptation Evolution Strategy (CMA-ES).

Sanin-Villa et al. [18] investigated the use of metaheuristic algorithms for refining parameter estimation in dynamic systems, focusing on the inverted pendulum model. Three optimization methods: PSO, Continuous Genetic Algorithm (CGA), and Salp Swarm Algorithm (SSA) were evaluated.

In this section, we review relevant works on parameter identification and optimization algorithms applied to quadcopter UAV systems. We highlight the novelty of using PSO algorithm, which has shown potential in solving optimization problems in other domains but has not been extensively applied to quadcopter UAV parameter identification.

Tran and Chiou [19] introduced a hybrid controller design method combining Particle PSO with Evolutionary Programming (EP) to achieve optimized control gains quickly for complex systems. By integrating PSO and EP, the approach generates improved parameter sets for effective control. Applied to nonlinear micro air vehicle models, the proposed controllers demonstrate superior performance, highlighting the effectiveness of this combined algorithm in designing robust controllers for advanced technology applications.

Another example of hybridization is in the study [20], where the authors studied and evaluated Support Vector Machine (SVM) and K-Nearest Neighbor (KNN) methods for fault diagnosis in a SCARA robot manipulator. A comparative analysis was conducted to detect and isolate seven classes of sensor faults using torque, position, and speed as input vectors. A large dataset was employed for training and testing. The SVM method utilized a Gaussian kernel with parameters γ and penalty margin C, optimized via the PSO algorithm to maximize diagnostic accuracy.

In the study [21], an adaptive Proportional-Integral-Derivative (PID) controller optimized using a Neural Network-Particle Swarm Optimization (NN-PSO) algorithm was introduced. The adaptive controller dynamically adjusts its parameters to enhance performance, hence eliminating the need for extensive manual tuning. By leveraging NN-PSO, the PID controller is optimized in real-time, ensuring stability and precision in dynamic environments.

Our research expands on and develops the underlying work originally reported in the study [5]. By leveraging this contribution, we aim to explore new methodologies and tackle more complex challenges in the field. This extension refines and expands upon the original findings, contributing to a deeper understanding and advancing the overall scope of the research. In this paper, we present a detailed study on how the PSO can be applied to identify critical parameters in quadcopter UAV systems, enhancing model accuracy and improving control performance. The effectiveness of this approach is demonstrated through simulations and experimental validation.

The remainder of this article is organized as follows: Section 2 is dedicated to the description of the quadcopter drone platform used in this work, while section 3 discusses the Particle Swarm Optimization method for Quadcopter UAV system identification. In section 4 we present the simulations carried out using the PSO algorithm on the chosen quadcopter UAV, together with their results and discussions. The paper concluded with a summary that encapsulates the key findings of the current study and outlines directions for future research.

2. The Quadcopter Drone Platform

A quadcopter drone is a flying machine with four horizontally mounted propellers that are supported by two sets of orthogonal propeller engines. As seen in Figure 1, adjacent propellers rotate in a clockwise direction while the others rotate counterclockwise.

The quadcopter has 6 DOF which are three altitudes and three attitudes where we can control the DOFs by adjusting the spinning rate of each motor. However, it is impossible to reach or achieve all set points in drone space, and due to this notice, we can tell that the quadcopter drone is an underactuated system with nonlinear dynamics.

In most of papers in the literature, the quadcopter drone dynamic model has been demonstrated using Newton-Euler or Newton-Lagrange formalism [22-24] with consideration of different forces acting on the system.

In this paper two reference frames are considered to define the system coordinates. A Body fixed frame (B-frame) and an inertial Earth fixed frame (E-frame), both frames are designated using the ONED (North-East-Down) orientation for x, y and z axis respectively. The origin of the Body fixed frame is coincident with the quadcopter’s center of gravity.

We define in the inertial frame ONED the three Euler angles (roll, pitch and yaw) as η=[ϕθψ].

We define v=[pqr]T as angular velocity in Body frame of roll, pitch and yaw respectively and Vb=[uvw]T is the vector of linear velocity of x, y and z respectively.

The mathematical relation between ˙η and v is described as below:

˙η=[1tan(θ)sin(f)tan(θ)cos(f)0cos(f)sin(f)0sin(f)/cos(θ)cos(f)/cos(θ)]v        (1)

The kinematic and dynamics equations of the rigid body are as follows:

[mI3×303×303×3 J][Vb˙v]+[v×mVbv×Jv]=[Fbτb]            (2)

where, m is the mass in [Kg],Fb[N] and τb[N.m] are the forces and torques calculated in fixed frame respectively, Ia×a denotes the identity matrix, J moment of inertial matrix [Kg.m2]. The vectors v[rad/s] and Vb[m.s1] correspond to rotational and translation speed velocities, respectively.

Figure 1. Quadcopter frame reference showing the rotation direction

The moment of inertia is represented as a diagonal matrix, assuming symmetry and considering that the origin coincides with the quadcopter’s center of gravity.

The angular velocity of rotor i, denoted with ωi, creates force fi in the direction of the rotor axis. The angular velocity and acceleration of the rotor also create torque τd around the rotor axis.

fi=bω2i       (3)

τd=dω2i        (4)

where, b is the lift coefficient, and d is the drag constant. Thrust Γ is produced in the direction of the body's z-axis by the combined forces of the rotors. Torque τB consists of the torques τϕ,τθ and τψ in the direction of the corresponding body frame angles.

Γ=4i=1fi=b4i=1ω2i           (5)

τB=[τϕτθτψ]=[lb(ω22+ω24)lb(ω21+ω23)4i=1τd]        (6)

The gyroscopic effect produced by the angular speed rate, can be defined as follow:

O(v)Ω=[03×1Jr(ωbb/e×[001])ωr]=Jr[03×1qp0]ωr        (7)

where, × is the cross product and ωr=ω1+ω2ω3+ω4.

The acceleration caused by the gravitational effect g[m/s2] is expressed as follows:

GB(v)=[Fb03×1]=[R1ΘFe03×1]=[R1Θ[00mg]03×1]=[mgsin(θ)mgcos(θ)sin(f)mgcos(θ)cos(f)03×1]    (8)

Finally, thrust and torque can be extracted straightforward from the selected inputs. The equation of motion can be expressed by substitution of the torques and forces effect in the right-hand side of Eq. (2), therefore the equation can be expressed as:

˙p=[qr(JyyJzz)+JrqΩr+τϕ]/Jxx˙q=[pr(JzzJxx)JrpΩr+τθ]/Jyy˙r=pq(JxxJyy)+τψ]/Jzz˙u=rvqwgsin(θ)˙v=pwru+gcos(θ)sin(ϕ)˙w=qupv+gcos(θ)cos(ϕ)Γ/m       (9)

Additionally, Eq. (1) can be used to directly extract the angles rate stated in the E-frame as follows:

˙ϕ=p+qtan(θ)sin(ϕ)+rtan(θ)cos(ϕ)

˙θ=qcos(ϕ)rsin(ϕ)            (10)

˙ψ=qsin(ϕ)cos(θ)+rcos(ϕ)/cos(θ)

3. Particle Swarm Optimization Algorithm Overview

Particle Swarm Algorithm as originally proposed by Kennedy and Eberhart (1995), is a meta-heuristic optimization technique that simulates the social behavior of groups, such as bird flocks or fish schools, to find optimal solutions in a search space. The algorithm uses a population of potential solutions (known as particles) and moves these particles about in the search space using simple mathematical calculations based on the particle's position and velocity.

PSO was utilized in this paper for offline parameter estimation based on collected data to enhance model accuracy and reliability. The collected dataset, consisting of input-output pairs, served as a foundation for defining an objective function that quantified the error between the mathematical model outputs and the actual measurements as it is illustrated in Figure 2. By employing PSO, a swarm of candidate solutions explored the parameter space iteratively, adjusting their positions based on individual and collective performance.

The algorithm is based on the following:

- Velocity and Position Updates:

Firstly, a group of particles with a random velocity vector vi(t) and random spatial position vector xi(t) are generated. This allows the particle swarm to be evenly distributed throughout the entire space, maximizing the search range and reducing the likelihood of converging to a local optimal solution [25]. The vector vi(t)a and xi(t) are defined as follows:

vi(t)=[vi1(t),vi2(t),,viM(t)]xi(t)=[xi1(t),xi2(t),.,xiM(t)]       (11)

where, M is the number of the parameters to be identified within the identification process.

Subsequently, particles adjust their velocities and positions in the parameter space based on their best-known position Pbest  and the best-known positions of neighboring particles gbest , guiding the swarm towards better solutions.

- Convergence: The algorithm iteratively refines the particle positions until convergence criteria are met, such as achieving a minimal fitting error or reaching a specified number of iterations.

- Particle Representation: We choose each particle to represent a set of quadcopter parameters, including thrust and drag coefficients and moments of inertia.

- Fitness Function: Let x represent the estimated parameter vector Θ. The objective of the Particle Swarm Algorithm here is to minimize the error between the UAV's simulated output, based on the model of the Eqs. (9) to (10), and the actual flight data. We can define the equation as:

fobj=Tt=1            (12)

The fitness function, which evaluates this error, guides the movements of the particles to optimize the parameter estimates accordingly.

Figure 2. Particle Swarm Optimization (PSO)-based identification approach

In our case, the algorithm is presented as follows:

Algorithm 1 Pseudo code for the Particle Swarm Optimization

  • Input

Objective function (fitness function), upper bound (ub) and lower bound (lb), population size (N), inertia weight (\varpi),\left(c_1\right. and \left.c_2\right) individual and social cognitive acceleration coefficients, respectively. The terms r_1 \sim U(0,1) and r_2 \sim U(0,1) are the random variables corresponding to these acceleration coefficients. T Is the number of iterations,

  • Initialization

Initialize random position ( x ) and velocity ( v ) within the search space boundaries.

Assign P_{\text {best }} and g_{\text {best }} (based on the objective function).

  • Loop

1: For iteration t=1, . . . , T do

2:       For i=1, . . . , N do

3: Update velocity: v_i(t)=\varpi v_i(t-1)+

c_1 r_1\left(P_{\text {best }, i}-x_i(t-1)\right)+c_2 r_2\left(g_{\text {best }, i}-x_i(t-1)\right)

4: Update position values: x_i(t)=\mathrm{x}_i(\mathrm{t}-1)+\mathrm{v}_i(t)

5: Check x_i(t) within the boundaries: If x_i(t)> x_{u b} \rightarrow x_i(t)=x_{u b} and If x_i(t)<x_{l b} \rightarrow x_i(t)=x_{l b}

6: Evaluate the objective function f_{x_i}

7: Update P_{\text {best }} and g_{\text {best }}: P_{\text {best }}=x_i if f_{x_i} is better than f_{P_{\text {best }, i}}, and g_{\text {best }}=P_{\text {best }, i} if f_{P_{\text {best }, i}} is better than f_{g_{\text {best }}}

8: If there is no convergence of the current solution and if t>T

9:      end For

10:    Print Output: g_{\text {best }} and f_{g_{b e s t}}

         11: end For

4. Simulations and Experimental Results

Quadcopters are inherently unstable systems that cannot be controlled using open loop methods. In this investigation, Ascending Technologies GmbH’s Pelican UAV platform for research was used. The platform has an integrated stabilizing controller that runs at 1 kHz on an embedded ARM7 microprocessor. This controller enables the operator to pilot the quadcopter by sending orientation reference inputs (roll, pitch, and yaw angles) and throttle values via a transmitting device. This setup ensures data collecting to take place while flying a closed-loop stable system. The measurements were gathered from the onboard MEMS gyroscopes where body rates are (p, q, r), and the Attitude and Heading Reference System (AHRS) estimates the attitude angles (\phi, \theta, \psi). Additionally, the onboard MEMS accelerometers capture the body accelerations \left(a_x, a_y, a_z\right), which are corrected for gravitational effects using AHRS attitude estimates. During test flights, input and output data are recorded using an SD card to store the measurements via I2C connection with an on-board ARM7 embedded microcontroller at a sample rate of 50Hz (measurements were taken every 20ms) as the quadcopter’s attitude and throttle are manually adjusted. Three experimental data sets, are collected each 500 seconds in duration, for system identification and model validation.

In this paper, to verify the effectiveness of the proposed PSO-based identification method, a series of simulations were carried out using MATLAB®. Three data sets were utilized:

● Data Set 1: Used to train the model using Particle Swarm Optimization, with the initial values carefully selected beforehand.

● Data Set 2 and Data Set 3 are test data that were not involved in the identification process, the performance of the proposed method is verified using these data sets. The validity of the results is further confirmed through direct comparison between the identified model and the actual flight test data.

The simulation results are presented in Figures 3 to 8, and Tables 1 to 2.

Table 1 gives an overview of the results from the three data sets. The Mean Squared Error (MSE) is used as a fitness function as it is calculated from Eq. (13) for each set, as well as the corresponding fitting percentages.

Table 1. The calculated model fitting error E using both the initial estimates and the refined model parameters

 

MSE for Initial Guess

MSE QN Based Estimation

MSE PSO Based Estimation

Enhancement Over Initial Guess Result (Baseline)

Enhancement Over QN Result [5]

SET1 (Training)

14.64

7.67

6.388

0.5637

0.1672

SET2 (Validation)

16.81

8.79

6.694

0.6018

0.2384

SET3 (Validation)

18.93

8.71

7.309

0.6139

0.1608

Table 2 represents model parameters obtained from identification-based PSO.

Table 2. Refined model parameters based on Particle Swarm Optimization throughout the system identification

Parameter

PSO Algorithm Obtained Value

Thrust Coefficient b

2.33E-05

Drag Coefficient d

4.96E-07

Moments of Inertia Jxx

1.00E-02

Moments of Inertia Jyy

1.36E-02

Moments of Inertia Jzz

2.92E-02

Rotor Inertia Jr

5.00E-05

Figures 3 to 5 represent the attitude angles, body accelerations, and body rates, respectively, with Data Set 1 used to train the PSO model.

Figure 3. Three Euler angle model output fitting in a closed-loop configuration using Particle Swarm Optimization with the training dataset

Figure 4. Body accelerations for model output fittings in a closed-loop configuration using Particle Swarm Optimization with the training dataset

Figure 5. Angular velocities for model output fittings in a closed-loop configuration using Particle Swarm Optimization with the training dataset

Figures 6 to 8 represent the body accelerations, body rates, and attitude angles using the obtained model parameters with Data Sets 2 and 3 to validate the PSO-based model. The blue line, dashed red and yellow lines in the Figures represent time segments of the real measurements, the mathematical model outputs using the optimized parameter estimates from [5] and the PSO-based identification technique, respectively.

Figure 6. Model output fitting of the three Euler angles in a closed-loop configuration using an unseen dataset for model validation

Figure 7. Model output fittings of the three body acceleration in a closed-loop configuration using an unseen dataset for model validation

Figure 8. Model output fitting of the angular velocities in a closed-loop configuration using an unseen dataset for model validation

From the figures, we extract metrics that we present in Table 1, demonstrating significant percentage improvements. The current model based on the PSO method shows a 61.37% enhancement over the baseline (initial guess) and a 16.08% improvement over the results from the study [5]. Additionally, it achieves further improvements of 17.67% and 18.08% compared to our previous results in the study [22], obtained using Canonical Variate Analysis (CVA) and the Multi-Output Error State Space (MOESP) methods, respectively. These results highlight a clear advancement over prior work, as the identified parameters significantly enhance the accuracy of the quadcopter model compared to the initial estimates across all three data sets. Error metrics, including Mean Squared Error (MSE) and fitting percentage, were used to evaluate the effectiveness of the PSO in reducing model-fitting errors.

We have to mention that, the quadcopter’s motors, rotors, and frame generate vibrations during operation that affect the gyroscope's ability to accurately measure angular velocity, leading to errors in motion tracking and control systems. These disturbances, typically characterized as random vibrations inducing angular velocity fluctuations and are often modeled as white noise, Despite the disturbances in body rate for p, q, r, the model still can track the dynamics. These results confirm the effectiveness of the current approach in reducing the mean squared error and improving the fitting percentage, thus achieving a more accurate and reliable quadcopter model.

The results demonstrate that the PSO algorithm provides a robust and effective method for identifying key parameters in quadcopter UAV systems. Compared to traditional techniques, PSO offers several advantages, including faster convergence and better handling of noise in the data.

However, we have found that the PSO algorithm has some limitations, such as the sensitivity to parameter initialization and the need for high-quality experimental data.

5. Conclusions

This paper explores the potential of the PSO algorithm for precise parameter identification in quadcopter UAV systems. PSO, which is a population-based optimization algorithm inspired by the collective behavior of social animals, has shown promise in addressing nonlinear, multidimensional problems, making it a suitable candidate for UAV system identification. Our study demonstrates how PSO can be applied to estimate key dynamic parameters, such as thrust, drag coefficients, and moments of inertia, which are critical for improving model accuracy and control performance. The proposed approach was validated through simulations and experimental results, indicating notable enhancements in model accuracy. While these findings suggest PSO's suitability for UAV system identification, further research is necessary to explore real-time implementations and its potential application to other UAV types, with the aim of advancing online parameter refinement. This is a subject of future research.

Nomenclature

O_{NED}

North-East-Down orientation for x, y and z axis respectively

\eta

Euler angles

\phi

roll

\theta

pitch

\psi

yaw

v

angular velocity in Body frame, rad/s

p

angular velocity of roll

q

angular velocity of pitch

r

angular velocity of yaw

V^b

Linear velocity, m/s

u

Linear velocity of x, m/s

v

Linear velocity of y, m/s

w

Linear velocity of z, m/s

m

Mass in Kg

F^b

Forces calculated in fixed frame, N

\tau^b

Torques calculated in fixed frame, N.m

\omega_i

The angular velocity of rotor i

J

Moment of inertial matrix, Kg.m2

\Gamma

Thrust

g

Acceleration due the gravity effect, m.s-2

b

lift coefficient

d

drag constant

  References

[1] Bouabdallah, S., Siegwart, R. (2007). Full control of a quadrotor. In 2007 IEEE/RSJ International Conference on Intelligent Robots and Systems, San Diego, CA, USA, pp. 153-158. https://doi.org/10.1109/IROS.2007.4399042

[2] Charland-Arcand, G. (2014). Contrôle non linéaire par backstepping d'un hélicoptère de type quadrotor pour des applications autonomes. Doctoral dissertation, École de Technologie Supérieure.

[3] Ouchi, Y., Kinoshita, K., Watanabe, K., Nagai, I. (2014). Control of position and attitude of the tethered X4-Flyer. In 2014 IEEE/SICE International Symposium on System Integration, Tokyo, Japan, pp. 706-711. https://doi.org/10.1109/SII.2014.7028125

[4] Kim, J., Gadsden, S.A., Wilkerson, S.A. (2019). A comprehensive survey of control strategies for autonomous quadrotors. Canadian Journal of Electrical and Computer Engineering, 43(1): 3-16. https://doi.org/10.1109/CJECE.2019.2920938

[5] Alkowatly, M.T., Becerra, V.M., Holderbaum, W. (2015). Body-centric modelling, identification, and acceleration tracking control of a quadrotor UAV. International Journal of Modelling, Identification and Control, 24(1): 29-41. https://doi.org/10.1504/IJMIC.2015.071697

[6] Hoshu, A.A., Wang, L., Ansari, S., Sattar, A., Bilal, M.H.A. (2022). System identification of heterogeneous multirotor unmanned aerial vehicle. Drones, 6(10): 309. https://doi.org/10.3390/drones6100309

[7] Mansour, M. (2016). A genetic algorithm identification technique for the estimation of process derivatives and model parameters in on-line optimization. In 2016 5th International Conference on Systems and Control (ICSC), Marrakesh, Morocco, pp. 120-125. https://doi.org/10.1109/ICoSC.2016.7507076

[8] Mercangöz, B.A. (2021). Applying particle swarm optimization: New solutions and cases for optimized portfolios. Springer Nature. https://doi.org/10.1007/978-3-030-70281-6 

[9] Osaba, E., Yang, X.S. (2021). Applied Optimization and Swarm Intelligence. Singapore: Springer. https://doi.org/10.1007/978-981-16-0662-5

[10] Bian, Q., Wang, X.M., Xie, R., Li, T., Ma, T.L. (2016). Small scale helicopter system identification based on Modified Particle Swarm Optimization. In 2016 IEEE Chinese Guidance, Navigation and Control Conference (CGNCC) Nanjing, China, pp. 182-186. https://doi.org/10.1109/CGNCC.2016.7828780

[11] Bounouara, N., Ghanai, M., Chafaa, K. (2021). Metaheuristic optimization of PD and PID controllers for robotic manipulators. Journal Européen des Systèmes Automatisés, 54(6): 835-845. https://doi.org/10.18280/jesa.540605

[12] Gad, A.G. (2022). Particle swarm optimization algorithm and its applications: A systematic review. Archives of Computational Methods in Engineering, 29(5): 2531-2561. https://doi.org/10.1007/s11831-021-09694-4

[13] Shami, T.M., El-Saleh, A.A., Alswaitti, M., Al-Tashi, Q., Summakieh, M.A., Mirjalili, S. (2022). Particle swarm optimization: A comprehensive survey. IEEE Access, 10: 10031-10061. https://doi.org/10.1109/ACCESS.2022.3142859

[14] Zhang, Y., Yu, H. (2023). Application of hybrid swarming algorithm on a UAV regional logistics distribution. Biomimetics, 8(1): 96. https://doi.org/10.3390/biomimetics8010096

[15] Tao, X., Liu, K., Yang, J., Chen, Y., Chen, J., Zhu, H. (2025). Sliding mode backstepping control of excavator bucket trajectory synovial in particle swarm optimization algorithm and neural network disturbance observer. In Actuators. Actuators, 14(1): 9. https://doi.org/10.3390/act14010009

[16] Liu, Y., Zhang, H., Zheng, H., Li, Q., Tian, Q. (2025). A spherical vector-Based adaptive evolutionary particle swarm optimization for UAV path planning under threat conditions. Scientific Reports, 15(1): 2116. https://doi.org/10.1038/s41598-025-85912-4

[17] Nabi, Z., Ouali, M.A., Ladjal, M., Bennacer, H. (2024). A novel ANN-ARMA scheme enhanced by metaheuristic algorithms for dynamical systems and time series modeling and identification. Revue d'Intelligence Artificielle, 38(3): 939-956. https://doi.org/10.18280/ria.380320

[18] Sanin-Villa, D., Rodriguez-Cabal, M.A., Grisales-Noreña, L.F., Ramirez-Neria, M., Tejada, J.C. (2024). A comparative analysis of metaheuristic algorithms for enhanced parameter estimation on inverted pendulum system dynamics. Mathematics, 12(11): 1625. https://doi.org/10.3390/math12111625

[19] Tran, H.K., Chiou, J.S. (2016). PSO-based algorithm applied to quadcopter micro air vehicle controller design. Micromachines, 7(9): 168. https://doi.org/10.3390/mi7090168

[20] Maincer, D., Benmahamed, Y., Mansour, M., Alharthi, M., Ghonein, S.S. (2023). Fault diagnosis in robot manipulators using svm and knn. Intelligent Automation & Soft Computing, 35(2): 1957-1969. http://dx.doi.org/10.32604/iasc.2023.029210

[21] Wu, L.F., Wang, Z., Rastgaar, M., Mahmoudian, N. (2025). Adaptive velocity control for UAV boat landing: A neural network and particle swarm optimization approach. Journal of Intelligent & Robotic Systems, 111(1): 1-18. https://doi.org/10.1007/s10846-024-02201-4

[22] Hacene, A., Moufid, M. (2018). Quadrotor UAV dynamics modeling based on subspace identification system. In 2018 International Conference on Electrical Sciences and Technologies in Maghreb (CISTEM) Algiers, Algeria, pp. 1-6. https://doi.org/10.1109/CISTEM.2018.8613584

[23] Ryll, M., Bülthoff, H.H., Giordano, P.R. (2014). A novel overactuated quadrotor unmanned aerial vehicle: Modeling, control, and experimental validation. IEEE Transactions on Control Systems Technology, 23(2): 540-556. https://doi.org/10.1109/TCST.2014.2330999

[24] Bouabdallah, S. (2007). Design and control of quadrotors with application to autonomous flying (No. 3727). EPFL. https://doi.org/10.5075/epfl-thesis-3727

[25] Zdiri, S., Chrouta, J., Zaafouri, A. (2020). Inertia weight strategies in multiswarm particle swarm optimization. In 2020 4th International Conference on Advanced Systems and Emergent Technologies (IC_ASET), Hammamet, Tunisia, pp. 266-271. https://doi.org/10.1109/IC_ASET49463.2020.9318226