Attitude Estimation Using a Quaternion-Based Kalman Filter With Adaptive and Norm-Based Estimation of External Acceleration
This project aimed to estimate the attitude of a vehicle using measurements from onboard sensors. The sensors used were inertial sensors (gyroscope and accelerometer) and a magnetometer. The project utilized quaternion algebra and an indirect Kalman filter to estimate the vehicle's orientation. To estimate external acceleration, two methods were employed: norm-based estimation [1] and adaptive estimation [2]. The filter was tested using simulated and real data to validate its effectiveness.
Prerequisite • Use • Scripts • Functions Library • Presentation • Indirect Kalman Filter
- Y. S. Suh, "Orientation Estimation Using a Quaternion-Based Indirect Kalman Filter With Adaptive Estimation of External Acceleration," in IEEE Transactions on Instrumentation and Measurement, vol. 59, no. 12, pp. 3296-3305, Dec. 2010, doi:10.1109/TIM.2010.2047157
- A. Nez, L. Fradet, F. Marin, T. Monnet and P. Lacouture, "Identification of Noise Covariance Matrices to Improve Orientation Estimation by Kalman Filter." Sensors 2018, 18, 3490, doi:10.3390/s18103490
- N. Trawny and S.I. Roumeliotis, "Indirect Kalman filter for 3D attitude estimation." In Technical Report; Department of Computer Science and Engineering, University of Minnesota: Minneapolis, MN, USA, 2005, Google Scholar
- A. M. Sabatini, "Quaternion-based extended Kalman filter for determining orientation by inertial and magnetic sensing," in IEEE Transactions on Biomedical Engineering, vol. 53, no. 7, pp. 1346-1356, July 2006, doi:10.1109/TBME.2006.875664
- R. Schneider and C. Georgakis, "How To NOT Make the Extended Kalman Filter Fail". Industrial & Engineering Chemistry Research 2013 52 (9), 3354-3362, doi:10.1021/ie300415d
- Add this repository to your MATLAB path (replace /path/to/this/repository with the actual path to the directory where the repository is located on your computer):
addpath('/path/to/this/repository') - Add your flight data to the data folder
- If desired, edit the scripts in the scripts folder according to your needs as detailed here
- Run the
main.mscript - If the 'saving_flag' is turned on in the
plot_results.mscript, figures will be saved in the img folder
This repository contains four folders:
- data: Contains real data acquired from sensors and the magnetic field parameters used.
- functions: Contains a collection of low-level, useful MATLAB functions utilized by the scripts in the 'scripts' folder.
- img: Contains any figures saved if the 'saving_flag' is turned on.
- scripts: Contains MATLAB scripts that use the functions in the 'functions' folder.
The data folder should contain flight data collected from real sensors (gyroscope, accelerometer, magnetometer, and inclinometer), as well as magnetic field parameters. The magnetic field parameters can be generated using the most recent World Magnetic Model (WMM) from 2019-2024, which can be accessed through the following link: https://www.ngdc.noaa.gov/geomag/calculators/magcalc.shtml.
The images presented in the presentation were generated using magnetic field parameters calculated for a specific date (February 13th, 2020) and location (43°52'52"N, 10°14'6"E, Viareggio, IT) where real data was collected.
The img folder contains the images generated and saved by the plot_results.m script.
The scripts folder contains all the scripts used. Possible editing, such as switching between synthetic and real data, should be done by modifying the code itself. All scripts have extensive comments in the code.
Notation used:
prev = k - 1(ork, respectively)next = k(ork + 1, respectively)
e.g., q_next_prev denotes q(k|k-1) (or q(k+1|k), respectively)
-
generate_synthetic_data.m
This script generates synthetic data.- Please select one of the following rate_mode:
-
null: null rate -
const: constant rate -
roll: zero(0-50 s) - phi=phi+90° - zero (150-200 s) -
pitch: zero(0-50 s) - theta=theta+45° - zero (150-200 s) -
yaw: zero(0-50 s) - psi=psi+90° - zero (150-200 s) -
mult_const: miscellaneous (multiple) constant rates -
mult_ramp: miscellaneous (multiple), fast, ramp-like rates
-
- Choose either
ONorOFF(case insensitive, by the way):- noise_gyro: If
ON, it adds noise to gyroscope measurements - noise_acc: If
ON, it adds noise to accelerometer measurements - noise_mag: If
ON, it adds noise to magnetometer measurements - bias_gyro: If
ON, it adds bias to gyroscope measurements - bias_acc: If
ON, it adds bias to accelerometer measurements - ext_acc: If
ON, it creates 3 external accelerations:-
$[10 m/s², 5 m/s², 20 m/s²]^T$ from$80 s$ to$81 s$ -
$[0 m/s², -7 m/s², 0 m/s²]^T$ from$120 s$ to$122 s$ -
$[-4 m/s², -3 m/s², 8 m/s²]^T$ from$140 s$ to$140.5 s$
-
- noise_gyro: If
- Please select one of the following rate_mode:
-
import_real_data.m
This script loads real data from the data folder (the specific folder to be used is determined within the code.).- Please select one of the following interpolation modes:
-
1: interpolates samples (using Matlab functioninterp1(nearest)) -
2: linearly interpolates samples (usinglin_interpolate, located in the functions folder); it is a time-consuming task -
3: loads previously interpolated data otherwise do nothing
-
Make sure to adjust the paths according to your real data folder location.
- Please select one of the following interpolation modes:
-
kalmanCorrect_acc.m
This script adjusts the projected estimate by an actual accelerometer measurement at that time. -
kalmanCorrect_mag.m
This script adjusts the projected estimate by an actual magnetometer measurement at that time. -
kalmanPredict.m
This script projects the current state estimate ahead in time by two actual gyroscope measurements: at that time and the previous one. -
main.m
This is the main script that should be executed on Matlab.- Please select one of the following sensor_data types:
-
synthetic: Computer-generated sequence of angular velocity, acceleration, and magnetic field. Seegenerate_synthetic_data.mfor further details. -
real: Load sequence of angular velocity, acceleration, magnetic field, and attitude measured by real sensors (gyroscope, accelerometer, magnetometer, and inclinometer, respectively). Seeimport_real_data.mfor further details.
-
- Please select one of the following sensor_data types:
-
plot_results.m
This script has the capability to generate and, if desired, save all figures in the desired format (.png, .pdf, etc.). Users can customize the settings by selecting from the following options:-
saving_flag: set this to1to save the generated plots in the desired format (specified inimage_extension), and set it to any other value to disable saving. -
title_flag: set this to1to enable adding titles to the generated plots, and set it to any other value to disable adding titles. -
plot_detected_ext_acc: set this to1to display detected external acceleration instant dots on the acceleration plot, and set it to any other value to disable displaying detected external acceleration instant dots. -
image_extension: specify the format for saving the images. This can include file types such as .png, .pdf, and so on. -
images_path: set this variable to the folder path where you want to save the generated images (e.g., '/Users/a_user_name/Documents/MATLAB/quaternion-kalman-filter/images'). Modify the path as needed. -
main_path: set this variable to the folder path where the source code is located (e.g., '/Users/a_user_name/Documents/MATLAB/quaternion-kalman-filter'). Modify the path as needed.
-
The functions folder includes a set of MATLAB functions library used by the scripts in the scripts folder. A list of the functions contained in the folder and their descriptions can be found below.
-
computeAccMode
function acceleration_mode = computeAccMode(lambda, mu)
[Eq. pre-34 Suh]
Computes Shu's acceleration mode, which is capable of detecting external acceleration (i.e., acceleration caused by forces other than gravity).- INPUT:
-
lambdaThe 3 eigenvalues of the matrix U, at times k, k-1, k-2 (3 x (M_2+1)) matrix -
muDefined after [Eq. 32 Suh] (3 x (M_2+1)) matrix
-
- OUTPUT:
-
acceleration_modePossible values:- '1' (i.e.,
Mode 1meaning 'No external acceleration Mode') - '2' (i.e.,
Mode 2meaning 'External acceleration Mode')
- '1' (i.e.,
-
- INPUT:
-
create_extAcc
function a_b = create_extAcc(a_b_OLD, t_i, ext_acc, length)
Generates constant external acceleration ext_acc from
t_itot_i + length, overwriting previous external accelerationa_b_OLD.- INPUT:
-
a_b_OLDPrevious external acceleration; it'll be overwritten (3 x N_samples) vector [m / s^2] -
t_iExt. acc. starting (initial) time scalar [s] -
ext_accExt. acc. constant value (3 x 1) vector [m / s^2] -
lengthExt. acc. duration scalar [s]
-
- OUTPUT:
-
a_bExternal acceleration a_b(t) (3 x N_samples) vector [m / s^2]
-
- INPUT:
-
estimateExtAccCov_Sab
function Q_hat_a_b = estimateExtAccCov_Sab(y_a)
[Eq. 37 Suh]
Implements the accelerometer norm-based adaptive algorithm by A. M. Sabatini [1] for estimating external acceleration covariance matrixQ__a_b.- INPUT:
-
y_aMeasured acceleration (3 x 1) vector [m/s^2]
-
- OUTPUT:
-
Q_hat_a_bEstimated external acceleration covariance (3 x 3) matrix [-]
-
- INPUT:
-
estimateExtAccCov_Suh
function [Q_hat_a_b, lambda, mu] = estimateExtAccCov_Suh(r_a, lambda, mu, H_a, P__next_prev, R_a)
[Eq. 34 - 35 Suh]
Implements the adaptive estimation algorithm by Y. S. Suh [2] for estimating external acceleration covariance matrixQ__a_b.- INPUT:
-
r_aResidual in the accelerometer measurement update (3 x M_1) vector [m / s^2] -
lambdaThreshold between first and second condition (3 x (M_2+1)) matrix -
muDefined after [Eq. 32 Suh] (3 x (M_2+1)) matrix -
H_aAccelerometer measurement matrix (3 x 9) matrix -
P__next_prevState covariance matrix (9 x 9) matrix -
R_aCovariance measurement matrix of the accelerometer (3 x 3) matrix
-
- OUTPUT:
-
Q_hat_a_bEstimated external acceleration covariance (3 x 3) matrix -
lambda(newly computed) lambda (3 x (M_2+1)) matrix -
mu(newly computed) mu (3 x (M_2+1)) matrix
-
- INPUT:
-
euler2quat
function q = euler2quat(angles)
[https://marc-b-reynolds.github.io/math/2017/04/18/TaitEuler.html#mjx-eqn%3Aeq%3Atait, Eq. 2 - 3 - 4 - 5]
Converts Euler angles to quaternion.- INPUT:
-
anglesEuler angles (angles = [roll; pitch; yaw]) (3 x 1) vector [rad]
-
- OUTPUT:
-
qQuaternion (q= [q0; q1; q2; q3], where the first element, q0, is the scalar part aka real part) (4 x 1) vector [-]
-
- INPUT:
-
euler2RotMat
function C = euler2RotMat(angles)
Converts Euler angles to rotation matrix (aka Direction Cosine Matrix, DCM). The Euler angles rotate the frame
n(navigation) to the frameb(body) according to the 'zyx' sequence.- INPUT:
-
anglesEuler angles (angles = [roll; pitch; yaw]) (3 x 1) vector [rad]
-
- OUTPUT:
-
CCoordinate transformation matrix from n to b (3 x 3) matrix [-] N.B.: That is,v_b = C * v_n. (_bor_nare the frames in which the vectorvcan be expressed, representing the body and navigation frames, respectively.)
-
- INPUT:
-
euler_angle_range_three_axis
function a = euler_angle_range_three_axis(angles)
Limits Euler angles range. For three-axis rotation, the angle ranges are [-pi, pi], [-pi/2, pi/2] and [-pi, pi]. For two-axis rotation, the angle ranges are [-pi, pi], [0, pi] and [-pi, pi].
- INPUT:
-
anglesEuler angles (3 x 1) vector [rad]
-
- OUTPUT:
-
aLimited Euler angles (3 x 1) vector [rad]
-
- INPUT:
-
lin_interpolate
function values_interpolated = lin_interpolate(T, values, N_samples, N_samples__theoretical)
[Eq. pre-34 Suh]
Linearly interpolates values.- INPUT:
-
TTime stamp array (1 xN_samples) vector [s] -
valuesArray with elements to be interpolated (1 xN_samples) vector [-] -
N_samplesNumber of samples of T and values scalar [-] -
N_samples__theoreticalTheoretical number of samples scalar [-]
-
- OUTPUT:
-
values_interpolatedN_samples__theoreticalinterpolated values (1 xN_samples__theoretical) array [-]
N.B.:N_samples <= N_samples__theoretical
-
- INPUT:
-
omega2quat
function q = omega2quat(omega)
Creates a pure imaginary quaternion (i.e., null scalar part, that is,
q(1) = 0) from the angular velocity omega.
Please note: the quaternion thus obtained is NOT a unitary quaternion.- INPUT:
-
omegaAngular velocity omega(k) (3 x 1) vector [rad / s]
-
- OUTPUT:
-
qQuaternion (q= [q0; q1; q2; q3], where the first element, q0, is the scalar part aka real part) (4 x 1) vector [-]
-
- INPUT:
-
Omega
function Omega_omega = Omega(omega)
[Eq. A12 ("A Kalman Filter for Nonlinear Attitude Estimation Using Time Variable Matrices and Quaternions" - Alvaro Deibe)]
Computes the Omega(omega) matrix.
N.B.: Omega(omega) appears in the product of a vector and a quaternion, and is used for example in the quaternion derivative.
(N.B.: [Eq. 64 Trawny] DOES NOT work properly anymore, probably sinceq(1) = q_0is the scalar part)- INPUT:
-
omega_nextAngular velocity omega(k) (3 x 1) vector [rad / s]
-
- OUTPUT:
-
Omega__omegaOmega matrix (3 x 3) matrix
-
- INPUT:
-
Omega_avg_omega
function Omega__avg_omega = Omega_avg_omega(omega_next, omega_prev, dt)
[Eq. 129 Trawny]
Computes the Omega(omega_avg) matrix.- INPUT:
-
omega_nextAngular velocity omega(k+1) (3 x 1) vector [rad / s] -
omega_prevAngular velocity omega(k) (3 x 1) vector [rad / s] -
dtTime step (dt= t(k+1) - t(k)) scalar [s]
-
- OUTPUT:
-
Omega__avg_omegaOmega(omega_avg) matrix (3 x 3) matrix [rad / s]
-
- INPUT:
-
Omega_dot_omega
function Omega__dot_omega = Omega_dot_omega(omega_next, omega_prev, dt)
[Eq. 126 Trawny]
Defines the derivative of the turn rate (omega_dot) and the associated matrix (Omega(omega_dot)), which - in the linear case - is constant.- INPUT:
-
omega_nextAngular velocity omega(k+1) (3 x 1) vector [rad / s] -
omega_prevAngular velocity omega(k) (3 x 1) vector [rad / s] -
dtTime step (dt= t(k+1) - t(k)) scalar [s]
-
- OUTPUT:
-
Omega__dot_omegaOmega matrix (3 x 3) matrix
-
- INPUT:
-
Phi_matrix
function Phi = Phi_matrix(y_g__next, Phi_mode)
[Eq. post-15 Suh] ('precise') OR [Eq. 16a Suh] ('approximated') OR [Eq. 187 Trawny] ('Trawny')
Computes the transition matrix Phi(t + dt, t).- INPUT:
-
y_g__nextMeasured angular velocity (i.e., gyro output) y_g(k) (3 x 1) vector [rad / s] -
Phi_modePossible values:-
precise: [Eq. post-15 Suh] -
approximated: [Eq. 16a Suh] -
Trawny: [Eq. 187 Trawny]
-
-
- OUTPUT:
-
PhiTransition matrix Phi(t + dt, t) (9 x 9) matrix
-
- INPUT:
-
Q_d_matrix
function Q_d = Q_d_matrix(y_g__next, Q_d_mode)
[Eq. post-15 Suh] ('precise') OR [Eq. 16b Suh] ('approximated') OR [Eq. 208 Trawny] ('Trawny')
Computes the Noise Covariance MatrixQ_d.- INPUT:
-
y_g__nextMeasured angular velocity (i.e., gyro output) y_g(k) (3 x 1) vector [rad / s] -
Q_d_modePossible values:- 'precise': [Eq. post-15 Suh]
- 'approximated': [Eq. 16a Suh]
-
- OUTPUT:
-
Q_dNoise Covariance Matrix Q_d(k) (9 x 9) matrix
-
- INPUT:
-
quat2euler
function r = quat2euler(q)
https://marc-b-reynolds.github.io/math/2017/04/18/TaitEuler.html#mjx-eqn%3Aeq%3Atait
Converts quaternion to Euler angles.- INPUT:
-
qQuaternion (q= [q0; q1; q2; q3], where the first element, q0, is the scalar part aka real part) (4 x 1) vector [-]
-
- OUTPUT:
-
rEuler angles (r= [roll; pitch; yaw]) (3 x 1) vector [rad]
-
- INPUT:
-
quat2RotMat
function C_from_q = quat2RotMat(q)
[Eq. 90 Trawny] [Eq. 1 Suh]
Computes the rotation matrix associated to the quaternionq.- INPUT:
-
qQuaternion (q= [q0; q1; q2; q3], where the first element, q0, is the scalar part aka real part) (4 x 1) vector [-]
-
- OUTPUT:
-
C_from_qCoordinate transformation matrix associated toq(3 x 3) matrix [-]
-
- INPUT:
-
quatConjugate
function q_conjugate = quatConjugate(q)
[Eq. 13 Trawny]
Takes the complex conjugate (that is, the inverse for a unit quaternion) of a given quaternion.
N.B.: The inverse rotation is described by the inverse or complex conjugate quaternion).- INPUT:
-
qQuaternion q(k) (q= [q0; q1; q2; q3], where the first element, q0, is the scalar part aka real part) (4 x 1) vector [-]
-
- OUTPUT:
-
q_conjugate(not unitary) Quaternion, conjugate ofq(4 x 1) vector [-]
-
- INPUT:
-
quatDerivative
function q_dot = quatDerivative(q, omega)
[Eq. 106 Trawny] OR [Eq. 2 Suh] (and [Eq. 4 Suh])
Computes the quaternion derivative.- INPUT:
-
qQuaternion (q= [q0; q1; q2; q3], where the first element, q0, is the scalar part aka real part) (4 x 1) vector [-] -
omegaAngular velocity omega(k) (3 x 1) vector [rad / s]
-
- OUTPUT:
-
q_do, Quaternion derivative ofq(4 x 1) vector [1 / s]
-
- INPUT:
-
quatFirstIntegration
function q_next = quatFirstIntegration(q_prev, omega_next, omega_prev, integration_mode)
[Eq. 18 Suh] ('Suh') OR [Eq. 131 Trawny] ('Trawny') OR [Eq. 8 Yuan] ('Yuan')
Computes the first-order quaternion integration. It makes the assumption of a linear evolution of omega during the integration interval dt.
N.B.: UseSuhforintegration_mode, notTrawny.- INPUT:
-
qQuaternion q(k) (q= [q0; q1; q2; q3], where the first element, q0, is the scalar part aka real part) (4 x 1) vector [-] -
omega_nextAngular velocity omega(k+1) (3 x 1) vector [rad/s] -
omega_prevAngular velocity omega(k) (3 x 1) vector [rad/s] -
integration_modeModality of integration:-
Suh, [Eq. 18 Suh] -
Trawny, [Eq. 131 Trawny] -
Yuan, [Eq. 8 Yuan]
-
-
- OUTPUT:
-
q_nextq(k+1); unit quaternion from integration ofq(4 x 1) vector [-]
-
- INPUT:
-
quatInverse
function q_inverse = quatInverse(q)
[Eq. 13 Trawny]
Takes the inverse of a given quaternion.
(N.B.: The inverse rotation is described by the inverse - or complex conjugate for unit quaternions quaternion)- INPUT:
-
qQuaternion q(k) (q= [q0; q1; q2; q3], where the first element, q0, is the scalar part aka real part) (4 x 1) vector [-]
-
- OUTPUT:
-
q_inverse(not unitary) Quaternion, the inverse ofq(4 x 1) vector [-]
-
- INPUT:
-
quatMultiplication
function q_times_p = quatMultiplication(q, p)
https://en.wikipedia.org/wiki/Quaternion#Hamilton_product
Multiplies the quaternionsqandp, thus obtaining their Hamilton product.
Please note: the quaternion product is NOT commutative!
(N.B.: [Eq. post-5 Trawny] is not used)- INPUT:
-
qQuaternion q(k) (q= [q0; q1; q2; q3], where the first element, q0, is the scalar part aka real part) (4 x 1) vector [-] -
pQuaternion p(k) (p= [p0; p1; p2; p3], p0 is the scalar) (4 x 1) vector [-]
-
- OUTPUT:
-
q_times_p(not unitary) Quaternion, the product of (in this order)qandp(4 x 1) vector [-]
-
- INPUT:
-
rand_range
function x = rand_range(xmin, xmax)
https://it.mathworks.com/matlabcentral/answers/66763-generate-random-numbers-in-range-from-0-8-to-4
Generates a value from the uniform distribution on the interval (xmin,xmax).- INPUT:
-
xminMinimum possible value scalar [-] -
xmaxMaximum possible value scalar [-]
-
- OUTPUT:
-
xPseudo-random number in (xmin,xmax) scalar [-]
-
- INPUT:
-
RotMat2euler
function r = RotMat2euler(C)
https://d3cw3dd2w32x2b.cloudfront.net/wp-content/uploads/2012/07/euler-angles1.pdf
Converts direction cosine matrix to Euler angles ('zyx' sequence).
N.B.: "We’ll follow the notational conventions of Shoemake’s “Euler Angle Conversion”, Graphics Gems IV, pp. 222-9".- INPUT:
-
CCoordinate transformation matrix (3 x 3) matrix [-]
-
- OUTPUT:
-
rEuler angles (r = [roll; pitch; yaw]) (3 x 1) vector [rad]
-
- INPUT:
-
RotMat2quat
function q = RotMat2quat(C)
[Eq. 98a - 98b - 99a - 99b Trawny]
Converts direction cosine matrix to quaternion.- INPUT:
-
CCoordinate transformation matrix (3 x 3) matrix [-]
-
- OUTPUT:
-
qQuaternion (q= [q0; q1; q2; q3], where the first element, q0, is the scalar part aka real part) (4 x 1) vector [-]
-
- INPUT:
-
rotX
function C_x = rotX(alpha)
Computes a basic rotation about the x-axis by an angle
alpha.- INPUT:
-
alphaangle scalar [rad]
-
- OUTPUT:
-
CCoordinate transformation matrix (3 x 3) matrix [-]
-
- INPUT:
-
rotY
function C_y = rotY(alpha)
Computes a basic rotation about the y-axis by an angle
alpha.- INPUT:
-
alphaangle scalar [rad]
-
- OUTPUT:
-
CCoordinate transformation matrix (3 x 3) matrix [-]
-
- INPUT:
-
rotZ
function C_y = rotY(alpha)
Computes a basic rotation about the z-axis by an angle
alpha.- INPUT:
-
alphaangle scalar [rad]
-
- OUTPUT:
-
CCoordinate transformation matrix (3 x 3) matrix [-]
-
- INPUT:
-
skewSymmetric
function skew_symmetric_matrix = skewSymmetric(p)
[Eq. post-9 Suh]
Computes the skew-symmetric matrix operator [px], formed fromp.- INPUT:
-
pPossible values:- angular velocity, (3 x 1) vector [rad / s]
- quaternion (only the vector part (aka imaginary part) of
pis considered), (4 x 1) vector [-]
-
- OUTPUT:
-
skew_symmetric_matrixSkew-symmetric matrix formed fromp(3 x 3) matrix [-]
-
- INPUT:
-
wrapTo90
function alpha_wrapped = wrapTo90(alpha)
https://it.mathworks.com/matlabcentral/answers/324032-how-to-wrap-angle-in-radians-to-pi-2-pi-2
Wraps the given angle to$[-90\degree, 90\degree]$ .- INPUT:
-
alphaAngle scalar [deg]
-
- OUTPUT:
-
alpha_wrappedWrapped angle scalar [deg]
-
- INPUT:
-
wrapToPi2
function alpha_wrapped = wrapToPi2(alpha)
https://it.mathworks.com/matlabcentral/answers/324032-how-to-wrap-angle-in-radians-to-pi-2-pi-2
Wraps the given angle to$[-\pi/2, \pi/2]$ .- INPUT:
-
alphaAngle scalar [rad]
-
- OUTPUT:
-
alpha_wrappedWrapped angle scalar [rad]
-
- INPUT:
The objective of the filter is to estimate the attitude quaternion
-
The propagation stage, where the filter produces a prediction of the attitude
$\hat{q}$ based on the previous estimate of the state$𝑥 = [q_e, b_g, b_a]^T$ , i.e.,$\hat{𝑥} = [\hat{q}_e, \hat{b}_g, \hat{b}_a]^T$ ,and the most recent gyroscope output$y_g$ . -
The update stage, which corrects the values predicted in the propagation stage. It consists of a two-step measurement update:
- An accelerometer measurement update, where the most recent accelerometer output
$y_a$ is used - A magnetometer measurement update, where the most recent magnetometer output
$y_m$ is used
- An accelerometer measurement update, where the most recent accelerometer output
