Next Article in Journal
Capacitance Characteristics of Glass-Embedded Interdigitated Capacitors for Touch Sensing Applications
Previous Article in Journal
Characteristics of Ground Reaction Force Variability During Walking in Post-Stroke Patients
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Optimized Fractional-Order Extended Kalman Filtering for IMU-Based Attitude Estimation Using the Hippopotamus Algorithm

1
College of Physics and Electronic Information Engineering, Guilin University of Technology, Guilin 541004, China
2
Guangxi Engineering Research Center of Optoelectronic Information and Intelligent Communication, Guilin 541004, China
3
Guangxi Key Laboratory of Embedded Technology and Intelligent System, Guilin University of Technology, Guilin 541004, China
4
College of Computer Science and Engineering, Guilin University of Technology, Guilin 541004, China
5
School of Aeronautics and Astronautics, Guilin University of Aerospace Technology, Guilin 541004, China
6
Guilin Ecological Environment Monitoring Center of Guangxi Zhuang Autonomous Region, Guilin 541199, China
7
Guilin Urban Planning and Design Institute, Guilin 541002, China
*
Author to whom correspondence should be addressed.
Sensors 2025, 25(22), 6942; https://doi.org/10.3390/s25226942
Submission received: 11 September 2025 / Revised: 29 October 2025 / Accepted: 7 November 2025 / Published: 13 November 2025
(This article belongs to the Section Intelligent Sensors)

Abstract

The performance of the Fractional-order Extended Kalman Filter (FEKF) is often constrained by the manual tuning of its fractional-order parameter. This paper proposes HO-FEKF, a novel framework that integrates the Hippopotamus Optimization (HO) algorithm to automate and intelligently determine this optimal parameter. Central to our approach is a hierarchical optimization strategy that efficiently minimizes attitude estimation error. In addition to this automated tuning, we enhance the core FEKF model by improving its handling of nonlinear system dynamics, including the effects of time discretization on the Jacobian, cross-factor interactions, and the use of a sliding residual window. We validated our method on both a public benchmark and a custom-collected dataset. Results show that our improved FEKF surpasses the traditional version, and the complete HO-FEKF framework significantly outperforms approaches based on other optimization algorithms (genetic algorithm GA, grey wolf optimizer GWO, Harris hawks optimizer HHO, and HiPPO-LegS algorithm) combined with FEKF. These findings confirm the practical potential of HO-FEKF for achieving adaptive, high-accuracy attitude estimation in real-world sensor fusion scenarios.

1. Introduction

Attitude prediction and estimation constitute a core issue in modern navigation systems and are widely applied in UAV flight control, missile guidance, and virtual reality devices [1,2]. The accuracy of attitude angles directly affects the system’s stability and performance. In practical applications, due to noise, drift, and external disturbances affecting inertial sensors, traditional filtering algorithms often suffer from reduced accuracy and instability in attitude estimation [3]. A particularly challenging yet common research background involves the navigation of autonomous systems, such as UAVs, in ‘magnetically denied environments’, including indoor factories, urban canyons, or areas with significant metallic infrastructure. In these environments, ambient magnetic fields are severely distorted by electromagnetic interference from power lines, electric motors, and ferrous structures, rendering magnetometers—the primary sensor for providing an absolute heading reference—highly unreliable. Consequently, accurately estimating the yaw angle becomes infeasible. However, for many critical tasks in these scenarios, such as maintaining platform stability, balancing, and immediate trajectory control, the precise and rapid estimation of roll and pitch angles is of paramount importance, while the absolute yaw angle is often non-essential. Therefore, this study focuses specifically on enhancing the accuracy and robustness of roll and pitch estimation.
To address this challenge, the Kalman Filter (KF) [4], as an optimal state estimation method, provides the theoretical foundation for such tasks. Building on this, the Extended Kalman Filter (EKF) [5], as its application to nonlinear systems, has become the mainstream approach in Attitude and Heading Reference Systems. However, EKF assumes that the system dynamics are governed by integer-order differential equations, which limits its ability to effectively capture the long-memory effects inherent in complex dynamic systems. This limitation becomes especially prominent in high-dynamic scenarios where the system state is significantly influenced by its historical behavior [6].
To address this limitation, the introduction of fractional-order calculus into the Kalman filtering framework can effectively enhance the modeling capability for historical dependencies and dynamic nonlinearities. The FEKF incorporates fractional derivatives and fractional residuals to refine the state prediction and covariance update processes, thereby significantly improving its adaptability to noise and nonlinear dynamics [7]. In recent years, fractional-order calculus has gained widespread attention in the fields of control theory, signal processing, and system identification [8,9,10].
However, determining the parameters of the Kalman filter has long been a challenging research problem. In 2023, Wondosen Assefinew et al. addressed the difficulty in tuning the Q (process noise covariance) and R (measurement noise covariance) matrices in EKF for UAV three-dimensional attitude estimation by proposing a Bayesian optimization algorithm based on innovation white-noise consistency analysis to automatically identify the optimal Q and R values [11]. Standard Kalman filter theory, and by extension the optimization methods designed for it, relies on the Markov property—the assumption that a system’s future state depends only on its present state. Methods like the Bayesian optimization proposed by Wondosen et al., which use innovation white-noise consistency analysis, are explicitly designed around this property. They assume that for an optimal filter, the innovation sequence (the difference between the measurement and the prediction) must be a zero-mean, uncorrelated white noise process. However, the integral nature of the fractional derivative means the system’s state is a weighted sum of its entire history. This inherent memory directly violates the Markovian assumption, introducing temporal correlations into the innovation sequence that these methods would misinterpret as poor tuning of Q and R, rather than as a fundamental property of the system’s dynamics.
In the same year, Xue-Bo Jin et al. introduced a parameter-free Kalman filter state estimation method based on attention mechanism learning. This approach employs a Transformer encoder and an LSTM network to extract dynamic features, and utilizes the EM algorithm to estimate system model parameters online, thereby enabling the Kalman filter to update the model in real time without pre-setting the parameters [12]. In 2024, Tavares et al. proposed an innovative EKF parameter tuning method aimed at improving navigation accuracy in INS/GNSS integrated systems. The authors estimated the process noise covariance matrix Q using ideal trajectory data and inertial error models generated by prior Monte Carlo simulations, and validated the approach on real datasets [13]. In 2025, Liu L. et al. employed the Modified Differential Bees Algorithm (MDBA) to independently optimize the model error covariance Q and measurement noise covariance R in both KF and EKF under scenarios involving unknown inputs [14]. The attention mechanism and EM algorithm used by Jin et al. and the Monte Carlo approach of Tavares Jr. et al. are designed to learn or model integer-order dynamics and are not equipped to navigate the complex interdependencies created by a variable fractional order. Similarly, while Liu et al. use a metaheuristic, their focus on independently optimizing Q and R overlooks the critical coupled effect of α on the entire system.
In summary, the pivotal challenge of parameter selection in FEKF remains a critical, unresolved issue [15]. The choice of the fractional order, α , is not merely a tuning step but a fundamental decision that critically governs the filter’s performance. An inappropriate value can lead to significant degradation through under- or over-filtering, potentially negating the very advantages of the fractional approach. Therefore, optimizing this parameter for a given application is an essential prerequisite to unlocking the full potential of the FEKF.
To address the above issue, this paper proposes the use of Hippopotamus Optimization [16], hereafter referred to as HO, to automatically optimize the fractional-order parameter α in the improved FEKF. HO, introduced in 2024, is a novel swarm intelligence optimization algorithm known for its excellent global search capability and convergence performance, achieving leading results on numerous benchmark test functions. In this study, HO is integrated into the FEKF-based attitude estimation framework to formulate an optimization problem where the attitude estimation error serves as the fitness function, enabling automatic identification of the optimal fractional order α .
Furthermore, to evaluate the effectiveness of the HO algorithm, we compare it with Harris Hawks Optimization (HHO) [17], Genetic Algorithm (GA) [18], Grey Wolf Optimization (GWO) [19], and a new memory mechanism from the machine learning field—HiPPO-LegS [20]. The comparison is conducted from both theoretical and experimental perspectives, analyzing the convergence speed, robustness, and optimality of HO.

2. Materials and Methods

2.1. Dynamic Model of Attitude Determination

The mathematical formulation of attitude estimation is based on the angular velocity w = ( p , q , r ) T measured by the Inertial Measurement Unit (IMU), where p , q , r denote the angular velocity components about the body-fixed coordinate axes X , Y , Z , respectively. To represent the orientation of the vehicle, Euler angles are commonly employed—namely, roll, pitch, and yaw—which correspond to rotations about the fixed coordinate system’s X , Y , Z axes, respectively [21].
In this study, Euler angles are employed for attitude estimation. The variation in the attitude can be described by the following Equation (1):
ϕ ˙ θ ˙ ψ ˙ = 1 sin ϕ tan θ cos ϕ tan θ 0 cos ϕ sin ϕ 0 sin ϕ cos θ 1 cos ϕ cos θ 1 p q r
Since the gyroscope in the IMU measures angular velocity, it is necessary to integrate the angular velocity over time in order to obtain the attitude angles:
ϕ k = ϕ k 1 + ϕ ˙ Δ t θ k = θ k 1 + θ ˙ Δ t ψ k = ψ k 1 + ψ ˙ Δ t
where Δ t denotes the sampling time interval, ϕ k , θ k , ψ k represents the attitude angles at the current time step k. ϕ k 1 , θ k 1 , ψ k 1 represents the attitude angles at the previous time step.
However, direct integration of angular velocity accumulates the gyroscope’s bias drift, causing the attitude estimation error to increase continuously over time. Therefore, practical systems typically combine measurements from accelerometers and magnetometers, employing filtering algorithms such as the Kalman Filter (KF), Extended Kalman Filter (EKF), or complementary filtering to fuse the data and improve the accuracy of attitude estimation.

2.2. Fractional-Order Calculus and Fractional-Order Kalman Filtering

2.2.1. Fractional-Order Calculus

The conventional Kalman filter is not inherently suitable for fractional-order systems, which are prevalent in many engineering applications. To enhance the applicability of Kalman filtering in such systems, a novel filtering algorithm known as the Fractional-order Extended Kalman Filter (FEKF) is introduced by integrating fractional-order calculus with the Kalman filter framework. By incorporating fractional-order processing in the error-corrected data update, FEKF significantly improves estimation accuracy.
Using the G r u n w a l d L e t n i k o v definition, the state-space representation of a fractional-order system can be derived [22]. This leads to a discrete-time fractional-order state-space expression, which is defined as follows:
D α G L f ( t ) = lim h 0 1 h α j = 0 ( 1 ) j α j f ( t j h )
In the equation, α represents the order of the fractional derivative; t denotes the sampling interval; and α j is defined as the binomial coefficient as follows:
α j = 1 j = 0 α ( α 1 ) ( α 2 ) ( α j + 1 ) j ! j > 0
When α is an integer, this expression degenerates to the conventional difference formula. However, when α is a non-integer, the derivative at the current time depends not only on the current value f ( t ) but also on multiple past values of the function, with their contributions gradually diminishing as k increases. This characteristic endows fractional-order operators with a “long memory” effect, making them more accurate for modeling systems exhibiting fading memory behavior.

2.2.2. Improvements and Applications of FEKF

The fractional-order Kalman filter uses a “predictor–corrector” method. It first predicts the state x ˜ k based on past data, then corrects that prediction at time t = k using current inertial sensor measurements y k . This method models fractional-order non-linear systems as follows:
Δ α x ˜ k + 1 = f ( x ^ k , u k ) + W k
y k = h x k + V k
In this model, x ˜ k is the predicted state vector, f represents the non-linear mapping of the state over time, u k is the control input, and the terms W k and V k represent the process noise and measurement noise, respectively. Both are assumed to be zero-mean, uncorrelated Gaussian white noise processes. The objective of this paper is to apply this fractional-order framework to the specific challenge of attitude estimation in environments with strong magnetic interference. In these scenarios, severe electromagnetic interference renders magnetometer data unreliable, which in turn makes the yaw angle unobservable. Therefore, to ensure the filter’s stability and observability, the state vector x and its fractional-order counterpart Δ α x ˜ k + 1 are defined as a five-dimensional vector, composed of the roll angle, the pitch angle, and the three-axis bias errors from the inertial sensors.
x k = θ k ϕ k b p , k b q , k b r , k ; Δ α x ˜ k = Δ α θ k Δ α ϕ k Δ α b p , k Δ α b q , k Δ α b r , k
Here, ( b p , b q , b r ) represent the three-axis gyroscope biases.
The measurement function h ( x k ) maps the five-dimensional state vector to the two-dimensional measurement space. For this linear model, it is defined as h ( x k ) = θ k ϕ k T .
It is essential to clarify these two equations, which describe the complete estimation problem. They consist of two distinct components: the filter’s prediction algorithm (Equation (5)) and the theoretical system measurement model (Equation (6)).
In the filter prediction model (Equation (5)), the goal is to generate the a priori (predicted) state estimate x ˜ k + 1 . To do this, the filter must use the best available information from the previous step, which is the a posteriori (corrected) state estimate x ^ k . Using x ^ k as the input to the nonlinear function f ( ) is the standard and correct formulation for the prediction step of a recursive filter.
In the theoretical measurement model (Equation (6)), the equation describes how the true, unobservable state x k relates to the actual sensor measurement y k , which is corrupted by measurement noise V k .
This combined formulation clarifies the distinct roles of the true state ( x k ), the corrected estimate ( x ^ k ), and the predicted estimate ( x ˜ k + 1 ) within the filter’s operation.
In FEFK, since fractional-order corrections are applied in the fractional-order prediction part, corresponding adjustments are also necessary.
F k 1 = f ( x , u k 1 ) x x = x ^ k 1
The partial derivatives describe the sensitivity of the system states (roll, pitch angles) to themselves and other state variables. Traditional methods typically neglect the influence of the time step d t on the Jacobian matrix due to system nonlinearity. In this study, by multiplying the above Taylor expansion by the time step d t , a correction term for the state transition Jacobian matrix is obtained:
A j = I + F k 1 d t
Here, I denotes the identity matrix. This study conducts a detailed analysis of the nonlinear dynamic variations in the roll, pitch, and yaw angles, calculating the sensitivity partial derivatives among the state variables. By capturing cross-coupling effects and extending the computation of each factor’s partial derivatives to include interactions with other factors, the dynamic interactions among variables in the nonlinear system can be better described. Through precise calculation of the partial derivatives of the attitude angle state equations and applying this approach to modify the Jacobian matrix, the resulting Jacobian matrix in this work more accurately characterizes the system’s nonlinear dynamic characteristics, especially under large-angle and high-dynamic conditions.
The covariance prediction step is the key stage where the non-Markovian, long-memory characteristics of the fractional-order system are incorporated into the FEKF algorithm. Unlike the standard EKF, the FEKF computes the a priori (predicted) error covariance P k | k 1 by adding a fractional-order covariance correction term P k f r a c to the standard prediction. This term quantifies the accumulated contribution of historical state uncertainty to the current prediction uncertainty.
First, the fractional coefficient matrix γ j is defined. This is a diagonal matrix whose elements are composed of standard binomial coefficients corresponding to each component of our five-dimensional state vector x = [ θ , ϕ , b p , b q , b r ] T :
γ j = d i g α θ j α ϕ j α b p j α b q j α b r j
where α j is the standard binomial coefficient as defined in Equation (4), and α θ ,   α ϕ ,   α b p ,   α b q ,   α b r are the fractional orders corresponding to each of the five states, which are to be optimized.
Next, based on the Grünwald–Letnikov definition, the fractional-order covariance correction term P k f r a c is computed as follows:
P k f r a c = j = 2 min ( k , L ) γ j P k j | k j γ j T
Here, L is the length of the historical window, limiting the memory range of the calculation; and P k j | k j is the a posteriori (corrected) error covariance matrix from j steps in the past. This summation (starting from j = 2 ) reflects the influence of historical covariance information, weighted by the fractional coefficients γ j , on the current predicted covariance.
Finally, this correction term is added to the standard EKF covariance prediction formula to obtain the FEKF’s a priori error covariance matrix P k | k 1 :
P k | k 1 = A k 1 P k 1 | k 1 A k 1 T + Q k + P k f r a c
where A k 1 is the linearized state transition matrix defined by Equation (9), P k 1 | k 1 is the a posteriori error covariance matrix from the previous step, and Q k is the process noise covariance matrix. Here, Q represents the process noise covariance matrix.
In this manner, the FEKF’s covariance prediction explicitly incorporates the historical memory effect inherent in the fractional-order model ( Q k ), in addition to the uncertainty from the current state transition ( A k 1 P k 1 | k 1 A k 1 T ) and the process noise ( Q k ), thereby potentially achieving more accurate estimation in systems exhibiting long-memory characteristics.
Measurement Update Stage: In the conventional FEKF, the measurement residual is calculated as:
r k = y k h ( x ˜ k )
In this study, the introduction of fractional-order operators aims to create a filter that is structurally consistent in its handling of historical information. Specifically, the conventional EKF and FEKF update step is designed for integer-order Markovian systems. This creates a structural inconsistency with our process model Equation (5), which explicitly uses a fractional-order term Δ α x ˜ to capture the system’s non-Markovian, long-memory dynamics.
To address this mismatch and align the update mechanism with the system’s fractional-order nature, this paper employs a sliding window approach that accumulates residuals from the past N time steps to construct a fractional-order residual:
r ˜ k = i = 0 N w i r k i
where
w i = ( 1 ) i α i
By updating the Kalman gain using r ˜ k instead of a single r k , when α 1 and N = 0 hold, the weights w 0 = 1 apply while others w i = 0 cause the FEFK to degenerate into the standard EKF.
The measurement function h ( ) from Equation (6) is linearized by calculating its Jacobian matrix H k at the predicted state estimate x ^ k | k 1 .
H k = h ( x ) x | x = x ˜ k
The Kalman gain K k is:
K k = P k | k 1 H k ( H k P k | k 1 H k + T R ) 1 T
Here, R represents the measurement noise covariance matrix.
By incorporating the aggregated residual r ˜ k into the FEFK update formula, we obtain:
x ^ k | k = x ˜ k + K k r ˜ k
The covariance is calculated using the traditional FEFK method as follows:
P k | k = ( I K k H k ) P k | k 1
The selection of the fractional-order parameter α significantly impacts the filtering performance. Therefore, it is necessary to optimize the fractional-order parameter for specific applications. Accordingly, this paper proposes a method based on the HO algorithm to optimize the fractional-order parameter α in the FEFK.

2.3. Principle of the HO Algorithm

The HO algorithm is a swarm intelligence optimization method that abstracts the behavioral patterns of hippopotamuses into a mathematical model.
Stage 1: Hippopotamus Position Updating. In the HO algorithm, the solution with the best fitness in the current population is designated as the dominant hippopotamus position, denoted as D h p p o . During this phase, a subset of the hippopotamuses (candidate solutions) attempts to move closer to the dominant individual to improve the overall quality of the population. The mathematical formulation of this behavior is as follows:
x i , j n e w = x i , j + y 1 ( D h p p o I 1 x i , j )
where x i , j represents the current value of the i t h candidate solution in the j t h dimension; x i , j n e w is the updated value; y 1 0 , 1 is a uniformly distributed random number; I 1 1 , 2 is a random integer. When I 1 = 1 , the increment is:
y 1 ( D h p p o x i , j )
The candidate solution takes a step toward the optimal solution. When I 1 = 2 , the increment is:
y 1 ( D h p p o 2 x i , j )
This mechanism enables candidate solutions to randomly drift around the optimal solution. Such a strategy allows some candidates to move away from the current solution, maintaining diversity within the population.
Phase 2: Hippopotamus Defending Against Predators. The HO algorithm introduces the concept of a virtual predator. In each iteration, a “predator” solution P r e d a t o r is randomly generated. Its position is determined by uniform random sampling within the search space, which enhances the algorithm’s exploration capability by encouraging candidate solutions to escape from potentially suboptimal regions. The position of the predator is mathematically expressed as:
P j p r e d = l b j + r u b j l b j , j = 1 , 2 m
where l b j and u b j are the lower and upper bounds of the j t h variable, respectively, and r is a uniformly distributed random number within the range 0 , 1 , The role of is to introduce randomness, acting as the engine for the algorithm’s unpredictability.
This mechanism is mathematically represented by comparing the fitness of the predator, denoted as F Pr e d a t o r , with the fitness of the hippo itself, denoted as F i , and then applying different position update formulas accordingly. Meanwhile, the distance between the two is defined as:
D = P r e d a t o r x i
To simulate the escape behavior of a hippopotamus, the HO algorithm introduces a L é v y random vector R L to generate sudden jumps [23]. When evasion is required, this vector is added to the current position. The mathematical formulation is expressed as follows:
Δ x L é v y ϑ = 0.05 w σ w v 1 ϑ
If F ( α pred ) < F i , The update formula is given by:
x i R = R L P p r e d + f c d cos ( 2 π g ) · 1 D i
When F Predator > F i , Otherwise, only a slight adjustment is made.
x i R = R L P p r e d + f c d cos ( 2 π g ) · 1 2 D i + r
Here, c ~ U ( 1 , 1.5 ) , d ~ U ( 2 , 3 ) , and g ~ U ( 1 , 1 ) .Within the algorithm’s update mechanism, the parameters g, c, and d work in synergy to dynamically regulate the search behavior. The role of g is to dynamically adjust the search step size to balance global exploration and local exploitation as the optimization progresses. The influence of c is more pronounced, as it directly controls the intensity of the entire “predator-prey” interaction, effectively managing the algorithm’s strategic shift from an exploratory to an exploitative phase over time. Finally, the role of d is to introduce directional uncertainty into the algorithm’s movement, which provides a more complex random perturbation mechanism than simply adjusting the step size, thereby enhancing its ability to escape from local optima.
Stage 3: Escape Phase. Centered at the current solution, the radius decreases following the iteration process. The candidate new position x i , j E is obtained by random sampling within this local range.
x i , j E = x i , j + r l b j l o c a l + s 1 u b j l o c a l l b j l o c a l
where s 1 is a random factor that can take one of the following three values:
s 1 = 2 r 1 1 r 2 r 3 r 1 U ( 0 , 1 ) r 2 N ( 0 , 1 ) r 3 U ( 0 , 1 )
In each iteration, the algorithm randomly selects one of the above strategies to generate x i , j E , thus assigning a corresponding value to s 1 . In this way, the local candidate position may lie on either side of the current solution ( r 1 ), be biased toward a specific direction ( r 3 ), or be located near a high-probability region ( r 2 ). This mechanism increases the likelihood of discovering a better local optimum. The newly generated position is then compared with the original one, and if the fitness improves, the new position is accepted; otherwise, the original solution is retained.

2.4. Problem Formulation and Methodology

Problem Formulation: To apply the HO algorithm for parameter optimization within the FEFK attitude estimation framework, it is essential first to define the objective function of the optimization problem. We select the attitude estimation error of the filter over a given time interval as the optimization target. The fitness function is constructed based on the error between the ground truth attitude x t r u e ( k ) and the FEFK estimated value. The fitness function formulated in this study is:
J ( α ) = 1 N k = 1 N x ^ ( k ; α ) x t r u e ( k ) 2
where x ^ ( k ; α ) denotes the attitude estimate obtained by running the FEFK filter up to step k with parameter α . The optimization objective is to find α that minimizes J ( α ) which corresponds to significantly reducing the attitude estimation error. This problem is typically challenging to solve analytically via differentiation, since J ( α ) is a complex function derived from nonlinear filtering. However, stochastic optimization algorithms such as the Hippo Optimization (HO) algorithm can be employed to iteratively test different values of α , progressively approaching the optimal parameter.
Parameter Settings: The population size of the HO algorithm is set to N , with the search range for α defined as α [ 0 , 3 ] . The range of α should not be too large, as an excessively wide range may diminish the fractional-order memory advantage. Within this range, N initial candidate solutions α i . are generated uniformly at random. Additionally, the maximum number of iterations T and other control parameters of the HO algorithm are specified. Other control parameters of the HO algorithm, such as the chasing coefficient and the gravity coefficient, were adopted directly from the original publication by Abdollahzadeh et al. [16]. This decision was made because the source paper demonstrated that these default values provide a robust balance between exploration and exploitation across a wide range of benchmark functions. Adopting these well-vetted parameters ensures a fair baseline for evaluating the algorithm’s performance without introducing confounding variables from parameter meta-optimization.
Implementation Method: For each candidate α i , compute the corresponding J ( α i ) using Equation (30) as the fitness value F i . Record the best solution α best and its associated error F best within the current population, which corresponds to the “leader” hippopotamus D h p p o .
During the iteration process from t = 1 to T , the population solutions are updated according to the three-phase behavioral rules of the HO algorithm. The first half of the population individuals are updated using Equation (20):
α i , j n e w = α i , j + y 1 ( D h p p o I 1 α i , j )
This step uses the current best solution α best and random perturbations to adjust the value of α i . The variation of α i can be constrained within the defined domain; for example, if the updated α exceeds the range α [ 0 , 3 ] , truncation or clipping is applied. This approach enables a subset of solutions to converge toward the optimum while maintaining sufficient randomness to prevent premature convergence.
Boundary Handling: During the optimization process, it is possible for a candidate solution α i to be updated to a value outside the defined search space. To handle such events, a truncation (or clipping) method is applied. Specifically, if an updated α i exceeds the upper bound (3), it is reset to 3. If it falls below the lower bound (0), it is reset to 0. This deterministic approach was chosen for its simplicity and effectiveness in ensuring all solutions remain within the valid and physically meaningful search domain at all times.
To simulate predator-induced behavior, a virtual predator position α p r e d is first randomly generated using Equation (23), sampling uniformly within the defined interval. Then, for the latter half of the population, Equation (24) is applied to calculate their distance from α p r e d .
D = α p r e d α i
According to their fitness comparison, the values of α i are adjusted. Specifically, if F ( α p r e d ) < F i , then α i is significantly shifted toward α p r e d , as described by Equation (26):
α i R = R L + P p r e d + f c d cos ( 2 π g ) · 1 D i
Otherwise, a small adjustment toward α p r e d is performed according to Equation (27):
α i R = R L + P p r e d + f c d cos ( 2 π g ) · 1 2 D i + r
This mechanism allows some candidate solutions to be influenced by a randomly generated position. When this random position represents a more optimal direction, the individual can escape from its current local region, thereby accelerating global exploration.
A local random search is applied to all individuals in the population. For each candidate α i , a specific neighborhood range is defined. The perturbation factor s 1 , generated from three distinct distributions as described in Equation (29), ensures that the local search can either perform fine-grained exploration around the current solution or jump toward the edge of the neighborhood. The fitness of the newly generated position, F ( α i E ) , is evaluated. If the new candidate yields a better fitness, α i E , replaces the original α i ; otherwise, the original solution is retained. This strategy enables each individual to leverage local information for self-improvement, enhancing the exploitation ability of the algorithm in the later stages of the optimization process.
After each round of the above updates, the fitness of the affected individuals is re-evaluated, and α best along with F best are updated. If a superior solution emerges, it replaces the current leader. To reduce computational overhead, fitness evaluations are typically deferred during the updates in Stages 1 and 2; the objective function J is recalculated by re-running the FEKF only during Stage 3, when a new solution is accepted, in order to assess its corresponding fitness F .
Termination Criterion: The iterative process terminates when either the maximum number of iterations is reached or no significant improvement is observed over multiple generations. The best parameter α best recorded up to that point is output as the optimized result, along with the corresponding minimum estimation error F best . At this stage, the optimal fractional order for the FEKF under the given test scenario is effectively determined, see Figure 1.

3. Results

The experimental data utilized in this study include both a publicly available dataset provided by Professor Yan Gongmin’s laboratory [24] and real attitude measurements obtained using a triaxial inertial navigation testing system and flight attitude simulation turntable developed by Beijing JunDa TengFei Technology Co., Ltd., Beijing, China The experiments were conducted in two phases: initially using the open-source dataset, followed by tests with self-collected data.
The following Table 1 are the models of the software and hardware we used:
The improved FEKF with a fixed fractional order was compared against traditional fixed-parameter FEKF, accelerometer-based estimation, gyroscope integration, KF, EKF. Subsequently, the improved FEKF was combined with several intelligent optimization algorithms, and the resulting attitude estimation performance—measured in terms of MSE against ground-truth attitudes—was compared across HO-FEKF, HHO-FEKF, GWO-FEKF, GA-FEKF, and HiPPO-LegS-FEKF.
The experimental results demonstrate that HO-FEKF achieves superior performance in terms of computational cost and estimation accuracy. Moreover, its efficiency and robustness make it suitable for practical deployment in real-world applications.
We fix the fractional order of the FEKF at α = 1.8 . The mean squared errors (MSE) of the fixed-parameter traditional FKEF and the fixed-parameter improved FKEF are shown in Figure 2 and Figure 3, respectively. According to the results, when α = 1.8 the fixed-parameter traditional FKEF achieves M S E ϕ = 0.02583 , M S E θ = 0.09945 . In comparison, the fixed-parameter improved FKEF attains M S E ϕ = 0.02018   M S E θ = 0.05231 . These results indicate that the FEKF enhanced by the method proposed in this paper achieves higher accuracy than the traditional FEKF.
For the fixed-parameter improved FKEF at α = 1.8 , the attitude estimation errors relative to the true angles—compared with those from the gyroscope, KF and EKF—are illustrated in Figure 4 and Figure 5.
As shown in Figure 4 and Figure 5, the improved FEKF proposed in this study clearly outperforms the gyroscope-based method, KF, and EKF in estimating the attitude angles.
We employ the improved FEKF in conjunction with an intelligent algorithm to automatically search for the optimal fractional-order parameter, leading to the proposed HO-FEKF. To demonstrate the superiority of the algorithm, we compare its performance with HHO-FEKF, GWO-FEKF, GA-FEKF, and HiPPO-LegS-FEKF. It is worth noting that GWO-FEKF and GA-FEKF tend to converge to local optima when the population size is set too small. Therefore, to ensure a fair and effective comparison, the population size for these algorithms is set to 30 in this study, see Figure 6, Figure 7, Figure 8, Figure 9 and Figure 10.
The results are presented in Table 2.
To ensure fairness, all algorithms were configured with an identical population size 20 and search space [0, 3]. Furthermore, to maintain consistency with the unit labeling in the figures (which use degrees, °), all error metrics reported in the tables and text are also presented in degrees (°). Furthermore, we applied a unified, two-part termination criterion to all algorithms:
A maximum iteration limit: Set to 30 generations, ensuring no algorithm was allocated a larger computational budget than another.
A common early stopping rule: The run would terminate if the best-found solution did not improve for 10 consecutive generations.
A fine-grained grid search of the parameter space empirically verified that the global optimum for this dataset corresponds to α = 1.99 The performance of each algorithm in finding this optimum is detailed in Table 1 and visualized in the convergence plots.
Our proposed HO-FEKF framework successfully identified this global optimum, converging to α = 1.99 in approximately six generations. This rapid and accurate convergence can be attributed to the inherent characteristics of the Hippopotamus Optimization algorithm. HO maintains a robust balance between global exploration and local exploitation, but critically, it incorporates a unique mechanism to actively avoid local optima. This feature is particularly valuable because the relationship between the FEKF’s parameters and its performance is highly complex, creating numerous “local optima” that can easily trap standard algorithms. The HO algorithm is specifically designed to overcome this challenge; by identifying and escaping these false solutions, it can effectively navigate the entire search space to locate the true global optimum.
The GWO-FEKF and HiPPO-LegS-FEKF algorithms also eventually found the optimal fractional order. However, their convergence was significantly less efficient. GWO, while a capable global optimizer, follows a simpler social hierarchy-based search pattern that lacks the sophisticated local-optima-avoidance strategy of HO, leading to more generations required to escape suboptimal regions. HiPPO-LegS-FEKF, while accurate, was computationally prohibitive. Its underlying methodology, rooted in continuous-time memory systems, requires complex internal state calculations for every fitness evaluation. This inherent complexity resulted in the longest computation time, raising questions about its practicality for offline tuning tasks where efficiency is a concern.
GA-FEKF converged prematurely to a suboptimal value of α = 1.37 . This is a classic failure mode for Genetic Algorithms when faced with a complex, multimodal search space. We attribute this to the limited efficacy of its standard crossover and mutation operators in this context [25]. HHO-FEKF converged to a significantly worse local minimum of α = 1.53 . This algorithm, which models the hunting behavior of hawks, is known for its powerful and often aggressive exploitation phase. While this allows it to converge very quickly (35.66 s), it also makes it highly susceptible to getting trapped. The algorithm’s strategy is to operate on a “greedy” principle: upon discovering a seemingly good solution in the initial stages, it rapidly concentrates all its resources on local optimization. However, this greedy strategy causes it to prematurely lock onto an incorrect region, completely abandoning the global search and thereby missing the opportunity to find the true optimum entirely.
Practically, our findings demonstrate that the full potential of advanced filters like FEKF can only be unlocked through a carefully chosen, automated tuning process. The baseline comparison, where a manually tuned FEKF ( α = 1.8 ) yielded a significantly higher error, clearly shows the unreliability of manual tuning. The HO-FEKF framework provides a robust and efficient method to achieve high-accuracy, adaptive attitude estimation, removing the need for expert intuition and laborious trial-and-error, thereby enhancing the practical applicability of fractional-order filtering in real-world scenarios.
To further validate the feasibility of the proposed method, this study employed a three-axis inertial navigation test combined with a flight attitude simulation turntable to conduct algorithm verification. The data measured from the three-axis inertial navigation system and the flight attitude simulation turntable were used as the ground truth for attitude angles, serving as a benchmark for comparative experiments. The testing setup is illustrated in Figure 11.
A three-axis inertial navigation test combined with a flight attitude simulation turntable was conducted, during which both the roll and pitch angles were simultaneously rotated by 60 ° . This setup was designed to evaluate the performance of the improved FEKF under large-amplitude dynamic conditions, in comparison with the traditional FEKF, KF, and EKF. The fractional order for both the traditional and improved FEKF was fixed at α = 1.8 . The results are presented in Figure 12, where it is evident that the improved FEKF demonstrates superior performance over the traditional FEKF.
As shown in Figure 13 and Figure 14, the standard KF demonstrates better performance in pitch angle estimation compared to the EKF and traditional FEKF, though it is slightly inferior to the improved FEKF. However, its roll estimation suffers from significant fluctuations and large errors, indicating poor stability. The EKF and traditional FEKF exhibit better results in roll estimation, yet their pitch estimation errors are greater than those of the KF and improved FEKF. Overall, the traditional FEKF outperforms both KF and EKF in combined performance, but it is still clearly inferior to the improved FEKF. These findings indicate that the improved FEKF provides superior performance under large-amplitude dynamic conditions compared to the traditional FEKF, KF, and EKF.
The performance comparisons of HO-FEKF, GWO-FEKF, GA-FEKF, HHO-FEKF, and HiPPO-LegS-FEKF under large-angle rotational conditions, in relation to the true attitude angles, are illustrated in Figure 15 and Figure 16.
The results are presented in Table 3.
Through a fine-grained grid search, we verified that α = 1.91 is the global optimum for this dataset. Our HO-FEKF not only successfully achieved this target but also demonstrated superior convergence speed and computational efficiency. However, the most revealing discovery came from the challenging test on the large-amplitude, real-world rotational dataset. This scenario acted as a touchstone, exposing the fragility of other competing algorithms in practical applications as HHO-FEKF, GWO-FEKF, GA-FEKF, and HiPPO-LegS-FEKF all failed in this test, becoming trapped in suboptimal local minima.
This collective failure reveals a key insight: the search space for real-world FEKF parameter optimization is far more rugged and deceptive than what is presented by benchmark data. The abnormally high mean squared error exhibited by GA-FEKF, in particular, is rooted in the inherent “premature convergence” defect of the genetic algorithm when handling such problems. Due to its population losing genetic diversity too early, the standard crossover and mutation operators were powerless to drive the solution out of a strong local optimum trap, causing it to converge in the wrong region. Similarly, although HHO has a fast iteration speed, its aggressive exploitation strategy makes it a high-risk option, while the success of GWO and HiPPO-LegS is limited to simpler scenarios, exposing their lack of robustness when facing complex dynamics.
In summary, all evidence indicates that HO-FEKF is not just an incremental improvement in performance but a fundamentally more effective and reliable solution. Its ability to maintain robust global search capabilities even in the most challenging scenarios fully confirms the value of its advanced algorithmic design and its immense practical utility in solving the intractable problem of fractional-order parameter optimization in FEKF.

4. Conclusions and Future Scope

The conclusion of this study is not merely that the HO-FEKF algorithm is numerically superior to other methods, but rather, through an in-depth analysis of the experimental results, it reveals the inherent challenges of the fractional-order system parameter optimization problem and demonstrates why the HO algorithm is an effective tool for its solution.
Our core argument is built upon the following key experimental evidence:
The Objective Existence of the Global Optimum and the Precise Convergence of HO-FEKF: Through a fine-grained grid search, we first established α = 1.99 as the indisputable global optimum for the public dataset scenario, setting a gold standard for the performance evaluation of all algorithms. Against this benchmark, the experimental results clearly show that the HO-FEKF was the only framework capable of converging to this optimum point stably and efficiently. Its rapid convergence within a minimal number of generations is a direct testament not only to its efficiency but also to its algorithmic robustness.
The “Failure Modes” of Competing Algorithms as Counter-evidence: The failures of other algorithms were not simply poor performance: their specific failure modes provide powerful counter-evidence for our thesis. The GA converged to a suboptimal α = 1.91 , resulting in a significantly higher root-mean-square error. This precisely exposes the classic defect of “premature convergence” that arises from a premature loss of population diversity when faced with a complex optimization landscape. Even more striking was the Harris Hawks Optimizer (HHO); although it had the fastest per-iteration time, it converged to a distant local trap ( α = 1.45 ). This validates that its “greedy” exploitation strategy is high-risk and unreliable when confronted with problems containing deceptive local optima.
The “Stress Test” of Real-World Data as the Definitive Proof: The most convincing evidence was derived from the large-amplitude, real-world rotational dataset. In this experiment, which simulates a true engineering challenge, all competing algorithms—including GWO and HiPPO-LegS, which performed adequately on the simpler benchmark—failed and became trapped in local optima. The singular success of HO-FEKF in this extreme scenario definitively proves that its advanced mechanism for local optima avoidance is not merely an enhancement but a necessary condition for ensuring system reliability in practical applications.
In summary, the conclusion drawn directly from this body of evidence is that the value of the HO-FEKF framework extends far beyond providing a filter with lower error. Its true contribution lies in successfully solving an optimization problem that is fundamentally intractable for traditional metaheuristic algorithms. Therefore, we have not only proposed a new method but have also, through rigorous comparison and failure analysis, demonstrated why it is the correct tool for the FEKF parameter optimization challenge, thereby genuinely bridging the gap from fractional-order filtering theory to high-performance, high-reliability practical application.
Building upon the successful validation of the HO-FEKF framework, several promising and high-impact avenues for future research are evident:
Unified Multi-Parameter Co-optimization: The current work focused on the critical parameter α . A significant and logical next step is to expand the HO framework to perform a simultaneous, co-optimization of the complete parameter set α Q R , where Q and R are the process and measurement noise covariance matrices. This would holistically address the strong coupling effects between these parameters and could unlock further performance enhancements. Extension to Broader Application Domains: The demonstrated success of the HO-FEKF in attitude estimation strongly suggests its potential applicability to other complex state estimation problems where fractional-order dynamics are likely present. Future research could explore its utility in diverse fields such as robotics, biomedical signal processing, and financial time-series forecasting.

Author Contributions

Conceptualization, X.Y.; methodology, G.L.; software, G.L.; validation, G.L.; formal analysis, G.L.; investigation, G.L.; resources, X.Y., L.Z., J.W. (Jianqi Wang), J.W. (Jianhui Wen) and X.L.; data curation, G.L.; writing—original draft preparation, G.L.; writing—review and editing, X.Y. and X.L.; visualization, G.L.; supervision, X.L.; project administration, X.L.; funding acquisition, X.Y. and X.L. All authors have read and agreed to the published version of the manuscript.

Funding

Key Research and Development Project of Guangxi Science and Technology Department (Project No. 23026149); Guangxi Key Research and Development Plan Project (Project No. AB24010073); 2022 Guilin Key Research and Development Plan (Grant No. 20220107-1).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Since our data is confidential to the funder and cannot be provided, the public dataset is available at the following URL: https://psins.org.cn/newsinfo/4445782.html (accessed on 18 June 2025).

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Al-Ahmadi, A. Drone Attitude and Position Prediction via Stacked Hybrid Deep Learning Model for Massive MIMO Applications. IEEE Access 2024, 12, 191377–191392. [Google Scholar] [CrossRef]
  2. Xiaolong, Y.; Dunzhuo, B.; Fuchun, Z.; Wei, Z. Magnetometer Calibration and Missile Attitude Filtering Method Based on Energy Estimation. IEEE Access 2022, 10, 113570–113582. [Google Scholar] [CrossRef]
  3. Groves, P.D. Principles of GNSS, Inertial, and Multisensor Integrated Navigation Systems, 2nd ed.; Artech House on Demand: Norwood, MA, USA, 2013. [Google Scholar]
  4. Kalman, R.E. A new approach to linear filtering and prediction problems. J. Basic Eng. 1960, 82, 35–45. [Google Scholar] [CrossRef]
  5. Lainiotis, D.G. Nonlinear Estimation and Control; IEEE: Piscataway, NJ, USA, 1970; Volume 58, pp. 1134–1159. [Google Scholar]
  6. Julier, S.J.; Uhlmann, J.K. Unscented Filtering and Nonlinear Estimation; IEEE: Piscataway, NJ, USA, 2004; pp. 401–422. [Google Scholar]
  7. Sharma, N.; Rufus, E.; Karar, V.; Poddar, S. Fractional order extended kalman filter for attitude estimation//Intelligent Systems Design and Applications. In Proceedings of the 18th International Conference on Intelligent Systems Design and Applications (ISDA 2018), Vellore, India, 6–8 December 2018; Springer International Publishing: Berlin/Heidelberg, Germany, 2020; Volume 1, pp. 823–832. [Google Scholar]
  8. Sierociuk, D.; Macias, M.; Markowski, K.A. Fractional-Order Identification of Gyroscope MEMS Noise Under Various Temperature Conditions. Sensors 2024, 24, 7504. [Google Scholar] [CrossRef] [PubMed]
  9. Wang, G.; Sun, X. Robust Kalman filter for fractional order systems with uncertain colored noise variance. Meas. Control. 2024, 57, 1445–1455. [Google Scholar] [CrossRef]
  10. Gao, K.; Song, J.; Wang, X.; Li, H. Fractional-order proportional-integral-derivative linear active disturbance rejection control design and parameter optimization for hypersonic vehicles with actuator faults. In Tsinghua Science and Technology; Tsinghua University Press: Beijing, China, 2021; Volume 26, pp. 9–23. [Google Scholar] [CrossRef]
  11. Wondosen, A.; Debele, Y.; Kim, S.K.; Shi, H.Y.; Endale, B.; Kang, B.S. Bayesian optimization for fine-tuning EKF parameters in UAV attitude and heading reference system estimation. Aerospace 2023, 10, 1023. [Google Scholar] [CrossRef]
  12. Jin, X.B.; Chen, W.; Ma, H.J.; Kong, J.L.; Su, T.L.; Bai, Y.T. Parameter-free state estimation based on Kalman filter with attention learning for GPS tracking in autonomous driving system. Sensors 2023, 23, 8650. [Google Scholar] [CrossRef] [PubMed]
  13. Tavares, A.J.A., Jr.; Oliveira, N.M. A Novel Approach for Kalman Filter Tuning for Direct and Indirect Inertial Navigation System/Global Navigation Satellite System Integration. Sensors 2024, 24, 7331. [Google Scholar] [CrossRef] [PubMed]
  14. Liu, L.; Yin, C.; Su, Y.; Lin, Y.; Lei, Y. Optimization of Covariance Matrices of Kalman Filter with Unknown Input Using Modified Directional Bat Algorithm. Buildings 2025, 15, 196. [Google Scholar] [CrossRef]
  15. Singh, H.; Kumar, H.; Bingi, K.; Prusty, B.R.; Devan, P.A.M. A Review on Developments and Applications of Fractional-Order Kalman Filter. In Sustainable Energy and Technological Advancements, ISSETA; Panda, G., Alhelou, H.H., Thakur, R., Eds.; Advances in Sustainability Science and Technology; Springer: Singapore, 2023. [Google Scholar] [CrossRef]
  16. Amiri, M.H.; Mehrabi Hashjin, N.; Montazeri, M.; Mirjalili, S.; Khodadadi, N. Hippopotamus optimization algorithm: A novel nature-inspired optimization algorithm. Sci. Rep. 2024, 14, 5032. [Google Scholar] [CrossRef] [PubMed]
  17. Heidari, A.A.; Mirjalili, S.; Faris, H.; Aljarah, I.; Mafarja, M.; Chen, H. Harris hawks optimization: Algorithm and applications. Future Gener. Comput. Syst. 2019, 97, 849–872. [Google Scholar] [CrossRef]
  18. Holland, J.H. Adaptation in Natural and Artificial Systems: An Introductory Analysis with Applications to Biology, Control, and Artificial Intelligence; MIT Press: Cambridge, MA, USA, 1992. [Google Scholar]
  19. Mirjalili, S.; Mirjalili, S.M.; Lewis, A. Grey wolf optimizer. Adv. Eng. Softw. 2014, 69, 46–61. [Google Scholar] [CrossRef]
  20. Gu, A.; Dao, T.; Ermon, S.; Rudra, A.; Ré, C. Hippo: Recurrent memory with optimal polynomial projections. Adv. Neural Inf. Process. Syst. 2020, 33, 1474–1487. [Google Scholar]
  21. Etkin, B.; Reid, L.D. Dynamics of Flight: Stability and Control; John Wiley & Sons: Hoboken, NJ, USA, 1995. [Google Scholar]
  22. Scherer, R.; Kalla, S.L.; Tang, Y.; Huang, J. The Grünwald–Letnikov method for fractional differential equations. Comput. Math. Appl. 2011, 62, 902–917. [Google Scholar] [CrossRef]
  23. Faramarzi, A.; Heidarinejad, M.; Mirjalili, S.; Gandomi, A.H. Marine Predators Algorithm: A nature-inspired metaheuristic. Expert Syst. Appl. 2020, 152, 113377. [Google Scholar] [CrossRef]
  24. Gongmin, Y.A. Set of Error-Free Inertial Navigation Flight Data, Institute of Navigation and Control, n.d. Available online: https://psins.org.cn/newsinfo/4445782.html (accessed on 18 June 2025).
  25. Goldberg, D.E. Genetic Algorithms in Search, Optimization, and Machine Learning; Addison-Wesley Pub. Co.: Boston, MA, USA, 1989. [Google Scholar] [CrossRef]
Figure 1. System Flowchart.
Figure 1. System Flowchart.
Sensors 25 06942 g001
Figure 2. Comparison Between Traditional FEKF with α = 1.8 and Truth Attitude Angles.
Figure 2. Comparison Between Traditional FEKF with α = 1.8 and Truth Attitude Angles.
Sensors 25 06942 g002
Figure 3. Comparison Between Improved FEKF with α = 1.8 and Truth Attitude Angles.
Figure 3. Comparison Between Improved FEKF with α = 1.8 and Truth Attitude Angles.
Sensors 25 06942 g003
Figure 4. Roll Angle Error Comparison Between Improved FEKF with α = 1.8 , Gyroscope, KF, EKF.
Figure 4. Roll Angle Error Comparison Between Improved FEKF with α = 1.8 , Gyroscope, KF, EKF.
Sensors 25 06942 g004
Figure 5. Pitch Angle Error Comparison Between Improved FEKF with α = 1.8 , Gyroscope, KF EKF.
Figure 5. Pitch Angle Error Comparison Between Improved FEKF with α = 1.8 , Gyroscope, KF EKF.
Sensors 25 06942 g005
Figure 6. Estimation Results of HO-FEKF.
Figure 6. Estimation Results of HO-FEKF.
Sensors 25 06942 g006
Figure 7. Estimation Results of GWO-FEKF.
Figure 7. Estimation Results of GWO-FEKF.
Sensors 25 06942 g007
Figure 8. Estimation Results of GA-FEKF.
Figure 8. Estimation Results of GA-FEKF.
Sensors 25 06942 g008
Figure 9. Estimation Results of HHO-FEKF.
Figure 9. Estimation Results of HHO-FEKF.
Sensors 25 06942 g009
Figure 10. Estimation Results of HiPPO-LegS-FEKF.
Figure 10. Estimation Results of HiPPO-LegS-FEKF.
Sensors 25 06942 g010
Figure 11. Triaxial Inertial Navigation Test and Flight Attitude Simulation Platform.
Figure 11. Triaxial Inertial Navigation Test and Flight Attitude Simulation Platform.
Sensors 25 06942 g011
Figure 12. α = 1.8 Comparison between the improved FEKF and the traditional FEKF under dynamic conditions.
Figure 12. α = 1.8 Comparison between the improved FEKF and the traditional FEKF under dynamic conditions.
Sensors 25 06942 g012
Figure 13. α = 1.8 Comparison of the roll estimation under dynamic conditions among the improved FEKF (with), traditional FEKF, KF, and EKF.
Figure 13. α = 1.8 Comparison of the roll estimation under dynamic conditions among the improved FEKF (with), traditional FEKF, KF, and EKF.
Sensors 25 06942 g013
Figure 14. α = 1.8 Comparison of the pitch estimation under dynamic conditions among the improved FEKF (with), traditional FEKF, KF, and EKF.
Figure 14. α = 1.8 Comparison of the pitch estimation under dynamic conditions among the improved FEKF (with), traditional FEKF, KF, and EKF.
Sensors 25 06942 g014
Figure 15. Estimation Results of HO-FEKF.
Figure 15. Estimation Results of HO-FEKF.
Sensors 25 06942 g015
Figure 16. Estimation Results of GWO-FEKF.
Figure 16. Estimation Results of GWO-FEKF.
Sensors 25 06942 g016
Table 1. Introduction to Software and Hardware Specifications.
Table 1. Introduction to Software and Hardware Specifications.
HardwareSoftware
CPU: [Intel Core i7-12700K @ 4.2 GHz] (Intel: Santa Clara, CA, USA)Operating System: [Windows 11 64-bit]
RAM: [32 GB DDR5 @ 4800 MHz]Environment: [MATLAB R2023b]
IMU Model: [JY61P] (100Hz)Programming Language: MATLAB
Table 2. α Optimization Performance Comparison.
Table 2. α Optimization Performance Comparison.
AlgorithmSPEEDTIME S n α M S E ϕ M S E θ
FEKF// O ( M ) 1.80.025830.09945
Improved FEKF// O ( M ) 1.80.020180.05231
GWO-FEKF10141.38SO(600M)1.990.005220.00232
GA-FEKF15568.42SO(600M)1.370.006500.00213
HHO-FEKF535.66SO(20M)1.530.005810.00223
HiPPO-LegS-FEKF10105.75SO(100M)1.990.005220.00232
OUR6 39.15SO(20M)1.990.005220.00232
Table 3. α Optimization Performance Comparison.
Table 3. α Optimization Performance Comparison.
AlgorithmSPEEDTIME S n α M S E ϕ M S E θ
GWO-FEKF15198.48sO(600M)1.800.011170.01881
GA-FEKF20368.42sO(600M)1.371.223061.62020
HHO-FEKF946.66sO(20M)1.830.012410.02017
HiPPO-LegS-FEKF13135.37sO(100M)1.950.008690.01946
OUR846.22sO(20M)1.910.006990.01694
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

Yang, X.; Lin, G.; Wang, J.; Zhang, L.; Wen, J.; Li, X. Optimized Fractional-Order Extended Kalman Filtering for IMU-Based Attitude Estimation Using the Hippopotamus Algorithm. Sensors 2025, 25, 6942. https://doi.org/10.3390/s25226942

AMA Style

Yang X, Lin G, Wang J, Zhang L, Wen J, Li X. Optimized Fractional-Order Extended Kalman Filtering for IMU-Based Attitude Estimation Using the Hippopotamus Algorithm. Sensors. 2025; 25(22):6942. https://doi.org/10.3390/s25226942

Chicago/Turabian Style

Yang, Xiaoping, Gangwang Lin, Jianqi Wang, Lieping Zhang, Jianhui Wen, and Xiaoxia Li. 2025. "Optimized Fractional-Order Extended Kalman Filtering for IMU-Based Attitude Estimation Using the Hippopotamus Algorithm" Sensors 25, no. 22: 6942. https://doi.org/10.3390/s25226942

APA Style

Yang, X., Lin, G., Wang, J., Zhang, L., Wen, J., & Li, X. (2025). Optimized Fractional-Order Extended Kalman Filtering for IMU-Based Attitude Estimation Using the Hippopotamus Algorithm. Sensors, 25(22), 6942. https://doi.org/10.3390/s25226942

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