Next Article in Journal
Multiple Linear Regression-Based Correlation Analysis of Various Critical Weather Factors and Solar Energy Generation in Smart Homes
Previous Article in Journal
Enhancing Fault Detection in Industry 4.0 by Introducing a Power and Fault Behavior Monitoring Tool for Programmable Logic Controllers with Validation Through a Virtual Manufacturing System
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Proceeding Paper

Robustness Analysis of LQR-PID Controller Based on PSO and GWO for Quadcopter Attitude Stabilization †

1
Identification, Command, Control and Communication Laboratory LI3CUB, Mohamed Khider University, Biskra 07000, Algeria
2
Department of Electronics, Mostefa Ben Boulaïd University, Batna 05000, Algeria
*
Author to whom correspondence should be addressed.
Presented at the 5th International Electronic Conference on Applied Sciences, 4–6 December 2024; https://sciforum.net/event/ASEC2024.
Eng. Proc. 2025, 87(1), 105; https://doi.org/10.3390/engproc2025087105
Published: 12 September 2025
(This article belongs to the Proceedings of The 5th International Electronic Conference on Applied Sciences)

Abstract

The robust control of quadcopters is essential for maintaining stability and performance in dynamic environments. This paper examines the effectiveness of Particle Swarm Optimization (PSO) and Grey Wolf Optimization (GWO) for tuning LQR-PID controllers tailored for a quadcopter constrained to rotational degrees of freedom, aiming to enhance attitude stabilization and perform a comparative robustness analysis under various disturbances. Using PSO and GWO to optimize the LQR controller’s Q and R matrices, the study minimizes a cost function based on attitude error and control effort. The optimized controllers are evaluated in a Simulink environment with external perturbation forces; noise perturbations and sudden impulse disturbances are introduced via feedback vector perturbations to simulate real-world operational challenges. The results reveal distinct robustness characteristics: the PSO-optimized controller achieves faster convergence with higher sensitivity to disturbances, while the GWO-optimized controller performs better under extreme parameter variations. By providing a detailed comparison of these optimization techniques, the study offers valuable insights into selecting the most suitable method for robust and reliable quadcopter attitude control.

1. Introduction

Quadcopters, a class of unmanned aerial vehicles (UAVs), are widely used in applications like surveillance, search-and-rescue, and precision delivery due to their agility, vertical takeoff and landing (VTOL) capability, and ability to navigate complex environments [1,2]. Their effectiveness depends on maintaining stable flight attitudes (pitch, roll, yaw) under dynamic conditions such as wind disturbances and external perturbation forces [3,4]. However, the nonlinear dynamics and susceptibility to external perturbations make quadcopter control challenging, particularly in mission-critical scenarios [5]. These challenges highlight the need for robust control strategies that ensure stability and efficiency in unpredictable conditions [2,4].
Recent advances in robust quadcopter control employ hybrid and adaptive strategies to address disturbances and uncertainties. Bhattacharjee and Subbarao [6] combined sliding mode control (SMC) for attitude stabilization with model predictive control (MPC) for position tracking, solving constrained optimization problems to achieve robust trajectory tracking under disturbances. Alonge et al. [7] developed a robust feedback linearization approach using extended state observers to estimate aerodynamic disturbances online, outperforming standard methods in dynamic behavior. For chattering reduction, Thanh and Hong [8] designed an adaptive second-order sliding mode controller with PID sliding surfaces that requires no prior disturbance bounds. Xie et al. [9] implemented adaptive backstepping control with disturbance estimators to handle unknown mass/inertia parameters while ensuring smooth convergence. Yanez-Badillo et al. [10] integrated B-spline neural networks with Particle Swarm Optimization to create vibration-resistant controllers that eliminate velocity measurements. Betancourt-Vera et al. [11] experimentally validated a hybrid MPC-UDE (Uncertainty and Disturbance Estimator) framework for perturbation-resistant trajectory tracking. Collectively, these approaches demonstrate that modern robustness relies on real-time disturbance estimation, adaptive compensation, and hybrid architectures to address quadcopters’ complex uncertainty landscape.
Metaheuristic optimization methods like Particle Swarm Optimization (PSO) offer solutions for complex control problems, such as tuning Linear Quadratic Regulators (LQR), by balancing stabilization and control effort without requiring gradients [12,13,14]. However, PSO can suffer from premature convergence and limited diversity, which adaptive or hybrid approaches (e.g., with fuzzy logic) aim to mitigate [12,15,16]. Similarly, Grey Wolf Optimization (GWO), inspired by wolf pack hierarchies, provides strong exploration capabilities and effectively balances exploration-exploitation, making it suitable for control system optimization [17,18,19]. While GWO has shown success in UAV trajectory planning [20], its potential for real-time LQR-PID tuning remains less explored compared to PSO.
The LQR-PID controller combines the optimal state regulation of LQR with PID’s error correction, ensuring effective stabilization for quadcopters [21]. However, tuning the Q and R matrices is critical for achieving a balance between stability, energy efficiency, and robustness to disturbances [22,23]. While traditional tuning methods lack adaptability to dynamic perturbations, metaheuristic approaches like PSO and GWO automate the tuning process and enhance robustness under diverse conditions [24,25].
This study addresses a critical gap in robust quadcopter control by providing the first systematic comparison of Particle Swarm Optimization (PSO) and Grey Wolf Optimization (GWO) for tuning LQR-PID controllers under combined wind and impulse disturbances. Unlike Bhattacharjee’s SMC-MPC [6], which focuses on hybrid control architectures, Alonge’s observer-based FL [7] for disturbance estimation, or Ghiloubi’s PSO-LQR tuning [13], our work directly contrasts both metaheuristics’ trade-offs: PSO enables faster disturbance recovery with smoother control signals, while GWO delivers superior disturbance rejection at the cost of voltage saturation. These insights empower UAV designers to make mission-aware algorithm selections for unpredictable aerial environments.
The remainder of this paper is organized as follows: Section 2 details the quadcopter dynamic model and simulation framework. Section 3 presents the LQR-PID control architecture and metaheuristic optimization methodology. Section 4 evaluates controller performance under disturbances, and Section 5 concludes with key findings and future research directions.

2. Quadcopter Dynamic Model and Mathematical Formulation

The Quanser 3-DOF Hover is an experimental platform designed to emulate the flight dynamics of vertical lift-off vehicles (Figure 1). It allows for rotation about the roll, pitch, and yaw axes, enabling the study and development of control laws for such systems. The setup consists of a planar frame with four propellers, each driven by a DC motor, mounted on a pivot joint that provides three degrees of freedom. This configuration facilitates the analysis of flight dynamics and control strategies in a controlled environment [26,27].
In the 3-DOF Hover system, the platform is horizontal (parallel to the ground) when both the pitch and roll angles are zero. A positive yaw rate indicates counterclockwise rotation about the vertical axis. Similarly, positive pitch and roll rates correspond to counterclockwise rotations about their respective axes [28].
The 3-DOF helicopter system representation is given by the manufacturer as follows:
x ˙ = A x + B u   y ˙ = C x + D u
The state vector is as follows:
x t =     θ y , θ p , θ r ,   θ ˙ y ,   θ ˙ p ,   θ ˙ r
The output vector is written as follows:
y t =     θ y , θ p , θ r
The control vector is written as follows:
u   =     U F , U B , U r , U l  
where U f , U B , U r ,   U l are the voltages applied to the front, back, right, and left motors, respectively.
The corresponding 3 DOF hover state space matrices:
A = 0 0 0 1 0 0 0 0 0 0 1 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 , B = 0             0 0             0 0             0 0           0 0           0 0           0 K t J y K t J y L K f J p L K f J p 0 0 K t J y K t J y 0 0 L K f J r L K f J r ,   C = 1 0 0 0 0 0 0 1 0 0 0 0 0 0 1 0 0 0
The main physical and aerodynamic parameters of the quadrotor used in this study are summarized in Table 1.

3. Proposed Control Approach

This study employs a hybrid control method combining LQR and PID controllers, optimized using Particle Swarm Optimization (PSO) and Grey Wolf Optimization (GWO). PSO and GWO are used to tune the LQR weighting matrices Q and R, enhancing control performance and robustness under dynamic conditions. The LQR ensures optimal state feedback, while the PID compensates for steady-state errors and unmodeled disturbances, achieving improved quadcopter attitude stabilization and disturbance rejection.

3.1. LQR-PID Controller

The Linear Quadratic Regulator (LQR) is a state-feedback control method that minimizes a cost function to regulate linear time-invariant systems. The goal is to determine the optimal control input u ( t ) that minimizes the following:
J = 0 x t T Q x ( t ) + u t T R u t d t
where x ( t ) is the state vector, u ( t ) is the control input, Q penalizes state deviations, and R penalizes control effort. The optimal control law is written as follows:
u ( t ) = K x ( t )
with the feedback gain matrix K calculated as follows:
K = R 1 B T P
Here, P is the solution for the continuous-time algebraic Riccati equation, written as follows:
A T P + P A + Q P B R 1 B T P = 0
In this control architecture, the error signals are processed through PID controllers to generate intermediate control signals. These signals are then adjusted by the LQR-derived gain matrix K to produce the final control inputs. The PID parameters were fine-tuned through a trial-and-error approach to achieve satisfactory performance. This configuration leverages the PID controllers for immediate error correction, while the LQR component enhances system robustness, particularly in the context of evaluating the effectiveness of PSO and GWO optimizations on the LQR controller’s robustness.
To ensure a fair comparison between PSO and GWO optimization of the LQR weighting matrices, identical PID gains were used for both controllers where we write the following:
K p = 6.7 ,   K I = 0.4 ,   K D = 2.7

3.2. PSO Optimization for LQR Controller

The Particle Swarm Optimization algorithm is employed to fine-tune the weighting matrices Q and R in the Linear Quadratic Regulator framework, thereby optimizing the state-feedback gain matrix K. This optimization enhances the controller’s performance by effectively balancing state regulation and control effort. Optimization process steps are:

3.2.1. Initialization

  • Define a population of particles, each representing potential values for the elements of matrices Q and R.
  • Initialize particle velocities and positions randomly within predefined bounds.

3.2.2. Fitness Evaluation

  • For each particle, compute the corresponding gain matrix K using the LQR design equations.
  • Simulate the closed-loop system’s response with the computed K.
  • Evaluate the performance using a cost function J, typically defined as (9).

3.2.3. Update Personal and Global Bests

  • Track the best position (Q and R values) each particle has achieved (personal best).
  • Identify the overall best position found by any particle (global best).

3.2.4. Velocity and Position Update

  • Update each particle’s velocity v i and position x i using the following:
v i t + 1 = w   v i t + c 1   r 1   p i x i t + c 2   r 2 g x i t
x i t + 1 = x i t + v i t + 1
where the following are defined:
  • v i is the current velocity of particle i ;
  • w is the inertia weight;
  • c 1 and c 2 are personal and social acceleration coefficients, respectively;
  • r 1 and r 2 are random numbers between 0 and 1;
  • p i is the personal best position of particle i ;
  • g is the global best position.

3.2.5. Iteration

  • Repeat the evaluation and update steps for a predetermined number of iterations or until convergence criteria are met.
  • By iteratively adjusting Q and R through PSO, the LQR controller’s gain matrix K is optimized, leading to improved system performance in terms of stability and response characteristics.

3.3. GWO Optimization for LQR Controller

The Grey Wolf Optimizer is a nature-inspired metaheuristic algorithm that emulates the leadership hierarchy and hunting strategy of grey wolves. In the context of control systems, GWO can be employed to fine-tune the weighting matrices Q and R of a linear quadratic regulator to achieve optimal performance. Optimization process steps are as follows:
  • Initialization: define an initial population of candidate solutions, each representing potential Q and R matrices. Assign hierarchical roles to the top candidates: alpha (α), beta (β), and delta (δ), with the remaining candidates designated as omega (ω).
  • Position Update: update the positions of candidate solutions based on the positions of α, β, and δ, simulating the encircling and hunting behaviors of grey wolves.
  • Evaluation: assess the fitness of each candidate by implementing the corresponding LQR controller and evaluating its performance using a predefined cost function.
  • Hierarchy Update: rank the candidates based on their fitness scores and update their hierarchical roles accordingly.
  • Iteration: repeat the position update and evaluation steps until convergence criteria are met or a specified number of iterations is reached.
  • By iteratively refining the Q and R matrices through the GWO algorithm, the LQR controller’s performance can be optimized, leading to improved system stability and robustness.
Figure 2 illustrates the cascaded PID-LQR control architecture for quadcopter attitude stabilization. Desired yaw, pitch, and roll angles are compared with measured values to generate tracking errors, which are processed by the PID controller to produce intermediate commands ( U y , U p , U r ). These PID outputs, along with angular velocities ( y ˙ , p ˙ , r ˙ ), form the 6-dimensional state vector for the LQR controller. The PSO/GWO optimization continuously tunes the Q and R weighting matrices to minimize the LQR cost function. The optimized LQR then computes motor commands ( U F r o n t , U B a c k , U R i g h t , U L e f t ) through state feedback U = K x , where K is the gain matrix. These commands drive the 3-DOF system.

4. Results and Discussion

4.1. Optimization Results

Before evaluating disturbance response, we first examine the optimization process itself, where PSO and GWO tuned the LQR-PID controller gains by minimizing the cost function J (defined in Equation (6)). Figure 3 illustrates the cost function convergence for both PSO and GWO, while Equations (12) and (13) present the resulting optimal gain matrices.
K P S O = 133.59 128.01 0.00 47.34 38.03 0.00 133.59 128.01 0.00 47.34 38.03 0.00 133.59 0.00 97.40 47.34 0.00 51.02 133.59 0.00 97.40 47.34 0.00 51.02
K G W O = 88.70 146.26 0.00 2.23 36.22 0.00 88.70 146.26 0.00 2.23 36.22 0.00 88.93 0.00 179.84 1.90 0.00 36.22 88.94 0.00 179.84 2.07 0.00 36.22
The optimization of the LQR K-gain using PSO and GWO showed performance differences. PSO minimized the cost function to 0.060 after 100 iterations, while GWO achieved a lower value of 1.5 × 1013 within the same iterations.

4.2. Trajectory Tracking and Robustness Analysis

Figure 4 presents the tracking performance of the three rotational angles—yaw, pitch, and roll—under multiple desired values and noise perturbations introduced at 2, 12, and 22 s, with increasing intensity. Both the PSO-optimized and GWO-optimized controllers exhibited effective tracking with no overshoot. The PSO-based controller achieved steady-state faster, while the GWO-based controller exhibited a slight delay but maintained stability.
In terms of robustness, the GWO-based controller demonstrated a more robust response, deviating less from the desired angles during perturbations. However, once the perturbation ceased, the PSO-based controller recovered and returned to the desired angle more quickly than the GWO-based controller. These patterns are quantified through six key metrics in Table 2.
The results show two main advantages: GWO kept the quadcopter steadier during disturbances with 24–40% smaller deviations (2.1° vs. 3.5° in yaw), while PSO recovered faster after disturbances ended (0.4 s vs. 1.1 s for roll angle recovery). This means GWO is better for maintaining position in windy conditions, while PSO reacts quicker when disturbances stop.
Figure 5 shows the front motor voltage response during disturbances, with consistent patterns observed across all motors (back, left, and right). The GWO-optimized controller exhibits frequent voltage saturation with sharp, high-frequency spikes during perturbations—particularly at t = 12 s and t = 22 s—reflecting its aggressive disturbance compensation strategy. This behavior correlates with GWO’s superior attitude holding but risks motor overheating and reduced actuator lifespan. Conversely, the PSO controller maintains smoother voltage profiles with 40–50% lower d v d t rates, demonstrating its emphasis on control efficiency. While this results in slightly larger attitude deviations (Figure 4), it reduces current ripple and extends motor service intervals.
Figure 6 demonstrates sinusoidal trajectory tracking under progressively stronger disturbances (2 s, 12 s, 22 s), revealing distinct controller behaviors: GWO maintained exceptional disturbance rejection with minimal deviation (near-zero oscillation during perturbations), while PSO exhibited moderate oscillations but achieved full recovery within 0.5–1 s post-disturbance. Critically, during the high-intensity 22 s disturbance, GWO failed to fully regain trajectory alignment even after 5 s, particularly evident in pitch angle, whereas PSO consistently converged to the reference within 0.5 s across all axes. This highlights GWO’s superior in-disturbance robustness versus PSO’s advantage in post-disturbance recovery agility.

5. Conclusions

This study provides a comprehensive comparison of Particle Swarm Optimization (PSO) and Grey Wolf Optimization (GWO) for tuning LQR-PID controllers in quadcopter attitude stabilization. Our results establish clear performance trade-offs that directly inform real-world UAV deployment: The PSO-optimized controller excels in missions requiring rapid recovery and energy efficiency, such as emergency medical delivery in urban environments or search-and-rescue operations, where its 40–60% faster disturbance recovery and smoother motor operation extend battery life and reduce mechanical stress during frequent maneuvering. Conversely, the GWO-optimized controller proves superior for precision-critical applications like power line inspection in windy conditions or bridge monitoring, where its 30–45% smaller deviation during disturbances maintains positioning accuracy despite higher energy costs and occasional voltage saturation.
By quantifying these operational trade-offs across diverse disturbance scenarios, this work offers practical guidance for UAV designers: PSO delivers optimal performance in dynamic missions, prioritizing response speed and efficiency, while GWO provides critical advantages in stability-focused applications where minimal deviation is paramount. This empirically grounded comparison framework, rather than proposing novel control methods, represents our core contribution to the field, enabling evidence-based algorithm selection for specific operational environments.

Author Contributions

Conceptualization, O.L. and L.A.; methodology, O.L. and L.A.; software, O.L., I.B.G. and A.D.; validation, O.L. and L.A.; investigation, O.L. and L.A.; writing—original draft preparation, O.L.; writing—review and editing, L.A.; visualization, O.L., L.A., I.B.G. and A.D.; supervision, L.A.; project administration, L.A. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

No new data were created or analyzed in this study. Data sharing is not applicable to this article.

Acknowledgments

The authors declare that no external support was received for this work.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Sulila, M.S.; Riyadi, M.A. Particle swarm optimization (PSO)-based self tuning proportional, integral, derivative (PID) for bearing navigation control system on quadcopter. In Proceedings of the 2017 4th International Conference on Information Technology, Computer, and Electrical Engineering (ICITACEE), Semarang, Indonesia, 18–19 October 2017; IEEE: Piscataway, NJ, USA, 2017; pp. 181–186. [Google Scholar]
  2. Büyüker, Y.; İlhan, İ. Parameter Optimization of LQR Controller Applied to Three Degrees of Freedom System with Hybrid Approach. Konya J. Eng. Sci. 2024, 12, 494–510. [Google Scholar] [CrossRef]
  3. Benghezal, A.; Nemra, A.; Bouaziz, N.E.I.; Tadjine, M. New robust backstepping attitude control approach applied to quanser 3 DOF hover quadrotor in the case of actuators faults. Unmanned Syst. 2024, 12, 3–17. [Google Scholar] [CrossRef]
  4. Mohanty, S.; Misra, A. 3 DOF Autonomous Control Analysis of an Quadcopter Using Artificial Neural Network. In Modern Approaches in Machine Learning and Cognitive Science: A Walkthrough: Latest Trends in AI; Springer International Publishing: Cham, Switzerland, 2020; pp. 39–57. [Google Scholar]
  5. Hoffman, D.; Rehan, M.; MacKunis, W.; Reyhanoglu, M. Quaternion-based robust trajectory tracking control of a quadrotor hover system. Int. J. Control. Autom. Syst. 2018, 16, 2575–2584. [Google Scholar] [CrossRef]
  6. Bhattacharjee, D.; Subbarao, K. Robust control strategy for quadcopters using sliding mode control and model predictive control. In Proceedings of the AIAA Scitech 2020 Forum, Orlando, FL, USA, 6–10 January 2020; p. 2071. [Google Scholar]
  7. Alonge, F.; D’Ippolito, F.; Fagiolini, A.; Garraffa, G.; Sferlazza, A. Trajectory robust control of autonomous quadcopters based on model decoupling and disturbance estimation. Int. J. Adv. Robot. Syst. 2021, 18, 1729881421996974. [Google Scholar] [CrossRef]
  8. Thanh, H.L.N.N.; Hong, S.K. Quadcopter robust adaptive second order sliding mode control based on PID sliding surface. IEEE Access 2018, 6, 66850–66860. [Google Scholar] [CrossRef]
  9. Xie, W.; Cabecinhas, D.; Cunha, R.; Silvestre, C. Adaptive backstepping control of a quadcopter with uncertain vehicle mass, moment of inertia, and disturbances. IEEE Trans. Ind. Electron. 2021, 69, 549–559. [Google Scholar] [CrossRef]
  10. Yanez-Badillo, H.; Beltran-Carbajal, F.; Tapia-Olvera, R.; Favela-Contreras, A.; Sotelo, C.; Sotelo, D. Adaptive robust motion control of quadrotor systems using artificial neural networks and particle swarm optimization. Mathematics 2021, 9, 2367. [Google Scholar] [CrossRef]
  11. Betancourt-Vera, J.; Castillo, P.; Lozano, R.; Vidolov, B. Robust control scheme for trajectory generation and tracking for quadcopters vehicles: Experimental results. In Proceedings of the 2018 International Conference on Unmanned Aircraft Systems (ICUAS), Dallas, TX, USA, 12–15 June 2018; IEEE: Piscataway, NJ, USA, 2018; pp. 1118–1124. [Google Scholar]
  12. Kumar, E.V.; Raaja, G.S.; Jerome, J. Adaptive PSO for optimal LQR tracking control of 2 DoF laboratory helicopter. Appl. Soft Comput. 2016, 41, 77–90. [Google Scholar] [CrossRef]
  13. Ghiloubi, I.B.; Abdou, L.; Lahmar, O.; Dahnoun, I. 3 DOF Quanser’s Quadrotor Control Using LQR Based on PSO, FPA & ACO with Input Saturation. In Proceedings of the 2023 IEEE 11th International Conference on Systems and Control (ICSC), Sousse, Tunisia, 18–20 December 2023; IEEE: Piscataway, NJ, USA, 2023; pp. 790–795. [Google Scholar]
  14. Maghfiroh, H.; Nizam, M.; Anwar, M.; Ma’Arif, A. Improved LQR control using PSO optimization and Kalman filter estimator. IEEE Access 2022, 10, 18330–18337. [Google Scholar] [CrossRef]
  15. Fakoor, M.; Nikpay, S.; Kalhor, A. On the ability of sliding mode and LQR controllers optimized with PSO in attitude control of a flexible 4-DOF satellite with time-varying payload. Adv. Space Res. 2021, 67, 334–349. [Google Scholar] [CrossRef]
  16. Li, K.; Bai, Y.; Zhou, H. Research on Quadrotor Control Based on Genetic Algorithm and Particle Swarm Optimization for PID Tuning and Fuzzy Control-Based Linear Active Disturbance Rejection Control. Electronics 2024, 13, 4386. [Google Scholar] [CrossRef]
  17. Priya, P.; Kamlu, S.S. Unmanned Aerial System Trajectory Tracking based on Diversified Grey Wolf Optimization Algorithm. IEEE Access 2023, 11, 145975–145988. [Google Scholar] [CrossRef]
  18. Mishra, A.K.; Das, S.R.; Ray, P.K.; Mallick, R.K.; Mohanty, A.; Mishra, D.K. PSO-GWO optimized fractional order PID based hybrid shunt active power filter for power quality improvements. IEEE Access 2020, 8, 74497–74512. [Google Scholar] [CrossRef]
  19. Shauqee, M.N.; Rajendran, P.; Suhadis, N.M. Proportional double derivative linear quadratic regulator controller using improvised grey wolf optimization technique to control quadcopter. Appl. Sci. 2021, 11, 2699. [Google Scholar] [CrossRef]
  20. Belge, E.; Altan, A.; Hacıoglu, R. Metaheuristic Optimization-Based Path Planning and Tracking of Quadcopter for Payload Hold-Release Mission. Electronics 2022, 11, 1208. [Google Scholar] [CrossRef]
  21. Khatoon, S.; Gupta, D.; Das, L.K. PID & LQR control for a quadrotor: Modeling and simulation. In Proceedings of the 2014 International Conference on Advances in Computing, Communications and Informatics (ICACCI), Delhi, India, 24–27 September 2014; IEEE: Piscataway, NJ, USA, 2014; pp. 796–802. [Google Scholar]
  22. Elkhatem, A.S.; Engin, S.N. Robust LQR and LQR-PI control strategies based on adaptive weighting matrix selection for a UAV position and attitude tracking control. Alex. Eng. J. 2022, 61, 6275–6292. [Google Scholar] [CrossRef]
  23. Pillai, A.G.; Rita Samuel, E. PSO based LQR-PID output feedback for load frequency control of reduced power system model using balanced truncation. Int. Trans. Electr. Energy Syst. 2021, 31, e13012. [Google Scholar] [CrossRef]
  24. Dhadekar, D.D.; Sanghani, P.D.; Mangrulkar, K.K.; Talole, S.E. Robust control of quadrotor using uncertainty and disturbance estimation. J. Intell. Robot. Syst. 2021, 101, 60. [Google Scholar] [CrossRef]
  25. Bagua, H. Performance Comparison of PID and LQR Control for DC Motor Speed Regulation. J. Eng. Exact Sci. 2023, 9, 19429. [Google Scholar] [CrossRef]
  26. Veyna, U.; Garcia-Nieto, S.; Simarro, R.; Salcedo, J.V. Quadcopters testing platform for educational environments. Sensors 2021, 21, 4134. [Google Scholar] [CrossRef]
  27. Ansari, U.; Bajodah, A.H.; Kada, B. Development and experimental investigation of a Quadrotor’s robust generalized dynamic inversion control system. Nonlinear Dyn. 2019, 96, 1541–1557. [Google Scholar] [CrossRef]
  28. Kim, T.S.; Stol, K.; Kecman, V. Control of 3 DOF quadrotor model. In Robot Motion and Control 2007; Springer: London, UK, 2007; pp. 29–38. [Google Scholar]
Figure 1. Quanser 3-Dof Hover and its free-body diagram.
Figure 1. Quanser 3-Dof Hover and its free-body diagram.
Engproc 87 00105 g001
Figure 2. Control architecture of 3-DOF hover system with optimized PID-LQR controllers.
Figure 2. Control architecture of 3-DOF hover system with optimized PID-LQR controllers.
Engproc 87 00105 g002
Figure 3. PSO and GWO cost function minimization.
Figure 3. PSO and GWO cost function minimization.
Engproc 87 00105 g003
Figure 4. Tracking performance of yaw, pitch, and roll angles under perturbations.
Figure 4. Tracking performance of yaw, pitch, and roll angles under perturbations.
Engproc 87 00105 g004
Figure 5. Front motor voltage during trajectory tracking with disturbances.
Figure 5. Front motor voltage during trajectory tracking with disturbances.
Engproc 87 00105 g005
Figure 6. Sinusoidal trajectory tracking under progressive disturbances.
Figure 6. Sinusoidal trajectory tracking under progressive disturbances.
Engproc 87 00105 g006
Table 1. Quadrotor parameters.
Table 1. Quadrotor parameters.
ParameterDescriptionValueUnit
K f Force–thrust constant for roll and pitch axis0.1188N/V
K t Force–thrust constant for yaw axis0.0036N/V
J r Moment of inertia about the roll axis0.0552kg·m2
J p Moment of inertia about the pitch axis0.0552kg·m2
J y Moment of inertia about the yaw axis0.1104kg·m2
gGravitational constant9.81 m / s 2
LDistance between each motor and the quadrotor’s center0.1969 M
V M A X Motor maximum voltage24V
Table 2. Robustness performance under dynamic disturbances.
Table 2. Robustness performance under dynamic disturbances.
Criterion PSO GWO Unit
YawPitchRollYawPitchRoll
Settling Time0.60.970.900.861.371.51s
Rise Time0.280.340.40.440.750.75s
Peak Overshoot0000.500%
Steady State Error000000deg
Maximum Deviation3.53.73.82.12.52.9deg
Settling Time after Disturbance0.40.30.41.21.11.1s
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

Lahmar, O.; Abdou, L.; Ghiloubi, I.B.; Drid, A. Robustness Analysis of LQR-PID Controller Based on PSO and GWO for Quadcopter Attitude Stabilization. Eng. Proc. 2025, 87, 105. https://doi.org/10.3390/engproc2025087105

AMA Style

Lahmar O, Abdou L, Ghiloubi IB, Drid A. Robustness Analysis of LQR-PID Controller Based on PSO and GWO for Quadcopter Attitude Stabilization. Engineering Proceedings. 2025; 87(1):105. https://doi.org/10.3390/engproc2025087105

Chicago/Turabian Style

Lahmar, Oussama, Latifa Abdou, Imam Barket Ghiloubi, and Abdelhakim Drid. 2025. "Robustness Analysis of LQR-PID Controller Based on PSO and GWO for Quadcopter Attitude Stabilization" Engineering Proceedings 87, no. 1: 105. https://doi.org/10.3390/engproc2025087105

APA Style

Lahmar, O., Abdou, L., Ghiloubi, I. B., & Drid, A. (2025). Robustness Analysis of LQR-PID Controller Based on PSO and GWO for Quadcopter Attitude Stabilization. Engineering Proceedings, 87(1), 105. https://doi.org/10.3390/engproc2025087105

Article Metrics

Back to TopTop