Next Article in Journal
TSLEPS: A Two-Stage Localization and Erasure Method for Privacy Protection in Sensor-Captured Images
Previous Article in Journal
Authentication of Counterfeit Electronics Using Rapid THz Time-of-Flight Imaging
Previous Article in Special Issue
An Inexpensive AI-Powered IoT Sensor for Continuous Farm-to-Factory Milk Quality Monitoring
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Time and Frequency Domain Analysis of IMU-Based Orientation Estimation Algorithms with Comparison to Robotic Arm Orientation as Reference †

Institute of Management and Technology, Hochschule Osnabrück, Kaiserstr. 10c, 49809 Lingen, Germany
*
Author to whom correspondence should be addressed.
This paper is an extended version of our paper published in 10th International Conference on Sensors Engineering and Electronics Instrumentation Advances (SEIA’ 2024), Ibiza (Balearic Islands), Spain, 25–27 September 2024.
Sensors 2025, 25(16), 5161; https://doi.org/10.3390/s25165161
Submission received: 6 June 2025 / Revised: 16 August 2025 / Accepted: 17 August 2025 / Published: 20 August 2025
(This article belongs to the Special Issue Advances in Physical, Chemical, and Biosensors)

Abstract

This work focuses on time and frequency domain analyses of IMU-based orientation estimation algorithms, including indirect Kalman (IKF), Madgwick (MF), and complementary (CF) filters. Euler angles and quaternions are used for orientation representation. A 6-DoF IMU is attached to a 6-joint UR5e robotic arm, with the robot’s orientation serving as the reference. Robotic arm data is obtained via an RTDE interface and IMU data via a CAN bus. Test signals include pose sequences, which are big-amplitude, slowly changing signals used to evaluate stationary and low-dynamics responses in the time domain, and small-amplitude, fast-changing generalized binary noise (GBN) signals used to evaluate dynamic responses in the frequency domain. To prevent poor filters’ performance, their parameters are tuned. In the time domain, RMSE and MaxAE are calculated for roll and pitch. In the frequency domain, composite frequency response and coherence are calculated using the Ockier method. RMSEs are computed for response magnitude and coherence, and averaged equivalent time delay (AETD) is derived from the response phase. In the time domain, MF and CF show the best overall performance. In the frequency domain, they again perform similarly well. IKF consistently performs the worst in both domains but achieves the lowest AETD.

1. Introduction

This paper is an extended version of our paper presented at the 10th International Conference on Sensors Engineering and Electronics Instrumentation Advances (SEIA’ 2024), Ibiza, Spain, 25–27 September 2024 [1].
Accurate orientation estimation is crucial for many applications and plays a huge role in aerospace, robotics, navigation, human movement analysis, and other areas [2,3,4]. Inertial measurement units (IMUs) are often used for orientation estimation. A 6-DoF (degree of freedom) IMU combines an accelerometer and a gyroscope that measure linear acceleration and angular velocity, respectively [2,4].
Orientation can be represented in several forms such as Euler angles, rotation matrices, axis-angle representation and quaternions [4,5,6] that describe the rotation required to align the sensor frame with the reference frame. In this work, Euler angles and quaternion orientation representations are used.
Euler angles describe three sequential rotations needed to arrive from the reference frame to the rotated target frame. In this work, ZY′X″ order of rotation is used. For this order of rotation, the first rotation happens around the Z axis of reference frame XYZ on angle ψ (yaw), the second rotation on angle θ (pitch) around the Y′ axis of frame X′Y′Z resulting from the first rotation, and the third rotation on angle ϕ (roll) around the X″ axis of frame X″Y′Z′ resulting from the second rotation. The resulting frame X″Y″Z″ corresponds to the target frame.
The body’s orientation can be estimated using an accelerometer. By measuring the projections of the gravity vector on the sensor axes, orientation can be estimated [2,3,4]. Gravity vector components in the body frame can be calculated using gravity vector components in the world reference frame pointing down, e.g., north-east-down frame (NED):
g b = R b w g w = R w b 1 g w = R w b g w = = ( R z ( ψ ) R y ( θ ) R x ( ϕ ) ) 0 0 g = g sin θ sin ϕ cos θ cos ϕ cos θ
where g b is the gravity vector expressed in the body frame, g w = 0 0 g is the gravity vector expressed in the world frame (NED convention), R b w is the rotation matrix from world frame to body frame, R w b is the rotation matrix from body frame to world frame, R w b 1 = R w b because rotation matrices are orthogonal, R w b = R z ( ψ ) R y ( θ ) R x ( ϕ ) is constructed by successive ψ (yaw), θ (pitch), and ϕ (roll) rotations.
Using Equation (1), the roll and pitch angles can be estimated. However, the yaw angle cannot be determined by this method.
ϕ = arctan 2 ( g y b , g z b )
θ = arcsin g x b g
Alternatively, body orientation can be estimated using a gyroscope. The relationship between body-frame angular velocities, which are measured by the gyroscope, and Euler angle rates and can be expressed as:
ω x b ω y b ω z b = T w b ( ϕ , θ ) ϕ ˙ θ ˙ ψ ˙ or equivalently ϕ ˙ θ ˙ ψ ˙ = T b w 1 ( ϕ , θ ) ω x b ω y b ω z b ,
where the transformation matrices are defined as:
T w b ( ϕ , θ ) = 1 0 sin ( θ ) 0 cos ( ϕ ) cos ( θ ) sin ( ϕ ) 0 sin ( ϕ ) cos ( θ ) cos ( ϕ )
T b w 1 ( ϕ , θ ) = 1 sin ( ϕ ) tan ( θ ) cos ( ϕ ) tan ( θ ) 0 cos ( ϕ ) sin ( ϕ ) 0 sin ( ϕ ) / cos ( θ ) cos ( ϕ ) / cos ( θ )
By integrating the time derivatives of the Euler angles from Equation (4) over time and knowing the initial orientation, the current body orientation can be estimated [2,3]. For a discrete-time system with time step Δ t , Euler angles at time m can be estimated using angles and rates at time m 1 using the forward Euler method:
ϕ m θ m ψ m = ϕ m 1 + ϕ ˙ m 1 Δ t θ m 1 + θ ˙ m 1 Δ t ψ m 1 + ψ ˙ m 1 Δ t
The method of orientation estimation with a gyroscope is effective only for short periods of time [3]. Due to the noise, the estimated orientation drifts from the actual orientation over time, even if the body is stationary.
Orientation representation using quaternions avoids singularities such as gimbal lock, which are associated with Euler angles, while providing rotation-order independence (due to a single rotation representation instead of three sequential ones) and ensuring better numerical stability and computational efficiency. Rotation can be described by a unit quaternion [6]:
q = q 0 + q 1 i + q 2 j + q 3 k , q 0 , q 1 q 2 q 3 = cos α 2 , u sin α 2 α = 2 · arccos ( q 0 ) , i 2 = j 2 = k 2 = 1 , q 0 , , q 3 R , q 0 2 + q 1 2 + q 2 2 + q 3 2 = 1 ,
where u sin ( α / 2 ) is a vector describing the rotation axis, and α is the rotation angle in the range [ 0 , 2 π ) .
The calculation of orientation of quaternion components using gravity vector components is shown in [4]. The following system must be solved to determine the quaternion components [4]:
2 ( q 1 q 3 + q 0 q 2 ) = a ^ x b 2 ( q 2 q 3 q 0 q 1 ) = a ^ y b q 0 2 q 1 2 q 2 2 + q 3 2 = a ^ z b a ^ x b 2 + a ^ y b 2 + a ^ z b 2 = 1
where a ^ x b , a ^ y b , a ^ z b are the normalized components of the measured acceleration vector in the body-fixed frame. Normalization is done by the magnitude of the measured acceleration vector. In static conditions, this magnitude equals the gravitational acceleration g. However, in dynamic conditions, the presence of linear accelerations causes the measured acceleration magnitude to deviate from g, which can introduce errors in the orientation estimation. The system (9) is underdetermined and can be solved only with additional constraints, such as assuming q 3 = 0 [4]. Under this assumption, the solution to the system is given by:
q 0 q 1 q 2 q 3 = ( a ^ z b + 1 ) / 2 a ^ y b / 2 ( a ^ z b + 1 ) a ^ x b / 2 ( a ^ z b + 1 ) 0
Alternative solutions to system (9) are also presented in [4].
Calculation of orientation using angular rates in the body-fixed frame can also be written in quaternion form [2,4]:
q ˙ = 1 2 q ω b
ω b = ω x b i + ω y b j + ω z b k ,
where ⊗ denotes the quaternion product between the orientation quaternion q and the quaternion representation of the angular velocity ω b in the body-fixed frame.
Similar to Equation (11), the quaternion at time step m in a discrete-time system can be estimated using the forward Euler method:
q m = q m 1 + q ˙ m 1 Δ t
Accelerometer and gyroscope data can be fused using different sensor fusion algorithms to achieve a more robust and accurate orientation estimation [3,4]. Various approaches have been proposed in the literature, each with specific advantages and drawbacks. Kalman filter variants, including the indirect Kalman filter (IKF) and the Extended Kalman Filter (EKF), offer a probabilistic framework and are theoretically optimal under Gaussian noise assumptions [2,3,4,7,8]. While the IKF reduces sensitivity to linearization errors compared to EKF by estimating only the error state, both approaches remain sensitive to sensor noise characteristics, rely on precise system modeling, and may experience degraded performance in highly dynamic conditions [2,3,4,7,8]. Complementary filters (CFs) [4] provide a computationally efficient alternative by blending high-frequency gyroscope data with low-frequency accelerometer information, yet they can lose accuracy in highly dynamic conditions as well. Gradient-descent-based methods, such as the Madgwick filter (MF) [2], offer fast convergence and good performance for low-cost IMUs without requiring a full dynamic model, but they may also accumulate orientation drift under fast rotational motions or significant transient linear accelerations affecting the accelerometer signal.
Using a 9-DoF IMU (accelerometer, gyroscope, magnetometer) allows for an orientation estimation relative to the Earth’s magnetic field and a gravity vector and helps correct gyroscope drift around the vertical axis [3,4]. However, a 9-DoF IMU is not used in this work because the experimental setup includes a robotic arm. Magnetometer measurements can be strongly affected by electromagnetic interference from its drives and other electrical equipment, as well as magnetic distortions caused by surrounding ferromagnetic materials.
To comprehensively evaluate the filters’ performance, traditional time-domain error metrics are combined with frequency-domain analysis, which captures key dynamic properties such as phase shift, magnitude response, and input–output coherence. While time-domain metrics like orientation error are effective for assessing accuracy during slow or static conditions, they may obscure important characteristics under dynamic motion, e.g., small time delays can result in large instantaneous errors despite accurate tracking. Frequency-domain analysis addresses these limitations by revealing how each filter attenuates or distorts signals across different frequency bands, quantifies phase delays, and measures linear correlation via coherence. These properties are robustly computed using the composite frequency response and coherence estimation approach described in the Ockier method [9].
Accurate computation of these metrics relies on a reliable reference for orientation. While indirect reference systems, such as optical tracking [10] or high-grade integrated inertial systems, can be used to provide such data, they may still lack the precision, repeatability, or long-term stability required to fully evaluate filter performance. In contrast, a high-precision robotic arm not only traces the pose with high accuracy but can also execute predefined trajectories reliably, enabling consistent and repeatable evaluation of orientation estimation algorithms. Several studies have used industrial robotic manipulators as precise, repeatable references for evaluating orientation or full pose estimation. Representative examples include Cavallo et al., who mounted an IMU on a KUKA manipulator to compare EKF-, Mahony-, and Madgwick-type estimators against the robot’s orientation [11]; El-Gohary and McNames, who validated joint-angle estimation with an IMU against a high-precision robot arm [12]; Ricci et al., who systematically characterized static and dynamic orientation accuracy using a KUKA LWR 4+ executing sinusoidal trajectories across frequencies [13]; Hislop et al. used an ABB IRB2600 industrial robot to validate the dynamic orientation accuracy of a commercial IMU system across several angular velocities and orientations, reporting error statistics under controlled motion conditions [14]; and more recently Kuti et al., who proposed a UR-series robot-based procedure that treats the manipulator as a high-accuracy reference for orientation sensors [15]. In line with this established practice, a robot arm is used as reference in this work. However, in contrast to most prior work that primarily reports time-domain metrics, our study adds an explicit frequency-domain evaluation, an analysis that remains relatively uncommon in the literature.
The remainder of this paper is structured as follows. Section 2 introduces the orientation estimation filters considered in this study. Section 3 describes the experimental setup, including the IMU and robotic arm configuration. Section 4 and Section 5 present the evaluation methodology and results in the time and frequency domains, respectively. Finally, Section 6 discusses the findings and concludes the paper.

2. Filters

2.1. Indirect Kalman Filter

The Indirect Kalman Filter (IKF), also known as the Error State Kalman Filter (ESKF), is a variant of the traditional Kalman Filter. In IKF, the state vector represents the state error rather than the actual state itself [7,8]. IKF is mathematically equivalent to a standard KF for linear systems, but it offers practical advantages in nonlinear settings [7,8]. In particular, by tracking the linearization error explicitly, the IKF often yields better numerical stability and accuracy than a conventional extended Kalman Filter (EKF) when estimating orientation [7,8].
In this work, IKF from the Sensor Fusion and Tracking Toolbox of MATLAB is used [16]. It uses a 9-element error state that tracks the orientation error, gyro bias error, and linear acceleration error [16]. Kalman equations used in this algorithm [16]:
x k = 0
P k = Q k
y k = z k
S k = R k + H k P k H k
K k = P k H k S k 1
x k + = K k y k
P k + = P k K k H k P k
where x k is the predicted state estimate representing the error process, P k is the predicted estimate covariance, y k is the innovation (or residual), S k is the innovation covariance, K k is the Kalman gain, x k + is the updated (corrected) state estimate, and P k + is the updated estimate covariance.
MATLAB’s IKF has the following parameters: variance in accelerometer signal noise, variance in gyroscope signal noise, variance in gyroscope offset drift, variance in linear acceleration noise, and decay factor for linear acceleration drift [16]. In MATLAB’s implementation of the IKF, the decay factor for linear acceleration drift is a scalar parameter in the range [0, 1), used to model the drift in linear acceleration as a low-pass-filtered white noise process [16]. It controls how quickly the estimated linear acceleration bias decays over time. A lower value causes the filter to adapt more rapidly to changes in acceleration, which is suitable for highly dynamic motion. Conversely, a higher value assumes more slowly varying acceleration and results in a more persistent bias estimate. To improve filter performance, default parameters of IKF were tuned (All filters used in this work were tuned using a Generalized Binary Noise (GBN) signal with a wider frequency range than the test signal GBN to introduce a broader range of dynamic conditions. The description of GBN is provided in Section 5.1.3) by using MATLAB’s tune function with a custom cost function being the sum of root mean squared errors (RMSEs) for roll and pitch. In general, RMSE can be calculated as:
RMSE = 1 n i = 1 n ( y i y ^ i ) 2
where y i is the true value, y ^ i is the predicted value, and n is the number of observations.

2.2. Complementary Filter

In this work, a quaternion-based complementary filter from Sensor Fusion and Tracking Toolbox of MATLAB [17] is used. Its implementation is described in [4]. In this filter, the gyroscope’s integrated orientation provides the high-frequency component of motion (capturing rapid rotations), while the accelerometer provides a low-frequency reference from the gravity vector (stabilizing long-term drift) [4,18].
The complementary filter blends the orientation estimates from the gyroscope and accelerometer using a weighted average, followed by normalization to ensure the result remains a unit quaternion. The update equation is given by [4]:
q k = α q gyro , k + ( 1 α ) q acc , k α q gyro , k + ( 1 α ) q acc , k ,
where q gyro , k is the orientation estimate obtained by integrating the gyroscope measurements, q acc , k is the estimate derived from the accelerometer, and α [0, 1] is the filter gain weighting the gyroscope contribution.
The choice of gain α significantly affects the filter dynamics. A larger value of ( 1 α ) , i.e., a higher accelerometer gain, causes the filter to converge more rapidly to the gravity-based orientation but increases sensitivity to noise and transient disturbances. Conversely, a smaller value of ( 1 α ) results in greater responsiveness to rapid motion but slower drift correction.
To improve filter performance, the default accelerometer gain ( 1 α ) = 0.01 was tuned by grid search to minimize the sum of RMSEs for roll and pitch on the tuning signal. The tuned gain is 0.005 .

2.3. Madgwick Filter

The Madgwick filter is a quaternion-based attitude estimator that fuses gyroscope and accelerometer data to track orientation. Originally introduced by Madgwick [2], it uses a single scalar gain β to balance gyroscope integration against accelerometer-based correction. The algorithm maintains a unit quaternion q representing orientation. At each timestep, the filter integrates the angular velocity ω to predict the new orientation, then corrects it by a gradient descent step that aligns the estimated gravity direction with the measured accelerometer vector [2].
The quaternion update can be summarized as [2]:
q ˙ ω = 1 2 q [ 0 , ω ] T ,
q ˙ est = q ˙ ω β f ( q ) f ( q ) ,
q q + q ˙ est Δ t ,
followed by normalization to unit length.
The filter represents orientation by a unit quaternion q . Gyroscope measurements ω = [ ω x , ω y , ω z ] T are converted to a quaternion derivative q ˙ ω = 1 2 q [ 0 , ω ] T . Pure gyroscope integration causes drift. Hence, the accelerometer a = [ a x , a y , a z ] T is used to correct this drift.
After normalization, a ^ = a / a , the filter minimizes the error:
f ( q ) = q * g ^ q [ 0 , a ^ ] T ,
where g ^ = [ 0 , 0 , 0 , 1 ] T is the global gravity vector. The filter derives the gradient analytically:
f ( q ) = J g ( q ) T f g ( q ) ,
where:
f g ( q ) = 2 ( q 1 q 3 q 0 q 2 ) a x 2 ( q 0 q 1 + q 2 q 3 ) a y 2 ( q 0 2 q 1 2 q 2 2 + q 3 2 ) a z ,
J g ( q ) = 2 q 2 2 q 3 2 q 0 2 q 1 2 q 1 2 q 0 2 q 3 2 q 2 0 4 q 1 4 q 2 0 .
Madgwick’s algorithm requires only a single gradient descent step per update [2]. The gradient f / f defines the correction axis. The correction is subtracted from the gyro-integrated quaternion derivative, thereby reducing tilt errors caused by gyroscope drift. To summarize, the main steps of the MF are:
  • Normalize accelerometer: a ^ = a / a .
  • Compute gyro quaternion derivative: q ˙ ω = 1 2 q [ 0 , ω ] T .
  • Compute f ( q ) using Jacobian J g and error f g .
  • Normalize gradient: g = f / f .
  • Apply correction: q ˙ est = q ˙ ω β g .
  • Integrate quaternion: q new = q + q ˙ est Δ t .
  • Normalize q new .
The scalar β is the only tuning parameter in the Madgwick filter. It controls how strongly the accelerometer correction is applied. A larger β results in faster convergence but increased sensitivity to noise. The relationship between β and the expected gyroscope measurement noise ω error is:
β = 3 4 ω error .
In practice, β can be tuned to improve filter performance. Grid search for β was used to minimize the sum of RMSEs for roll and pitch on the tuning signal. The resulting β used in this work is 0.006.

3. Experimental Setup

To evaluate the estimated orientation, it is essential to establish a reference orientation. Modern robotic arms, equipped with six or more joints, enable complex, precise, and accurate dynamic motion of an end effector, such as a gripper. For this reason, in this work, a Bosch MM7.10 IMU (Bosch Rexroth AG, Lohr am Main, Germany) is mounted on a 6-joint UR5e robotic arm (Universal Robots A/S, Odense, Denmark) to accurately track IMU orientation accurately (pose repeatability per ISO 9283 [19]: ±0.03 mm [20]) and execute dynamic maneuvers (maximum velocity: 4 m/s [20]). The experimental setup is shown in Figure 1.
The UR5e controller provides robot data such as the pose of the tool center point (TCP) frame via the TCP/IP-based (Here, TCP/IP refers to the Transmission Control Protocol/Internet Protocol, not to the tool center point) Real-Time Data Exchange (RTDE) interface with a configurable rate up to 500 Hz [21]. In this work, a rate of 100 Hz is used. For working with RTDE interface, the RTDE Python Client Library v2.7.2 is used.The TCP pose vector contains the coordinates and orientation of the TCP frame in the base frame (used as a reference frame) of the UR5e robot. Orientation of the TCP frame is provided in the rotation vector form (term used by Universal Robots for axis–angle representation), which is then transformed to quaternion and Euler angles representations.
The Bosch MM7.10 IMU provides accelerometer and gyroscope measurements at a rate of 100 Hz via the Controller Area Network (CAN) bus. The performance characteristics for angular rate and acceleration measurements, evaluated at room temperature, are summarized in Table 1 [22]. Our experiments were also carried out under similar room temperature conditions. The IMU frame is aligned with the TCP frame of the robot with a small offset along the Z-axis (around four centimetres). At the start of an experiment, TCP, and thus IMU, frames are aligned with the base frame. A PCAN-USB adapter (PEAK-System Technik GmbH, Darmstadt, Germany) provides the physical connection between the IMU and the computer, while data acquisition is handled using the Python-CAN v4.2.2 library.
After recording the robot and IMU data (both timestamped using the recording computer’s system clock), the two datasets were merged by linearly interpolating values to a common set of timestamps. Due to transmission and buffering delays there is a mismatch between the IMU and robot timestamps. To compensate for this, the time shift between the IMU and robot data was estimated by minimizing the Averaged Equivalent Time Delay (AETD) (for more details on the AETD calculation, see Equation (41)), based on the composite frequency response phase, with the time-shifted robot orientation as input and the integrated gyroscope measurements as output. The time shift that resulted in the lowest AETD was selected. For the pose sequence test signals (see description in Section 4.1.1), the following shifts were estimated and compensated: signal 1—31 ms; signal 2—16 ms; signal 3—20 ms. For the Generalized Binary Noise test signals (see description in Section 5.1.3): GBN roll—26 ms; GBN pitch—82 ms; GBN roll and pitch—4 ms.
For data postprocessing, filter implementation, parameter tuning and performance evaluation of the filters, MATLAB 2024a is used. For the evaluation of filter performance in the frequency domain, the MATLAB tool FitlabGui [9] developed by the DLR (German Aerospace Center) is used.

4. Time Domain Evaluation

4.1. Description and Methodology

4.1.1. Pose Sequence Signal

For the time-domain evaluation, pose sequence test signals are used, where pose sequence refers to a big-amplitude slowly changing (compared to small-amplitude, fast-changing signals such as GBN (Section 5.1.3)) sequential change in the robot’s pose over time. These signals are used in this work to assess the filters’ stationary behaviour and low-dynamic responses in the time domain. In pose sequence test signals 1 and 2, both the orientation and position of the TCP are varied to evaluate the filters’ performance under complex motion (translation and rotation). Pose sequence test signal 3 involves only a change in orientation (rotation around the TCP), without any position change. It is important to note that even pure rotation around the TCP results in the norm of the acceleration measured by the accelerometer not being equal to g, because the rotation does not occur around the accelerometer’s own frame (i.e., the IMU frame). The lever arm between the TCP and IMU frames introduces tangential and centripetal accelerations that are sensed by the accelerometer. The influence of this rotational motion on the linear acceleration at the IMU frame is given by:
a IMU = a TCP + α × r IMU / TCP tangential acceleration + ω × ω × r IMU / TCP centripetal acceleration
where a IMU and a TCP are the linear accelerations of the IMU and the TCP, respectively, α is the angular acceleration, ω is the angular velocity, and r IMU / TCP is the position vector from the TCP to the IMU.

4.1.2. Metrics

Root mean squared error (RMSE) is calculated for roll and pitch angles. Additionally, the maximum absolute error (MaxAE) is used.

4.2. Results

The RMSE and MaxAE values for roll and pitch angles and the sum of the errors for the angles, corresponding to the used filter and test signal, are presented in Table 2. The lowest value for a given test signal and metric is marked in green, and the biggest is in red. Errors for yaw angle are not taken into account due to the uncompensated yaw drift. Yaw drift happens due to the gyroscope drift and the inability of the gravity components analysis method to estimate the yaw angle and thus compensate for the drift. For the same reason, the cost function for tuning filters only included RMSEs for roll and pitch.
Figure 2 shows the robot (reference) orientation vs. estimated orientation for pose sequence test signal 1. Figure 3 shows the robot (reference) orientation vs. estimated orientation for pose sequence test signal 2. Figure 4 shows the robot (reference) orientation vs. estimated orientation for pose sequence test signal 3.
Considering the sum of RMSEs for roll and pitch, MF achieves the best performance in two out of three test signals. When evaluating the sum of MaxAEs for roll and pitch, CF performs best in two of the three test signals. Overall, the performance of CF and MF is very similar (the largest differences are 0.38° in the sum of RMSEs and 0.87° in the sum of MaxAEs), while IKF shows the worst performance (with the largest differences being 2.2° in the sum of RMSEs and 5.44° in the sum of MaxAEs).

5. Frequency Domain Evaluation

5.1. Description and Methodology

5.1.1. Discrete Fourier Transform

An important part of the evaluation in the frequency domain is the Fourier Transform, which provides the frequency spectrum of the signal.
By means of the discrete-time Fourier transform (DTFT), the frequency content of infinite-length discrete-time signals can be analyzed. It produces a continuous function of frequency defined over the interval [ π , π ] and is used primarily for the analysis of linear time-invariant (LTI) systems and signal behavior [23]. DTFT of a discrete-time signal x [ n ] is defined as:
X ( e j ω ) = n = x [ n ] e j ω n , ω [ π , π ]
The discrete Fourier transform (DFT) is a sampled version of the DTFT, applied to finite-length discrete-time signals [23]. Given a sequence x [ n ] , where n = 0 , 1 , , N 1 , the DFT transforms it into a sequence X [ k ] of the same length, representing frequency components. The DFT is defined as [23]:
X [ k ] = n = 0 N 1 x [ n ] · e j 2 π N k n , for k = 0 , 1 , , N 1
where X [ k ] represents the complex amplitude of the frequency component at index k, and j = 1 is the imaginary unit.
DFT is commonly implemented via the Fast Fourier Transform (FFT), an efficient algorithm for computing the frequency content of discrete-time signals. However, the FFT achieves peak performance only when the input size is a power of two or composed of small prime factors. For data lengths involving large primes, the FFT becomes inefficient due to its dependency on favorable factorization of the input length [23]. In contrast, the Chirp Z-Transform (CZT) offers more flexibility and efficiency in such cases, since its algorithmic structure does not rely on the factorization of the signal length [24].
Moreover, while the FFT computes the frequency response at uniformly spaced points on the unit circle in the complex plane, the CZT allows evaluation along arbitrary contours. This makes it ideal for focused spectral analysis where only a specific frequency band is of interest, and where increased frequency resolution is required without increasing the time-domain sample size [25]. The CZT can thus perform a zoomed-in frequency analysis more efficiently than zero-padding and interpolating an FFT.
CZT of a discrete-time signal x n is defined as the evaluation of its Z-transform at a sequence of complex points z k . The general form of the CZT is given by [24]:
X k = n = 0 N 1 x n z k n , k = 0 , 1 , , M 1
where x n is a signal of length N, and z k C are the points in the complex plane (Z-plane) at which the transform is evaluated. These points are typically chosen to lie along a spiral contour defined by z k = A W k , where A is the starting point and W is the ratio between successive points.
The Discrete Fourier Transform (DFT) is a special case of the CZT, obtained when the z k are uniformly spaced around the unit circle [24]:
z k = exp j 2 π N k , k = 0 , 1 , , N 1

5.1.2. Windowing

DFT assumes that the input finite-duration signal represents one period of a periodic signal [23]. This means that the signal is conceptually extended periodically, repeating every N samples. If the values at the start and end of the segment do not match in amplitude and slope, this creates a discontinuity in the periodic extension. Such discontinuities introduce high-frequency artifacts that spread energy across multiple frequency bins, a phenomenon known as spectral leakage [26]. Spectral leakage obscures the true frequency content of the signal and degrades the spectral estimate.
To reduce spectral leakage, window functions (e.g., Hanning or Hamming windows) are commonly applied before computing the DFT. These functions taper the signal smoothly to zero at the segment boundaries, thereby minimizing the discontinuity and improving the frequency representation [23]. Figure 5 demonstrates how a Hanning window mitigates spectral leakage introduced by discontinuity. A 10 Hz sine wave with a sampling rate of 100 Hz was used in this example.

5.1.3. Generalized Binary Noise

A generalized binary noise (GBN) signal was used in this work for filters’ performance evaluation and additionally for tuning filters’ parameters.
A step signal contains predominantly low frequencies [27]. A pseudo-random binary sequence (PRBS) contains the entire frequency range with signal energy equally distributed across all frequencies [27]. PRBS randomly switches with 0.5 probability between low and high levels of the same amplitude [27,28]; in other words, it comprises step signals with randomly chosen durations. Using GBN introduced by Tulleken [28] with the method presented in [27] allows for the excitation of frequencies in the given range. Similar to PRBS, GBN also randomly switches between low and high levels with the same amplitude [27,28]. Unlike PRBS, which switches randomly between levels with 0.5 probability, the probability of switching for GBN can vary [27,28]. The calculation of the non-switching probability P n s for the given frequency range and switching time is presented in Equation (34) from [27]. If P n s is equal to 1, then GBN behaves like a step signal, and if P n s is equal to 0.5, then GBN behaves like PRBS [27,28]. The upper-frequency limit for GBN can be defined by the Nyquist frequency, i.e., π / T s w [27,28]. To increase the upper-frequency limit, it is important to reduce switching time. In this work, it is achieved by using small amplitudes and moving the robot with high velocity and acceleration. For the GBN implementation on UR5e robot, the following settings were chosen: tool speed: 3 m / s , tool acceleration: 15 m / s 2 .
P n s = 1 1 + tan ω L T s w 2 tan ω H T s w 2
where P n s is the non-switching probability, ω L and ω H are the lower and upper bounds of the frequency interval, and T s w is the switching time.
It is also worth noting that the frequency spectrum of GBN is not strictly confined to the interval ω L to ω H ; rather, most of the signal power is concentrated in that region [27,28].
GBN signal was used for tuning filters’ parameters. It was applied to roll and pitch axes with an amplitude of 3° for the frequency range of 0.1–25 rad/s, duration of 60 s, and empirically estimated T s w equal to 0.12 s (corresponding P n s value of 0.77).
GBN was also used as a test signal. It was applied to roll and pitch axes (separately and together) with an amplitude of 5° for the frequency range of 0.5–20 rad/s, duration of 30 s, and empirically estimated T s w equal to 0.15 s (corresponding P n s value of 0.58). This GBN test signal is shown in Figure 6. Compared to the GBN signal for tuning, the GBN signal for testing has a smaller frequency range, shorter duration, bigger amplitude, and bigger T s w .

5.1.4. Composite Frequency Response

For filters’ evaluation in the frequency domain, composite frequency response and coherence are used in this work. The composite frequency response and coherence are calculated using the Ockier method described in [9].
The frequency response of an LTI system describes how the system modifies the amplitude and phase of sinusoidal components of an input signal. Mathematically, it is defined as the Fourier transform of the system’s impulse response h ( t ) [29]:
H ( f ) = h ( t ) e j 2 π f t d t
In the discrete-time case, the frequency response is the Discrete-Time Fourier Transform (DTFT) of the impulse response [29]:
H ( e j ω ) = n = h [ n ] e j ω n
The magnitude | H ( f ) | describes how much each frequency is amplified or attenuated, and the angle H ( f ) describes the phase shift introduced at each frequency.
In practical cases, a system is often unknown and estimated based on input–ouput signals (so-called system identification). The frequency response can be estimated from input–output data using power spectral densities [9,30]:
H ^ ( f ) = S x y ( f ) S x x ( f )
where S x y ( f ) is the cross-spectral density (cross-spectrum) between x ( t ) and y ( t ) , and S x x ( f ) is the auto-spectral density (auto-spectrum) of x ( t ) .
The auto-spectral densities of the input and output signals are given by [9]:
S x x ( f k ) = 2 T X ( f k ) 2
S y y ( f k ) = 2 T Y ( f k ) 2
The cross-spectral density between input and output is defined as [9]:
S x y ( f k ) = 2 T X * ( f k ) Y ( f k )
where X ( f k ) , Y ( f k ) are the Fourier transforms of x ( t ) and y ( t ) evaluated at frequency f k , T is the duration of the time window, and * denotes the complex conjugate.
The magnitude-squared coherence function γ x y 2 ( f ) measures the linear correlation between input and output at each frequency and is defined as [9,31]:
γ x y 2 ( f ) = | S x y ( f ) | 2 S x x ( f ) S y y ( f )
The coherence ranges from zero (no correlation) to one (perfect linear relationship at that frequency) [31].
The composite frequency response extends the classical concept by combining multiple estimates obtained from windowed data segments, thereby reducing random variability and improving reliability in practical system identification [9]. The data is first segmented, and a window function (e.g., Hanning or Hamming) is applied to each segment before estimating its frequency response. Averaging these individual windowed-segment (hereafter referred to as ’window’) responses reduces random error and increases the resolution of the amplitude and phase of the frequency response [9,31].
However, segmentation increases the fundamental frequency, i.e., the lowest frequency detectable by DFT, and decreases the frequency resolution of DFT. In conclusion, bigger windows are better for the evaluation of lower frequencies, and smaller windows are better for the evaluation of high frequencies. Thus, using different window sizes and consequently number of windows makes it possible to obtain a more accurate frequency response and coherence. Ockier shows the empirically determined frequency ranges (normal and high resolution) that can be reliably identified for a given number of windows and fundamental frequency. For normal resolution (used in this work) [9]:
f 1 n d 10 2 + 1 < f k < f 1 n d 10 2 + 1 + 14 n d 10
where f 1 is the fundamental frequency, and n d is the number of windows into which the data record is divided.
The process of calculating a composite frequency response and coherence with the Ockier method for each number of segments (windows) involves the following steps [9,31,32]:
  • Segmenting the input and output signals into the segments that have 50% overlap,
  • Windowing each segment with Hanning windows to reduce spectral leakage,
  • Applying DFT, more specifically Chirp-Z transform, on each window,
  • Calculation of auto- and cross spectral densities across the windows,
  • Calculation of the frequency response and coherence based on the auto- and cross-spectral densities using Multiple Input Single Output (MISO) conditioning,
After calculating the frequency responses and coherences for each number of windows using MISO conditioning, they are weighted at each frequency point using weights based on Equation (40), and the composite frequency response and coherence are then calculated [9].

5.1.5. Metrics

As a metric for frequency domain evaluation, the RMSE of the composite frequency response magnitude (RMSEM) is calculated with 0 dB being the reference magnitude. Moreover, the RMSE of the composite coherence (RMSEC) is calculated where a coherence of one represents the desired value, indicating a linear behaviour between the UR5e orientation and the estimated orientation. Additionally, based on the composite frequency response phase, the averaged equivalent time delay (AETD) is calculated according to:
A E T D = 1 n i = 0 n γ i ω i
where γ i is the phase of frequency response corresponding to the angular frequency ω i , n is the number of frequencies in the frequency response.

5.1.6. Evaluation Example

As an example for evaluation, a second-order transfer function with a known frequency response is considered. In the Laplace domain, the transfer function of the system can be written as [33]:
H ( s ) = ω n 2 s 2 + 2 ζ ω n s + ω n 2
where ω n is the natural frequency of the system in radians per second, and ζ is the damping ratio.
For this example, ω n = 10 rad / s and ζ = 0.4 are selected. The system is evaluated over the frequency range from 0.1 to 100 rad/s. A sine chirp signal with logarithmic frequency progression in the same range (0.1 to 100 rad/s) is applied as input (Figure 7a), and the known frequency response (model-based) is compared with the composite frequency response identified from the input and output signals using the Ockier method. As shown in Figure 7b, the two responses are nearly identical.
Subsequently, the evaluation frequency range (0.1 to 100 rad/s) is retained, while the input chirp signal frequency range is reduced to 0.1 to 50 rad/s (Figure 8a). As expected, the composite frequency response (Figure 8b) is accurately identified only within this narrower excitation range.
Figure 9 shows a comparison of the composite coherence obtained from the chirp input covering the full frequency range of interest versus the chirp input applied over a shorter frequency range. As expected, the composite coherence of the full-range chirp remains close to one across the entire frequency range of interest, whereas the coherence of the shorter-range chirp drops close to zero beyond its excitation range.

5.2. Results

The frequency domain evaluation was done in the range of 0.5–30 rad/s. The lower frequency limit was chosen based on the longest window duration, while the upper limit was set slightly above the highest frequency (20 rad/s) of the GBN test signal because the frequency spectrum of GBN is not strictly within interval ω L to ω H from Equation (34).
The GBN test signal was applied to the roll and pitch axes separately and simultaneously. The GBN test signal applied separately to the roll and pitch axes is shown in the time domain in Figure 10a,b.
Composite frequency response (magnitude and phase) and composite coherence for GBN test signal applied separately to the roll and pitch axes is shown in Figure 11. Figure 12 shows the composite frequency response and composite coherence for the GBN test signal applied simultaneously to the roll and pitch axes.
Table 3 shows the RMSE of the composite frequency response magnitude, the RMSE of the composite coherence and the averaged equivalent time delay. In the table, the lowest value for a given test signal and metric is marked in green, and the biggest is in red. For the GBN test signal applied simultaneously to the roll and pitch axes, the reported metrics correspond to the sum of the individual metrics for roll and pitch.
Based on the RMSEM (Table 3), MF achieves the best results across all three test signals. CF delivers a performance similar to MF, with the largest difference in RMSEM being only 0.04 dB. RMSEC is close to zero for all three filters, and the differences between them are negligible (the largest difference is only 0.002). IKF shows the worst performance in terms of RMSEM. However, it achieves the best AETD across all three test signals (with the largest difference being 10 ms).

6. Conclusions and Discussion

In this work, three IMU orientation estimation algorithms: IKF, CF, and MF, were evaluated in the time domain using pose sequence test signals and in the frequency domain using GBN signals. For big-amplitude, slowly changing pose sequence signals (stationary and low-dynamics responses as observed in the time domain), MF and CF demonstrated the best performance. Similarly, for small amplitude, fast-changing signals such as GBN (dynamic responses as observed in the frequency domain), MF and CF again demonstrated the best performance with very similar results. IKF overall performed the worst in both the time and frequency domains, possibly due to overfitting during tuning. Despite this, IKF achieved the lowest AETD.
In this work, the orientation of a robotic arm was utilized as the reference orientation. The evaluation was conducted in both the time and frequency domains, with specific test signals and metrics defined for each. This testing approach has the potential to be extended beyond orientation estimation to include position estimation or both (pose) and may also be valuable for evaluating other sensors and fusion algorithms.

Author Contributions

Conceptualization, S.G.; methodology, R.S.; software, R.S. and S.G.; validation, R.S. and S.G.; formal analysis, R.S.; investigation, R.S.; resources, R.S.; data curation, R.S.; writing—original draft preparation, R.S.; writing—review and editing, S.G.; visualization, R.S. and S.G.; supervision, S.G.; project administration, S.G.; funding acquisition, S.G. All authors have read and agreed to the published version of the manuscript.

Funding

This work is part of the CarLa project (funding code: 03FHP180A; funding programme: “FH-Personal”) funded by the German Federal Ministry of Research, Technology and Space (BMFTR) and the joint project TIDA5G (funding code: 19OI23014C; funding programme: “InnoNT—innovative Netztechnologien”) funded by the German Federal Ministry of Transport (BMV).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data used for filters’ evaluation and tuning are available on request from the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

Abbreviations

The following abbreviations are used in this manuscript:
AETDAveraged Equivalent Time Delay
CANController Area Network
CFComplementary Filter
CZTChirp Z-Transform
DFTDiscrete Fourier Transform
DLRGerman Aerospace Center (Deutsches Zentrum für Luft- und Raumfahrt)
DoFDegrees of Freedom
DTFTDiscrete-Time Fourier Transform
EKFExtended Kalman Filter
ESKFError State Kalman Filter
FFTFast Fourier Transform
GBNGeneralized Binary Noise
IKFIndirect Kalman Filter
IMUInertial Measurement Unit
LTILinear Time-Invariant
MaxAEMaximum Absolute Error
MFMadgwick Filter
MISOMultiple Input Single Output
NEDNorth-East-Down
RMSERoot Mean Squared Error
RMSECRMSE of composite Coherence
RMSEMRMSE of composite frequency response Magnitude
RTDEReal-Time Data Exchange
TCPTool Center Point
TCP/IPTransmission Control Protocol / Internet Protocol

References

  1. Sultan, R.; Greiser, S.; Brix, N. Time and Frequency Domain Analysis of IMU-based Orientation Estimation Algorithms with Comparison to Robotic Arm Orientation as Reference. In Proceedings of the 10th International Conference on Sensors and Electronic Instrumentation Advances (SEIA’ 2024), Ibiza, Spain, 25–27 September 2024; IFSA Publishing, S.L.: Barcelona, Spain, 2024; pp. 87–93. [Google Scholar]
  2. Madgwick, S.O.H.; Harrison, A.J.L.; Vaidyanathan, A. Estimation of IMU and MARG orientation using a gradient descent algorithm. In Proceedings of the 2011 IEEE International Conference on Rehabilitation Robotics, Zurich, Switzerland, 29 June–1 July 2011; Volume 2011, p. 5975346. [Google Scholar] [CrossRef]
  3. Roetenberg, D.; Luinge, H.J.; Baten, C.T.M.; Veltink, P.H. Compensation of magnetic disturbances improves inertial and magnetic sensing of human body segment orientation. IEEE Trans. Neural Syst. Rehabil. Eng. 2005, 13, 395–405. [Google Scholar] [CrossRef] [PubMed]
  4. Valenti, R.G.; Dryanovski, I.; Xiao, J. Keeping a Good Attitude: A Quaternion-Based Orientation Filter for IMUs and MARGs. Sensors 2015, 15, 19302–19330. [Google Scholar] [CrossRef] [PubMed]
  5. Shuster, M.D. A Survey of Attitude Representations. J. Astronaut. Sci. 1993, 41, 439–517. [Google Scholar]
  6. Jia, Y.B. Foundations of Robotics and Computer Vision (COMS 4770/5770). Available online: https://faculty.sites.iastate.edu/jia/foundations-robotics-and-computer-vision-coms-47705770 (accessed on 14 April 2025).
  7. Madyastha, V.; Ravindra, V.; Mallikarjunan, S.; Goyal, A. Extended Kalman Filter vs. Error State Kalman Filter for Aircraft Attitude Estimation. In Proceedings of the AIAA Guidance, Navigation, and Control Conference, Reston, VA, USA, 8–11 August 2011. [Google Scholar] [CrossRef]
  8. Do, H.V.; Song, J.w. Error-State Kalman Filtering with Linearized State Constraints. Aerospace 2025, 12, 243. [Google Scholar] [CrossRef]
  9. Seher-Weiss, S. FitlabGui—A MATLAB Tool for Flight Data Analysis and Parameter Estimation, Version 2.5. 2015. Available online: https://www.researchgate.net/publication/303708111_FitlabGui_-_A_MATLAB_Tool_for_Flight_Data_Analysis_and_Parameter_Estimation_-_Version_25 (accessed on 4 April 2025).
  10. Sorriento, A.; Porfido, M.B.; Mazzoleni, S.; Calvosa, G.; Tenucci, M.; Ciuti, G.; Dario, P. Optical and Electromagnetic Tracking Systems for Biomedical Applications: A Critical Review on Potentialities and Limitations. IEEE Rev. Biomed. Eng. 2020, 13, 212–232. [Google Scholar] [CrossRef] [PubMed]
  11. Cavallo, A.; Cirillo, A.; Cirillo, P.; De Maria, G.; Falco, P.; Natale, C.; Pirozzi, S. Experimental Comparison of Sensor Fusion Algorithms for Attitude Estimation. In Proceedings of the 19th IFAC World Congress, Cape Town, South Africa, 24–29 August 2014. [Google Scholar]
  12. El-Gohary, M.; McNames, J. Human Joint Angle Estimation with Inertial Sensors and Validation with A Robot Arm. IEEE Trans. Biomed. Eng. 2015, 62, 1759–1767. [Google Scholar] [CrossRef] [PubMed]
  13. Ricci, L.; Taffoni, F.; Formica, D. On the Orientation Error of IMU: Investigating Static and Dynamic Accuracy Targeting Human Motion. PLoS ONE 2016, 11, e0161940. [Google Scholar] [CrossRef] [PubMed]
  14. Hislop, J.; Isaksson, M.; McCormick, J.; Hensman, C. Validation of 3-Space Wireless Inertial Measurement Units Using an Industrial Robot. Sensors 2021, 21, 6858. [Google Scholar] [CrossRef] [PubMed]
  15. Kuti, J.; Piricz, T.; Galambos, P. A Robust Method for Validating Orientation Sensors Using a Robot Arm as a High-Precision Reference. Sensors 2024, 24, 8179. [Google Scholar] [CrossRef] [PubMed]
  16. MathWorks. MATLAB ImuFilter System Object. 2024. Available online: https://de.mathworks.com/help/nav/ref/imufilter-system-object.html (accessed on 14 April 2025).
  17. MathWorks. MATLAB ComplementaryFilter System Object. 2024. Available online: https://de.mathworks.com/help/fusion/ref/complementaryfilter-system-object.html (accessed on 14 April 2025).
  18. Mahony, R.; Hamel, T.; Pflimlin, J.M. Nonlinear complementary filters on the special orthogonal group. IEEE Trans. Autom. Control 2008, 53, 1203–1218. [Google Scholar] [CrossRef]
  19. ISO 9283; Manipulating Industrial Robots—Performance Criteria and Related Test Methods. International Organization for Standardization: Geneva, Switzerland, 1998.
  20. Universal Robots A/S. UR5e E-Series Datasheet. 2024. Available online: https://www.universal-robots.com/media/1807465/ur5e_e-series_datasheets_web.pdf (accessed on 28 July 2025).
  21. Universal Robots A/S. Real-Time Data Exchange (RTDE) Guide. 2024. Available online: https://docs.universal-robots.com/tutorials/communication-protocol-tutorials/rtde-guide.html (accessed on 28 July 2025).
  22. Bosch Rexroth AG. Inertial Measurement Unit MM7.10: Technical Customer Documentation; Bosch Rexroth AG: Lohr a. Main, Germany, 2022. [Google Scholar]
  23. Oppenheim, A.V.; Schafer, R.W. Discrete-Time Signal Processing, 3rd ed.; Prentice Hall: Hoboken, NJ, USA, 2013; p. 1056. [Google Scholar]
  24. Rabiner, L.R.; Schafer, R.W.; Rader, C.M. The chirp z-transform algorithm and its application. Bell Syst. Tech. J. 1969, 48, 1249–1292. [Google Scholar] [CrossRef]
  25. Smith, S.W. The Scientist and Engineer’s Guide to Digital Signal Processing; California Technical Publishing: San Diego, CA, USA, 1997. [Google Scholar]
  26. Mitra, S.K. Digital Signal Processing: A Computer-Based Approach, 4th ed.; McGraw-Hill: New York, NY, USA, 2010. [Google Scholar]
  27. Chen, J.K.; Yu, C.C. Optimal input design using generalized binary sequence. Automatica 1997, 33, 2081–2084. [Google Scholar] [CrossRef]
  28. Tulleken, H.J. Generalized binary noise test-signal concept for improved identification-experiment design. Automatica 1990, 26, 37–49. [Google Scholar] [CrossRef]
  29. Oppenheim, A.V.; Willsky, A.S.; Nawab, S.H. Signals and Systems, 2nd ed.; Prentice Hall: Hoboken, NJ, USA, 1997. [Google Scholar]
  30. Harris, F.J. On the use of windows for harmonic analysis with the discrete Fourier transform. Proc. IEEE 1978, 66, 51–83. [Google Scholar] [CrossRef]
  31. Tischler, M.B.; Remple, R.K. Aircraft and Rotorcraft System Identification, 2nd ed.; American Institute of Aeronautics and Astronautics, Inc.: Washington, DC, USA, 2012. [Google Scholar] [CrossRef]
  32. Sridhar, J.K.; Wulff, G. Application of Multiple-Input/Single-Output Analysis Procedures to Flight Test Data. J. Guid. Control. Dyn. 1991, 14, 645–651. [Google Scholar] [CrossRef]
  33. Haidekker, M.A. (Ed.) Linear Feedback Controls; Elsevier: Oxford, UK, 2013. [Google Scholar]
Figure 1. Experimental setup.
Figure 1. Experimental setup.
Sensors 25 05161 g001
Figure 2. Reference vs. estimated orientation, pose sequence test signal 1. (a) IKF. (b) CF. (c) MF.
Figure 2. Reference vs. estimated orientation, pose sequence test signal 1. (a) IKF. (b) CF. (c) MF.
Sensors 25 05161 g002
Figure 3. Reference vs. estimated orientation, pose sequence test signal 2. (a) IKF. (b) CF. (c) MF.
Figure 3. Reference vs. estimated orientation, pose sequence test signal 2. (a) IKF. (b) CF. (c) MF.
Sensors 25 05161 g003
Figure 4. Reference vs. estimated orientation, pose sequence test signal 3. (a) IKF. (b) CF. (c) MF.
Figure 4. Reference vs. estimated orientation, pose sequence test signal 3. (a) IKF. (b) CF. (c) MF.
Sensors 25 05161 g004
Figure 5. Effect of windowing on spectral leakage.
Figure 5. Effect of windowing on spectral leakage.
Sensors 25 05161 g005
Figure 6. GBN used for the evaluation in the frequency domain, frequency range: 0.5–20 rad/s, duration: 30 s, T s w : 0.15 s, corresponding P n s : 0.58.
Figure 6. GBN used for the evaluation in the frequency domain, frequency range: 0.5–20 rad/s, duration: 30 s, T s w : 0.15 s, corresponding P n s : 0.58.
Sensors 25 05161 g006
Figure 7. Response of a second-order system ( ω n = 10 rad / s ,   ζ = 0.4 ) to a chirp input applied across the full frequency range of interest (0.1 to 100 rad/s). (a) Time domain. (b) Frequency domain.
Figure 7. Response of a second-order system ( ω n = 10 rad / s ,   ζ = 0.4 ) to a chirp input applied across the full frequency range of interest (0.1 to 100 rad/s). (a) Time domain. (b) Frequency domain.
Sensors 25 05161 g007
Figure 8. Response of a second-order system ( ω n = 10 rad / s ,   ζ = 0.4 ) to a chirp input applied across the shorter frequency range (0.1 to 50 rad/s) than the frequency range of interest (0.1 to 100 rad/s). (a) Time domain. (b) Frequency domain.
Figure 8. Response of a second-order system ( ω n = 10 rad / s ,   ζ = 0.4 ) to a chirp input applied across the shorter frequency range (0.1 to 50 rad/s) than the frequency range of interest (0.1 to 100 rad/s). (a) Time domain. (b) Frequency domain.
Sensors 25 05161 g008
Figure 9. Comparison of the composite coherence obtained from a chirp input covering the full frequency range of interest (0.1 to 100 rad/s) versus a chirp input applied over a shorter frequency range (0.1 to 50 rad/s).
Figure 9. Comparison of the composite coherence obtained from a chirp input covering the full frequency range of interest (0.1 to 100 rad/s) versus a chirp input applied over a shorter frequency range (0.1 to 50 rad/s).
Sensors 25 05161 g009
Figure 10. GBN test signal in the time domain (not the full duration of the signal is shown). (a) Applied to roll. (b) Applied to pitch.
Figure 10. GBN test signal in the time domain (not the full duration of the signal is shown). (a) Applied to roll. (b) Applied to pitch.
Sensors 25 05161 g010
Figure 11. Composite frequency response and coherence for roll and pitch (GBN test signal is applied separately). (a) Roll. (b) Pitch.
Figure 11. Composite frequency response and coherence for roll and pitch (GBN test signal is applied separately). (a) Roll. (b) Pitch.
Sensors 25 05161 g011
Figure 12. Composite frequency response and coherence for roll and pitch (GBN test signal is applied simultaneously for both). (a) Roll. (b) Pitch.
Figure 12. Composite frequency response and coherence for roll and pitch (GBN test signal is applied simultaneously for both). (a) Roll. (b) Pitch.
Sensors 25 05161 g012
Table 1. Characteristics of Bosch MM7.10 IMU.
Table 1. Characteristics of Bosch MM7.10 IMU.
ParameterGyroscopeAccelerometer
Nominal measurement range±163°/s ±41 m/s2
Cut-off frequency (−3 dB)15 Hz15 Hz
Sensitivity error±2.0%±2.0%
Non-linearity±0.5°/s±0.4 m/s2
Offset (bias)±1.0°/s±0.5 m/s2
Cross axis sensitivity±1.5%±1.5%
Output noise0.2°/s RMS0.04 m/s2 RMS
Resolution (absolute)0.05°/s0.022 m/s2
Table 2. Evaluation in the time domain.
Table 2. Evaluation in the time domain.
Pose SequenceFilter TypeRMSE|MaxAE Roll (°)RMSE|MaxAE Pitch (°)RMSE|MaxAE Sum (°)
Test Signal 1IKF2.07|5.620.99|2.413.06|8.03
CF0.68|1.750.56|1.341.24|3.09
MF0.46|1.540.40|1.050.86|2.59
Test Signal 2IKF2.14|6.221.08|5.583.22|11.80
CF1.88|4.601.17|3.233.05|7.83
MF1.79|4.841.18|3.862.97| 8.70
Test Signal 3IKF0.59|1.450.58|0.941.17|2.39
CF0.53| 1.110.54|0.861.07|1.97
MF0.55|1.230.57|0.971.12 |2.20
The lowest value for a given test signal and metric is marked in green, and the highest is marked in red.
Table 3. RMSE of the composite frequency response magnitude (RMSEM), RMSE of the composite coherence (RMSEC), and averaged equivalent time delay (AETD).
Table 3. RMSE of the composite frequency response magnitude (RMSEM), RMSE of the composite coherence (RMSEC), and averaged equivalent time delay (AETD).
GBN SignalFilter TypeRMSEM (dB)RMSECAETD (ms)
Roll onlyIKF0.700.0052
CF0.140.0045
MF0.140.0037
Pitch onlyIKF0.160.0031
CF0.070.0056
MF0.060.0034
Roll and pitchIKF0.880.0083
CF0.280.0077
MF0.240.00613
The lowest value for a given test signal and metric is marked in green, and the highest is marked in red. For the GBN test signal applied simultaneously to the roll and pitch axes, the reported metrics correspond to the sum of the individual metrics for roll and pitch.
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

Sultan, R.; Greiser, S. Time and Frequency Domain Analysis of IMU-Based Orientation Estimation Algorithms with Comparison to Robotic Arm Orientation as Reference. Sensors 2025, 25, 5161. https://doi.org/10.3390/s25165161

AMA Style

Sultan R, Greiser S. Time and Frequency Domain Analysis of IMU-Based Orientation Estimation Algorithms with Comparison to Robotic Arm Orientation as Reference. Sensors. 2025; 25(16):5161. https://doi.org/10.3390/s25165161

Chicago/Turabian Style

Sultan, Ruslan, and Steffen Greiser. 2025. "Time and Frequency Domain Analysis of IMU-Based Orientation Estimation Algorithms with Comparison to Robotic Arm Orientation as Reference" Sensors 25, no. 16: 5161. https://doi.org/10.3390/s25165161

APA Style

Sultan, R., & Greiser, S. (2025). Time and Frequency Domain Analysis of IMU-Based Orientation Estimation Algorithms with Comparison to Robotic Arm Orientation as Reference. Sensors, 25(16), 5161. https://doi.org/10.3390/s25165161

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