Next Article in Journal
A Study of the Kinetics, Structure, and Morphology of the Effect of Organic Additives on Barium Sulfate Precipitation Reactions in Propan-1-ol–Water and Ethanol–Water Mixture Solutions
Previous Article in Journal
Research on Power Quality Control Methods for Active Distribution Networks with Large-Scale Renewable Energy Integration
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Extended State Observer Based Robust Nonlinear PID Attitude Tracking Control of Quadrotor with Lumped Disturbance

Key Laboratory of Advanced Perception and Intelligent Control of High-End Equipment, Ministry of Education, Anhui Polytechnic University, Wuhu 241000, China
*
Author to whom correspondence should be addressed.
Processes 2025, 13(5), 1470; https://doi.org/10.3390/pr13051470
Submission received: 15 March 2025 / Revised: 5 May 2025 / Accepted: 7 May 2025 / Published: 12 May 2025

Abstract

:
The paper presents a robust nonlinear PID controller for the attitude tracking problem of quadrotors subject to disturbance. First, to suppress the influence caused by external disturbance torque, considering the fact that the angular velocity can be obtained by the inertial measurement unit (IMU), a reduced-order extended state observer (ESO) is applied as a feedforward compensation to improve the robustness of the tracking system. Then, an ESO-based nonlinear PID controller is constructed to track the desired attitude command, and the rigorous proof of the convergence of the closed-loop system is derived by utilizing the Lyapunov method. Finally, the effectiveness of the proposed method is illustrated by numerical simulations and platform experiments.

1. Introduction

Quadrotor unmanned aerial vehicles (UAVs) have become increasingly vital across a spectrum of applications, including aerial surveillance, inspection, precision agriculture, and disaster response, owing to their vertical take-off and landing (VTOL) capabilities, mechanical simplicity, and high maneuverability [1,2,3]. However, their practical deployment remains constrained by inherent challenges such as strong nonlinear dynamics, underactuation, and high sensitivity to environmental disturbances like wind gusts, payload variations, and sensor noise. These limitations underscore the critical importance of robust and precise attitude control for achieving stable and reliable flight performance.
Traditionally, PID controllers have been the choice for attitude stabilization due to their simplicity and ease of implementation [4]. In [5], the PID algorithm-based flight control was constructed for a quadrotor to study the dynamic control performance under different wind scenarios. To improve the quadrotor control performance, the feedback linearization combined with PID was proposed in [6]. However, in view of disadvantages of linear PID as mentioned in [7], the exploitation of nonlinear PID has further gained interest of researchers [8,9,10,11,12]. In [8], by using error scaling in the integral operation, the nonlinear PID controller for attitude stabilization was developed. To address time and state constraint problem of a quadrotor, a finite-time stability scheme with implicit PID controller was developed in [9]. In [10], a nonlinear PID controller was proposed for a quadrotor to track the given trajectory with minimum energy, and the parameters were tuned by genetic algorithm. In [11], motion control of a quadrotor was achieved by utilizing the designed nonlinear PID-type controller; the rigorous theoretical analysis of the closed-loop system and gain tuning guidelines were provided. Nevertheless, one persistent shortcoming across both linear and nonlinear PID approaches is their passive disturbance rejection. While some robustness is inherently built into controller structures, explicit disturbance estimation and compensation remain underexplored. This is particularly critical given that real-world disturbances can be nontrivial and unpredictable.
To address this, recent attention has shifted towards disturbance observer (DOB) and extended state observer (ESO) [13,14,15,16], which actively estimate and compensate for lumped disturbances—comprising model uncertainties, sensor noise, and environmental forces. DOBs have been shown to enhance tracking under bounded disturbances [17], while ESO-based designs enable real-time estimation of both internal and external uncertainties [18,19,20,21,22,23,24]. For example, in [13], variable DOB control strategy was presented to improve disturbance estimation accuracy. By considering external disturbances, parametric uncertainties, input delay, and actuator fault as lumped disturbances, [14] proposed a fixed-time DOB based trajectory control scheme for a quadrotor. In [15], the integral sliding mode based ESO was developed for a quadrotor in the presence of actuator faults, which ensures the estimation errors accurately converge to the origin. In order to deal with unknown external disturbance, the composite nonlinear ESO, combining the advantages of linear and nonlinear ESOs, was proposed in [16] for trajectory tracking control of a quadrotor. In [18], adaptive ESO based prescribed-time attitude stabilization of a quadrotor was studied, in which ESO was used to estimate and compensate for complicated disturbed factors. However, most existing designs are full-order observers, which introduce undesirable phase lag and are sensitive to high-frequency noise, especially in high-bandwidth systems such as UAVs [25]. Additionally, few studies rigorously address the simultaneous compensation of lumped disturbances with reduced-order ESO within a nonlinear PID framework despite their potential to reduce computational burden and enhance active disturbance rejection while preserving design simplicity and improving real-time applicability [26]. Furthermore, experimental validation of ESO-based control strategies under realistic, noisy, and dynamic environments remains sparse [27], often confined to simulations or disturbance-free setups.
Motivated by the preceding observations, this paper aims to address these issues by proposing a reduced-order ESO-based nonlinear PID controller for quadrotor attitude tracking and bridging the gap between theoretical disturbance compensation techniques and their practical deployment in real-world aerial robotics. Main contributions include: (1) proposing a reduced-order ESO that leverages directly measurable angular velocities to estimate lumped disturbances with reduced phase lag and noise sensitivity; (2) designing a robust nonlinear PID controller that actively compensates for these disturbances in real time and providing rigorous Lyapunov-based stability proofs for the proposed closed-loop system; (3) demonstrating experimental validation on a quadrotor platform, including scenarios with payload-induced disturbances and sensor noise.
The remainder of this paper is organized as follows: Section 2 presents the quadrotor attitude dynamics and some useful properties. In Section 3, the nonlinear PID controller with disturbance rejection based on ESO is developed. Section 4 provides simulation and experimental results to show the control performance and the robustness against disturbance. Finally, conclusions are drawn in Section 5.
Notations: In this paper, the following notations are adopted: λ m ( A ) and λ M ( A ) stand for the minimum and maximum eigenvalue of a symmetric matrix A R 3 × 3 , respectively; x = x T x is the Euclidean norm of vector x R 3 ; and A = λ M ( A T A ) is the induced norm of matrix A R 3 × 3 .

2. Quadrotor Attitude Dynamics

2.1. Attitude Dynamics

In this paper, the quadrotor attitude dynamics are modeled as a fully actuated rigid body. As shown in Figure 1, for the convenience of establishing a mathematical model for a quadrotor, inertial reference frame and body-fixed frame are defined as I = [ x I , y I , z I ] and B = [ x B , y B , z B ] , respectively. The orientation of the body-fixed frame with respect to the inertial frame is denoted by η = [ ϕ , θ , ψ ] T R 3 , composed of the three Euler angles. These angles are bounded as follows: roll angle, ϕ , by ( π / 2 < ϕ < π / 2 ) ; pitch angle, θ , by ( π / 2 < θ < π / 2 ) ; yaw angle, ψ , by ( π < ψ < π ) .
The quadrotor attitude dynamic can be expressed by the Lagrange–Euler equation as follows [28]:
M ( η ) η ¨ + C ( η , η ˙ ) η ˙ = τ + τ d
where M ( η ) R 3 × 3 denotes the inertia matrix, C ( η , η ˙ ) R 3 × 3 represents the centripetal–Coriolis matrix, τ R 3 and τ d R 3 are the control torque and external disturbance torque, represented with respect to the body-fixed frame, respectively.
Matrices M ( η ) and C ( η , η ˙ ) are in the following form:
M ( η ) = I x x 0 I x x S θ 0 I y y C ϕ 2 + I z z S ϕ 2 ( I y y I z z ) C ϕ S ϕ C θ I x x S θ ( I y y I z z ) C ϕ S ϕ C θ I x x S θ 2 + I y y S ϕ 2 C θ 2 + I z z C ϕ 2 C θ 2
and
C ( η , η ˙ ) = c 11 c 12 c 13 c 21 c 22 c 23 c 31 c 32 c 33
with
c 11 = 0 c 12 = ( I y y I z z ) θ ˙ C ϕ S ϕ + ψ ˙ S ϕ 2 C θ ψ ˙ C ϕ 2 C θ I x x ψ ˙ C θ c 13 = ( I z z I y y ) ψ ˙ C ϕ S ϕ C θ 2 c 21 = ( I z z I y y ) θ ˙ C ϕ S ϕ + ψ ˙ S ϕ 2 C θ ψ ˙ C ϕ 2 C θ + I x x ψ ˙ C θ c 22 = ( I z z I y y ) ϕ ˙ C ϕ S ϕ c 23 = I x x ψ ˙ S θ C θ + I y y ψ ˙ S ϕ 2 C θ S θ + I z z ψ ˙ C ϕ 2 S θ C θ c 31 = ( I y y I z z ) ψ ˙ C ϕ S ϕ C θ 2 I x x θ ˙ C θ c 32 = ( I z z I y y ) θ ˙ C ϕ S ϕ S θ + ϕ ˙ S ϕ 2 C θ + ( I y y I z z ) ϕ ˙ C ϕ 2 C θ + I x x ψ ˙ S θ C θ I y y ψ ˙ S ϕ 2 C θ S θ I z z ψ ˙ C ϕ 2 S θ C θ c 33 = ( I y y I z z ) ϕ ˙ C ϕ S ϕ C θ 2 I y y θ ˙ S ϕ 2 C θ S θ I z z θ ˙ C ϕ 2 C θ S θ + I x x θ ˙ C θ S θ
where S · = sin ( · ) , C · = cos ( · ) , I x x , I y y , I z z are moments of inertia around x, y, z axis, respectively.
The control torque τ is calculated as
τ = k T l 1 k T l 1 k T l 1 k T l 1 k T l 2 k T l 2 k T l 2 k T l 2 k τ k τ k τ k τ ω 1 2 ω 2 2 ω 3 2 ω 4 2
where k T is the thrust factor, k τ is the drag factor, ω i is the angular velocity of the ith motor ( i = 1 , 2 , 3 , 4 ), and l 1 and l 2 represent the distances from the rotors to the x B and y B axes, respectively.
Considering the boundaries of the system, the following assumptions are presumed for the following controller design:
Assumption 1.
The desired trajectory η d ( t ) R 3 satisfies η d ( t ) , η ˙ d ( t ) , η ¨ d ( t ) , η d ( t ) L , and η ˙ d ν .
Assumption 2.
The nonlinear disturbance term and its first time derivative are bounded, i.e., τ d ( t ) , τ ˙ d ( t ) L .
Remark 1.
Assumption 1 implies that there is no chance to produce an infinite control torque. Assumptions 1 and 2 ensure that the lumped disturbance mentioned later is bounded and differentiable.

2.2. Useful Properties

Recalling the attitude dynamics in (1), the following properties for nominal dynamics are established:
Property 1.
The matrix M ( η ) is symmetric, positive definite, and bounded by
0 < λ m ( M ) M ( η ) λ M ( M )
Property 2.
The matrix M ˙ ( η ) 2 C ( η , η ˙ ) is skew-symmetric, i.e.,
ς T M ˙ ( η ) 2 C ( η , η ˙ ) ς = 0 , η , η ˙ , ς R 3
Property 3.
The matrices M ( η ) and C ( η , η ˙ ) satisfy
M ˙ ( η ) = C ( η , η ˙ ) + C ( η , η ˙ ) T
Property 4.
There exists a positive constant C M such that
C ( η , η ˙ ) C M η ˙

3. Controller Design

3.1. Objective

The control objective is to develop a controller that will enable the attitude dynamics (1) to track a desired smooth trajectory η d . To quantify the objective, an attitude tracking error is defined as e η ( t ) = η η d R 3 . Then, the error dynamics can be written as follows:
M ( η ) e ¨ η = C ( η , η ˙ ) e ˙ η + τ + f
where f = M ( η ) η ¨ d C ( η , η ˙ ) η ˙ d + τ d is considered as the lumped disturbance. To simplify the subsequent controller design, a portion of desired dynamics is also involved.

3.2. Disturbance Estimation

In this paper, to improve the robustness of the attitude tracking system, ESO is applied for a feedforward compensation. Since the angular velocity can be measured by IMU practically, a reduced-order ESO is considered here to reduce the phase lag and the influence of measurement noises. We define x 1 = e ˙ η , x 2 = M 1 f . According to Assumptions 1 and 2 and (6) in Property 1, h ( t ) d d t M 1 f is bounded. Then attitude error dynamics (10) can be rewritten as follows:
x ˙ 1 = x 2 + f 0 + u
x ˙ 2 = h ( t )
where f 0 = M 1 C e ˙ η and u = M 1 τ .
Then, the dynamics can be regarded as decoupled systems, and it has
x ˙ 1 i = x 2 i + f 0 i + u i
x ˙ 2 i = h i
where x i denotes the ith element of vector x R 3 , and i = 1, 2, 3 stands for roll, pitch, and yaw, respectively.
For system (13), the ESO is usually in the following form:
z ˙ 1 i = z 2 i + g 1 x 1 i z 1 i ε + f 0 i + u i
z ˙ 2 i = 1 ε g 2 x 1 i z 1 i ε
where ε is a small adjustable parameter, and g 1 , g 2 : R R are selectable linear or nonlinear functions.
The following assumption is made for the ESO:
Assumption 3.
There exist constants λ 1 , λ 2 , λ 3 , λ 4 , α, and β and positive definite, continuous differentiable functions V 1 , W 1 : R 2 R such that for y = [ y 1 , y 2 ] T
λ 1 y 2 V 1 ( y ) λ 2 y 2 λ 3 y 2 W 1 ( y ) λ 4 y 2 , V 1 y 1 y 2 g 1 ( y 1 ) V 1 y 2 g 2 ( y 1 ) W 1 ( y ) V 1 y 2 β y
In order to illustrate the convergence of the presented ESO, and the following lemma is useful:
Lemma 1
([17]). Suppose that Assumptions 1–3 are satisfied; then, for ESO (15) and (16)
lim ε 0 | e j i | = 0 , t [ T 1 , )
lim t | e j i | ε 3 j ϖ 0 i
where e j i = z j i x j i , j = 1 , 2 , T 1 is a constant independent of ε, ϖ 0 i = β h ¯ λ 2 / ( λ 1 λ 3 ) is a positive constant.
According to the ESO (15) and (16), a nonlinear ESO is constructed for system (13) by choosing the functions as follows:
g 1 ( y ) = 2 ω y 1 + β fal ( y 1 , ς , δ )
g 2 ( y ) = ω 2 y 1
where 0 < ς < 1 , ω , β , δ are positive constants, and
fal ( y 1 , ς , δ ) = y 1 / δ 1 ς | y 1 | < δ | y 1 | ς sign ( y 1 ) | y 1 | δ
For simplicity, fal ( y 1 , ς , δ ) is abbreviated to fal ( y 1 ) . Then, the ESO is obtained as follows:
z ˙ 1 i = z 2 i 2 ω ε e 1 i β fal e 1 i ε + f 0 i + u i
z ˙ 2 i = ω 2 ε 2 e 1 i
Theorem 1.
Suppose that Assumptions 1 and 2 are satisfied, and the observer is parameterized as
β 5 ω 2 + 1 2 ω δ 1 ς
then, for ESO (23) and (24),
lim t | e j i | ε 3 j ϖ i
where j = 1 , 2 and ϖ i is a positive constant.
Proof. 
Consider the Lyapunov function V 1 : R 2 R given by
V 1 ( y ) = y T P y + β 0 y 1 fal ( s ) d s
where P is a positive definite matrix that is the solution of a Lyapunov equation A T P + P A = I , and I R 2 × 2 is the identity matrix. For ESO (23) and (24), A is obtained as
A = 2 ω 1 ω 2 0
and thus
P = 1 + ω 2 4 ω 1 2 1 2 5 ω 2 + 1 4 ω 3
Now we will prove that all conditions of Assumption 3 are satisfied. First, denote μ = ω 2 + 6 ω 2 + 1 and then λ m ( P ) = μ 2 μ ω 2 μ 8 ω 3 , λ M ( P ) = μ 2 + μ ω 2 + μ 8 ω 3 . Hence,
λ m ( P ) y 2 y T P y λ M ( P ) y 2
Consider the term 0 y 1 fal ( s ) d s in two cases. If | y 1 | < δ , then
0 y 1 fal ( s ) d s = 0 y 1 δ ς 1 s d s = 1 2 δ ς 1 y 1 2 1 2 δ ς 1 y 2
If | y 1 | δ , then
0 y 1 fal ( s ) d s 0 y 1 δ ς 1 s d s = 1 2 δ ς 1 y 1 2 1 2 δ ς 1 y 2
It is obvious that 0 y 1 fal ( s ) d s 0 . From (28) to (30), it is obtained that
λ m ( P ) y 2 V 1 ( y ) λ M ( P ) + 1 2 δ ς 1 y 2
Then, a direct computation shows that
V 1 y 1 y 2 g 1 ( y 1 ) V 1 y 2 g 2 ( y 1 ) = y 1 2 y 2 2 β 2 fal 2 ( y 1 ) 5 ω 2 + 1 2 ω y 1 fal ( y 1 ) + 2 β y 2 fal ( y 1 )
Invoking Young’s inequality, it has
2 β y 2 fal ( y 1 ) 1 2 y 2 2 + 2 β 2 fal 2 ( y 1 )
Then
V 1 y 1 y 2 g 1 ( y 1 ) V 1 y 2 g 2 ( y 1 ) y 1 2 1 2 y 2 2 + β 2 fal 2 ( y 1 ) 5 ω 2 + 1 2 ω y 1 fal ( y 1 ) = y 1 2 1 2 y 2 2 β fal ( y 1 ) 5 ω 2 + 1 2 ω y 1 β fal ( y 1 )
Note that fal ( y 1 ) ( 5 ω 2 + 1 2 ω y 1 β fal ( y 1 ) ) 0 always holds when (25) is satisfied, and thus
V 1 y 1 y 2 g 1 ( y 1 ) V 1 y 2 g 2 ( y 1 ) ω 2 y 1 2 1 2 y 2 2 W 1 ( y )
It is obvious that
min 1 , 1 2 y 2 W 1 ( y ) max 1 , 1 2 y 2
and
V 1 y 2 = y 1 + 5 ω 2 + 1 2 ω 3 y 2 max 1 , 5 ω 2 + 1 2 ω 3 y
Equations (31)–(37) indicate that all conditions of Assumption 3 are satisfied. Therefore, the convergence of ESO (23)–(24) is guaranteed according to Lemma 1. The proof is completed. □
From the discussion above, the estimation error of ESO is bounded. We define the estimation error of disturbance f as e f = M z 2 f , and thus e f is also bounded, i.e.,
e f = M z 2 f e ¯ f

3.3. Attitude Tracking Control

Here, the problem of quadrotor dynamics tracking the desired attitude command η d is considered. To aid the subsequent controller design and stability analysis, the vector Atan ( · ) R 3 and the diagonal matrix T ( · ) R 3 × 3 are defined as follows:
Atan ( x ) = [ atan ( x 1 ) atan ( x 2 ) atan ( x 3 ) ] T
T ( x ) = diag 1 1 + x i 2 , i = 1 , 2 , 3
for x = [ x 1 x 2 x 3 ] T R 3 . It is obvious that the following expressions hold:
d d t Atan ( x ) = T ( x ) x ˙
Atan ( x ) 3 2 π
T ( x ) 1
Based on the control objective and the subsequent stability analysis, the proposed nonlinear PID controller is formulated as follows:
τ = K p Atan ( σ e η ) K i Atan ( ξ ) K d e ˙ η M z 2
where K p , K i , K d R 3 × 3 are diagonal positive definite matrices, and σ is a positive constant; ξ R 3 is given by the filter
ξ ˙ = T ( ξ ) 1 K f Atan ( ξ ) + γ Atan ( σ e η ) + ρ e ˙ η
where K f R 3 × 3 is a diagonal positive definite matrix, and γ and ρ are positive constants.
Theorem 2.
For system (1) controlled by (44), if the controller is parameterized as
σ min σ 1 , σ 2
where
σ 1 = ρ λ m ( M ) ρ λ m ( K p ) + γ λ m ( K d ) γ 2 λ M 2 ( M ) σ 2 = λ m ( K p ) ρ λ m ( K d ) 3 2 π γ C M γ 4 C M 2 ν 2 γ λ m ( K p ) λ M ( M )
then the closed-loop system is uniformly ultimately bounded (UUB).
Proof. 
Consider the following Lyapunov function:
V 2 = 1 2 ρ e ˙ η T M e ˙ η + γ Atan ( σ e η ) T M e ˙ η + ρ σ 1 i = 1 3 k p i σ e η i atan ( σ e η i ) 1 2 ln ( 1 + σ 2 e η i 2 ) + γ σ 1 i = 1 3 k d i σ e η i atan ( σ e η i ) 1 2 ln ( 1 + σ 2 e η i 2 ) + 1 2 Atan ( ξ ) T K i Atan ( ξ )
where k p i , k d i R are the ith diagonal entries of K p and K d , respectively, and e η i R is the ith element of e η .
First, the range of parameters is to be determined to guarantee positive definiteness of V 2 . Using the fact
i = 1 3 x i atan ( x i ) 1 2 ln ( 1 + x i 2 ) 1 2 Atan ( x ) 2
for x = [ x 1 x 2 x 3 ] T R 3 , yields
V 2 1 2 ρ λ m ( M ) e ˙ η 2 γ λ M ( M ) atan ( σ e η ) e ˙ η + 1 2 σ ρ λ m ( K p ) + γ λ m ( K d ) atan ( σ e η ) 2
Applying Young’s inequality, there is
V 2 σ 1 ρ λ m ( M ) ρ λ m ( K p ) + γ λ m ( K d ) γ λ M ( M ) atan ( σ e η ) e ˙ η
and thus V 2 is positive definite if
σ ρ λ m ( M ) ρ λ m ( K p ) + γ λ m ( K d ) γ 2 λ M 2 ( M )
which is always satisfied if (46) holds.
Then the negativity of V ˙ 2 is to be considered. Substituting (44) into (10) yields
M e ¨ η = C e ˙ η K p Atan ( σ e η ) K i Atan ( ξ ) K d e ˙ η e f
Using the fact
d d t i = 1 3 k p i σ e η i atan ( σ e η i ) 1 2 ln ( 1 + σ 2 e η i 2 ) = σ e ˙ η T K p Atan ( σ e η )
then the derivative of V 2 is calculated as follows:
V ˙ 2 = 1 2 ρ e ˙ η T M ˙ e ˙ η + ρ e ˙ η T M e ¨ η + γ σ e ˙ η T T ( σ e η ) M e ˙ η + γ Atan ( σ e η ) T M ˙ e ˙ η + γ Atan ( σ e η ) T M e ¨ η + ρ e ˙ η T K p Atan ( σ e η ) + γ e ˙ η T K d Atan ( σ e η ) + Atan ( ξ ) T K i T ( ξ ) ξ ˙
Substituting (44), (51) into (53), and recalling (7) in Property 2 and (8) in Property 3, yields
V ˙ 2 = ρ e ˙ η T K d e ˙ η ρ e ˙ η T e f + γ σ e ˙ η T T ( σ e η ) M e ˙ η + γ Atan ( σ e η ) T C ( η , η ˙ ) T e ˙ η γ Atan ( σ e η ) T K p Atan ( σ e η ) γ Atan ( σ e η ) T e f Atan ( ξ ) T K i K f Atan ( ξ )
Using (6) in Property 1, (9) in Property 4, (43), and (38), V ˙ 2 is upper bounded by
V ˙ 2 ρ λ m ( K d ) e ˙ η 2 + ρ e ¯ f e ˙ η + γ σ λ M ( M ) e ˙ η 2 + γ C M η ˙ Atan ( σ e η ) e ˙ η γ λ m ( K p ) Atan ( σ e η ) 2 + γ e ¯ f Atan ( σ e η ) λ m ( K i K f ) Atan ( ξ ) 2
According to Assumption 1, (42), and the fact that η ˙ η ˙ d + e ˙ η , the fourth term of (55) is upper bounded by
γ C M η ˙ Atan ( σ e η ) e ˙ η γ C M ( η ˙ d + e ˙ η ) Atan ( σ e η ) e ˙ η γ C M ν Atan ( σ e η ) e ˙ η + 3 2 π γ C M e ˙ η 2
Therefore,
V ˙ 2 ρ λ m ( K d ) e ˙ η 2 + ρ e ¯ f e ˙ η + γ σ λ M ( M ) e ˙ η 2 + γ C M ν Atan ( σ e η ) e ˙ η + 3 2 π γ C M e ˙ η 2 γ λ m ( K p ) Atan ( σ e η ) 2 + γ e ¯ f Atan ( σ e η ) λ m ( K i K f ) Atan ( ξ ) 2 ζ T Q ζ λ m ( K i K f ) Atan ( ξ ) 2 + max { γ , ρ } e ¯ f ζ
where
ζ = Atan ( σ e η ) e ˙ η
and
Q = γ λ m ( K p ) γ 2 C M ν ρ λ m ( K d ) γ σ λ M ( M ) 3 2 π γ C M
To guarantee V ˙ 2 < 0 , Q should be positive definite, which is equivalent to
σ < λ m ( K p ) ρ λ m ( K d ) 3 2 π γ C M γ 4 C M 2 ν 2 γ λ m ( K p ) λ M ( M )
which is always satisfied if the controller is parameterized as (46).
Moreover, (57) also indicates that
V ˙ 2 λ m ( Q ) ζ 2 λ m ( K i K f ) Atan ( ξ ) 2 + max { γ , ρ } e ¯ f ζ
It follows that if
ζ max { γ , ρ } λ m ( Q ) e ¯ f Δ ζ
then V ˙ 2 0 , which means V 2 is decreasing and bounded, and ζ enters a small neighborhood of the origin B Δ ζ . Even though ζ enters B Δ ζ , it may move in and out since the negativity of V ˙ 2 in B Δ ζ is not guaranteed. However, when ζ leaves the neighborhood, V ˙ 2 becomes negative again and drives it back to B Δ ζ . Therefore, ζ is guaranteed to be UUB. As a result, states e η , e ˙ η , and ξ are also bounded in a small neighborhood of the origin, and the closed-loop system is UUB. The proof is completed. □

4. Simulation and Experimental Results

The experimental platform is a custom-built quadrotor based on the QAV-250 frame, featuring an axis-to-axis diagonal length of 250 mm. The airframe utilizes a carbon fiber-reinforced structure to ensure rigidity while minimizing inertia. There are four EMAX MT2204 KV2300 brushless motors paired with 5045 self-tightening propellers. Motor commands are executed via EMAX Simonk 12A electronic speed controllers (ESCs). Attitude feedback is provided by an ICM20602 IMU module, which integrates a 3-axis gyroscope and accelerometer. The ANO-Pioneer flight control board, equipped with an STM32F407VG microcontroller (168 MHz clock speed), runs a real-time operating system to achieve a 200 Hz control loop frequency. This configuration reflects typical small-scale quadrotor dynamics, ensuring the controller’s applicability to similar UAV platforms.

4.1. Parameters

To begin with, some necessary parameters of the quadrotor are measured or estimated. The brushless DC motors are driven by given ESC signals, and the relation between the angular speed of each rotor ω i ( i = 1 , 2 , 3 , 4 ) and PWM n i signal can be experimentally determined by ω i 2 = k 1 n i + k 2 , where k 1 = 8.1270 × 10 6 and k 2 = 3.5866 × 10 6 , as shown in Figure 2. For a desired ω i designed by (5), the ESC signal n i can be calculated. The rest of the parameters are l 1 = 0.077 m, l 2 = 0.102 m, I x x = 0.0026 kg· m 2 , I y y = 0.0027 kg· m 2 , I z z = 0.0047 kg· m 2 , k T = 1.468 × 10 6 s 2 / rad 2 , k τ = 1.446 × 10 8 N·m· s 2 / rad 2 [29].
The control parameters are the same in subsequent simulations and experiments, which are as follows:
K p = diag { 0.04 , 0.04 , 0.01 } , K i = diag { 0.01 , 0.01 , 0.002 } , K d = diag { 0.02 , 0.02 , 0.005 } , K f = diag { 0.05 , 0.05 , 0.01 } , σ = 1.5 , γ = 0.02 , ρ = 0.02 , ω = 0.6 , β = 0.75 , ε = 0.05 , δ = 1 9

4.2. Simulation Results

In the simulation, the quadrotor attitude tracks a reference attitude command, similar to [24], η d = [ 10 sin ( 0.4 t ) 10 sin ( 0.3 t ) 0 ] T and a set of sinusoidal wave disturbances is added as τ d = 0.001 [ sin ( 0.5 t ) sin ( 0.5 t ) 0.1 sin ( 0.5 t ) ] T N·m. The initial conditions are η ( 0 ) = [ 0 , 0 , 0 ] T rad and η ˙ ( 0 ) = [ 0 , 0 , 0 ] T rad/s. The initial values of z 1 , z 2 , and ξ are set to zeros. The simulation is carried out in MATLAB 2016a with a sampling time of 5 ms.
By utilizing the ESO, modeling error can also be considered as internal disturbance and can be compensated for. Here, the modeling error is assumed to be mainly caused by inaccurate measurement of moments of inertia, and a bias of 30 % is added in simulations. In addition, considering the case in practical application, a measurement noise with zero mean and covariance of 0.01 and a system noise with zero mean and covariance of 10 6 are added in attitude angle and angular acceleration, respectively.
The simulation results are shown in Figure 3a, Figure 4a and Figure 5a. In Figure 3a, it can be observed that the attitude angles can track the reference smoothly in the presence of lumped disturbance and noises. In Figure 4a, the control torques for the roll, pitch, and yaw axes are depicted, generated by the proposed ESO-based nonlinear PID controller. These torques exhibit smooth variations despite the applied lumped disturbance (sinusoidal wave) and measurement/system noises, demonstrating the controller’s ability to stabilize the system. The absence of abrupt spikes indicates effective disturbance rejection through feedforward compensation from the ESO. Figure 5a illustrates the ESO’s estimation performance, where the estimated lumped disturbance (combining external torque, modeling errors, and noise) closely tracks the actual disturbance profile. Minor discrepancies arise due to the 30 % inertia bias and added noises in the simulation, yet the bounded estimation errors align with the theoretical convergence guarantees. Together, these figures validate the ESO’s role in actively mitigating disturbances and the controller’s robustness in maintaining precise attitude tracking under noisy conditions.

4.3. Experimental Results

In this section, experiments are conducted to illustrate the effectiveness of the proposed method. To this end, an attitude experimental platform is built, as shown in Figure 6a. The quadrotor is fixed to a smooth joint and the translational movement is restricted. The hardware configuration is summarized in the beginning of this section. The attitude control frequency is 200 Hz and the updating frequency of the ESO is 1000 Hz.

4.3.1. Attitude Tracking Control

First, experiments are done to show the attitude tracking performance of the designed controller. The reference trajectory, initial values, and controller gains are set up identically to the simulations. In this case, the experimental results are depicted in Figure 3b, Figure 4b and Figure 5b. The oscillations in attitudes, control torques, and ESO estimations are due to the measurements noise of the IMU and the high-frequency dynamics caused by the vibration of quadrotor. Figure 3b shows the attitude tracking performance, including the reference commands and measurements of roll, pitch, and yaw angles. It was found that the tracking errors are driven into a small neighborhood of the origin, which agrees with the theoretical analysis. To show the efficiency of the ESO, the estimations of the derivatives of attitude tracking errors are also depicted in Figure 5b. The results indicate that the proposed reduced-order ESO can make a relatively accurate estimation even in the presence of measurement noises and high-frequency dynamics.
While experimental results include noise-induced oscillations (Figure 3b), the tracking errors remain bounded within theoretical predictions (Figure 3a). The ESO’s disturbance estimates (Figure 5a vs. Figure 5b) exhibit consistent performance, with experimental deviations attributable to unmodeled high-frequency dynamics, yet still ensure effective compensation.
To quantitatively evaluate the controller’s performance, key metrics such as maximum absolute error (MAE) and root mean square error (RMSE) are computed for both simulation and experimental results. For instance, in Figure 3a, the roll and pitch tracking errors exhibit MAEs of 0.12 rad and 0.11 rad, respectively, with RMSEs of 0.08 rad (roll) and 0.07 rad (pitch). The yaw channel shows superior precision, achieving an MAE of 0.018 rad and RMSE of 0.009 rad under disturbances. Experimental results (Figure 3b) reflect slightly higher but still bounded errors due to real-world noise and vibrations: MAEs of 0.16 rad (roll), 0.15 rad (pitch), and 0.025 rad (yaw), with RMSEs of 0.10 rad, 0.09 rad, and 0.015 rad, respectively. Control torque signals (Figure 4) remain within ± 0.25 N·m (roll/pitch) and ± 0.05 N·m (yaw), demonstrating smooth actuation. The ESO’s disturbance estimation error (Figure 5) maintains an RMSE of 0.003 N·m in simulations and 0.008 N·m in experiments, confirming its efficacy despite noise. These quantitative results align with the theoretical UUB guarantees and validate the algorithm’s robustness.
Furthermore, in order to verify that ESO is likely to enhance the robustness of system, another set of experiments will be discussed in Section 4.3.2.

4.3.2. Attitude Stabilization with Disturbance Torque

In this paper, to illustrate the robustness of the proposed method, experiments were carried out in which a payload of 200 g was hung on one arm of the quadrotor at a time instant. It can be approximately considered that a time-varying disturbance torque acts on the quadrotor as the payload swings. The experimental platform is shown in Figure 6b. All the parameters are the same as the previous ones. The results are given in Figure 7, Figure 8 and Figure 9, and the moment that disturbance torque joins is marked in the figures. Figure 7 indicates that there is no abrupt change in attitude angles and the tracking error is still acceptable even subjected to disturbance torque. It can also be observed from Figure 8 and Figure 9 that the disturbance torque can be estimated quickly and compensated for actively in control torques. It is considered that the ESO plays a key role in disturbance rejection, and the proposed method demonstrates a good robustness and tracking accuracy.

5. Conclusions

In this paper, a nonlinear PID controller was investigated for the quadrotor attitude tracking problem. First, the attitude error dynamics were obtained with a lumped disturbance, and a special form of ESO was designed to estimate and compensate for the disturbance. Since the angular velocities were available via IMU, a reduced-order ESO was applied to reduce the phase lag, as well as the influence of measurement noise and high-frequency dynamics. Then, an ESO-based nonlinear PID controller was designed for attitude tracking. Rigorous proof of the convergence of the closed-loop system in the presence of disturbances was provided based on the Lyapunov method. Finally, simulations and experimental results indicate a good tracking accuracy and robustness against disturbance of the proposed method. Despite the proposed method excelling in disturbance rejection and tracking precision, limitations such as manual parameter tuning and actuator saturation warrant further investigation. Therefore, future work will focus on intelligent parameter adaptation (e.g., reinforcement learning) and anti-saturation control of the quadrotor to broaden its applicability.

Author Contributions

Methodology, G.X.; Software, X.D.; Validation, G.X.; Investigation, Y.H.; Writing—original draft, G.X.; Writing—review & editing, S.L.; Supervision, Y.H.; Funding acquisition, S.L. and Y.H. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported in part by the National Natural Science Foundation of China under grant 62203013, Anhui Province University Collaborative Innovation Project under grant GXXT-2020-069, and the Scientific Research Foundation for Introduced Talent Scholars of Anhui Polytechnic University under grant 2022YQQ050.

Data Availability Statement

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

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Bui, D.N.; Van Nguyen, T.T.; Phung, M.D. Lyapunov-based nonlinear model predictive control for attitude trajectory tracking of unmanned aerial vehicles. Int. J. Aeronaut. Space Sci. 2023, 24, 502–513. [Google Scholar] [CrossRef]
  2. Lopez-Sanchez, I.; Pérez-Alcocer, R.; Moreno-Valenzuela, J. Trajectory tracking double two-loop adaptive neural network control for a Quadrotor. J. Frankl. Inst. 2023, 360, 3770–3799. [Google Scholar] [CrossRef]
  3. Lopez-Sanchez, I.; Moyrón, J.; Moreno-Valenzuela, J. Adaptive neural network-based trajectory tracking outer loop control for a quadrotor. Aerosp. Sci. Technol. 2022, 129, 107847. [Google Scholar] [CrossRef]
  4. Lopez-Sanchez, I.; Moreno-Valenzuela, J. PID control of quadrotor UAVs: A survey. Annu. Rev. Control 2023, 56, 100900. [Google Scholar] [CrossRef]
  5. Hong, K. Simulation and analysis of stability of UAV control system based on PID control under different wind forces. J. Phys. Conf. Ser. 2023, 2649, 012011. [Google Scholar] [CrossRef]
  6. Ghanifar, M.; Kamzan, M.; Tayefi, M. Different Intelligent Methods for Coefficient Tuning of Quadrotor Feedback-linearization Controller. J. Aerosp. Sci. Technol. 2023, 16, 56–65. [Google Scholar]
  7. Najm, A.A.; Ibraheem, I.K. Nonlinear PID controller design for a 6-DOF UAV quadrotor system. Eng. Sci. Technol. Int. J. 2019, 22, 1087–1097. [Google Scholar] [CrossRef]
  8. Jin, G.G.; Pal, P.; Chung, Y.K.; Kang, H.K.; Yetayew, T.T.; Bhakta, S. Modelling, control and development of GUI-based simulator for a quadcopter using nonlinear PID control. Aust. J. Electr. Electron. Eng. 2023, 20, 387–399. [Google Scholar] [CrossRef]
  9. Wang, S.; Polyakov, A.; Zheng, G. Quadrotor stabilization under time and space constraints using implicit PID controller. J. Frankl. Inst. 2022, 359, 1505–1530. [Google Scholar] [CrossRef]
  10. Najm, A.A.; Azar, A.T.; Ibraheem, I.K.; Humaidi, A.J. A Nonlinear PID Controller Design for 6-DOF Unmanned Aerial Vehicles; Academic Press: Cambridge, MA, USA, 2021; pp. 315–343. [Google Scholar]
  11. Moreno-Valenzuela, J.; Pérez-Alcocer, R.; Guerrero-Medina, M.; Dzul, A. Nonlinear PID-type controller for quadrotor trajectory tracking. IEEE/ASME Trans. Mechatron. 2018, 23, 2436–2447. [Google Scholar] [CrossRef]
  12. Zhu, B.; Huo, W. Nonlinear control for a model-scaled helicopter with constraints on rotor thrust and fuselage attitude. Acta Autom. Sin. 2014, 40, 2654–2664. [Google Scholar] [CrossRef]
  13. Jeong, H.; Suk, J.; Kim, S. Control of quadrotor UAV using variable disturbance observer-based strategy. Control Eng. Pract. 2024, 150, 105990. [Google Scholar] [CrossRef]
  14. Li, C.; Wang, Y.; Yang, X. Adaptive fuzzy control of a quadrotor using disturbance observer. Aerosp. Sci. Technol. 2022, 128, 107784. [Google Scholar] [CrossRef]
  15. Gong, W.; Li, B.; Ahn, C.K.; Yang, Y. Prescribed-time extended state observer and prescribed performance control of quadrotor UAVs against actuator faults. Aerosp. Sci. Technol. 2023, 138, 108322. [Google Scholar] [CrossRef]
  16. Zhao, K.; Zhang, J.; Shu, P.; Dong, X. Composite Nonlinear Extended State Observer-Based Trajectory Tracking Control for Quadrotor Under Input Constraints. IEEE Trans. Circuits Syst. I Regul. Pap. 2023, 70, 4126–4136. [Google Scholar] [CrossRef]
  17. Guo, B.; Zhao, Z. On the convergence of an extended state observer for nonlinear systems with uncertainty. Syst. Control Lett. 2011, 60, 420–430. [Google Scholar] [CrossRef]
  18. Wang, L.; Pei, H. Geometric prescribed-time control of quadrotors with adaptive extended state observers. Int. J. Robust Nonlinear Control 2024, 34, 7460–7479. [Google Scholar] [CrossRef]
  19. Li, J.; Cao, C.; Xu, J. An extended state observer-based active disturbance rejection control for quadrotor attitude stabilization. Mechatronics 2022, 85, 102853. [Google Scholar]
  20. Luo, Y.; Ma, J.; Hu, J. Fault-tolerant tracking control for quadrotor UAV with actuator saturation and multiple uncertainties. ISA Trans. 2023, 134, 373–385. [Google Scholar]
  21. Zhang, Y.; Ding, S.; Li, Y. Data-driven fault-tolerant tracking control for quadrotor UAV with actuator failure and external disturbance. IEEE Trans. Ind. Electron. 2023, 70, 5962–5972. [Google Scholar]
  22. Zhao, S.; Li, H.; Wang, L. Active disturbance rejection flight control for quadrotors based on nonlinear extended state observer. Aerospace 2023, 10, 327. [Google Scholar]
  23. Zhou, Y.; Liu, Z.; Zhang, C. Anti-saturation prescribed-time trajectory tracking control of quadrotors with nonlinear observers. IEEE Trans. Control Syst. Technol. 2024; early access. [Google Scholar]
  24. Ma, D.; Xia, Y.; Shen, G.; Jiang, H.; Hao, C. Practical fixed-time disturbance rejection control for quadrotor attitude tracking. IEEE Trans. Ind. Electron. 2020, 68, 7274–7283. [Google Scholar] [CrossRef]
  25. Chen, H.; Du, L.; Zhang, X. A robust disturbance observer-based control approach for quadrotors in uncertain environments. IEEE Access 2022, 10, 59338–59350. [Google Scholar]
  26. Tang, H.; Yu, M.; Zhang, J. Reduced-order disturbance observer-based trajectory tracking control for quadrotors under bounded uncertainties. Robot. Auton. Syst. 2023, 164, 104383. [Google Scholar]
  27. Yan, S.; Liu, Q.; Zhang, L. Robust trajectory tracking control of quadrotors under lumped disturbances: Simulation and experiments. Aerosp. Sci. Technol. 2022, 124, 107520. [Google Scholar]
  28. Raffo, G.V.; Ortega, M.G.; Rubio, F.R. An integral predictive/nonlinear H control structure for a quadrotor helicopter. Automatica 2010, 46, 29–39. [Google Scholar] [CrossRef]
  29. Shi, D.; Dai, X.; Zhang, X.; Quan, Q. A Practical Performance Evaluation Method for Electric Multicopters. IEEE/ASME Trans. Mechatron. 2017, 22, 1337–1348. [Google Scholar] [CrossRef]
Figure 1. Body-fixed frame and earth-fixed frame for the quadrotor.
Figure 1. Body-fixed frame and earth-fixed frame for the quadrotor.
Processes 13 01470 g001
Figure 2. Relationship between ESC signal and the angular speed of rotor.
Figure 2. Relationship between ESC signal and the angular speed of rotor.
Processes 13 01470 g002
Figure 3. Attitude tracking performance and errors.
Figure 3. Attitude tracking performance and errors.
Processes 13 01470 g003
Figure 4. Control torques of roll, pitch, and yaw axes.
Figure 4. Control torques of roll, pitch, and yaw axes.
Processes 13 01470 g004
Figure 5. Disturbance estimations of proposed ESO.
Figure 5. Disturbance estimations of proposed ESO.
Processes 13 01470 g005
Figure 6. Quadrotor attitude experimental platform.
Figure 6. Quadrotor attitude experimental platform.
Processes 13 01470 g006
Figure 7. Experimental results: attitude tracking performance with payload disturbance.
Figure 7. Experimental results: attitude tracking performance with payload disturbance.
Processes 13 01470 g007
Figure 8. Experimental results: control torques for roll, pitch, and yaw angles in payload disturbance scenario.
Figure 8. Experimental results: control torques for roll, pitch, and yaw angles in payload disturbance scenario.
Processes 13 01470 g008
Figure 9. Experimental results: estimation performance of the proposed ESO in payload disturbance scenario.
Figure 9. Experimental results: estimation performance of the proposed ESO in payload disturbance scenario.
Processes 13 01470 g009
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

Xu, G.; Luo, S.; Huang, Y.; Deng, X. Extended State Observer Based Robust Nonlinear PID Attitude Tracking Control of Quadrotor with Lumped Disturbance. Processes 2025, 13, 1470. https://doi.org/10.3390/pr13051470

AMA Style

Xu G, Luo S, Huang Y, Deng X. Extended State Observer Based Robust Nonlinear PID Attitude Tracking Control of Quadrotor with Lumped Disturbance. Processes. 2025; 13(5):1470. https://doi.org/10.3390/pr13051470

Chicago/Turabian Style

Xu, Gang, Shengping Luo, Yiqing Huang, and Xiongfeng Deng. 2025. "Extended State Observer Based Robust Nonlinear PID Attitude Tracking Control of Quadrotor with Lumped Disturbance" Processes 13, no. 5: 1470. https://doi.org/10.3390/pr13051470

APA Style

Xu, G., Luo, S., Huang, Y., & Deng, X. (2025). Extended State Observer Based Robust Nonlinear PID Attitude Tracking Control of Quadrotor with Lumped Disturbance. Processes, 13(5), 1470. https://doi.org/10.3390/pr13051470

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop