uf-ahrs rust no_std library for orientation estimation using gyroscope, accelerometer and magnetometer.
clip.mp4
no_stdand allocator-free for embedded systems.- IO and MCU agnostic.
- Implements
Mahony,MadgwickandVQFfilters. - Filters evaluated using
BROADdataset.
Library is under active development and testing, API might change at any time.
Add uf-ahrs to your Cargo.toml:
[dependencies]
uf-ahrs = "*" # replace * by the latest version of the crate.Or use the command line:
cargo add uf-ahrsHere is a simple example showing how to initialize and use Mahony, Madgwick, and VQF filters.
use core::time::Duration;
use nalgebra::Vector3;
use uf_ahrs::{Ahrs, Madgwick, MadgwickParams, Mahony, MahonyParams, Vqf, VqfParams};
fn main() {
let dt = Duration::from_secs_f32(1.0 / 100.0);
let mut mahony = Mahony::new(dt, MahonyParams::default());
let mut madgwick = Madgwick::new(dt, MadgwickParams::default());
let mut vqf = Vqf::new(dt, VqfParams::default());
// Sensor data
let gyr = Vector3::new(0.0, 0.0, 0.0);
let acc = Vector3::new(0.0, 0.0, 9.81);
let mag = Vector3::new(20.0, 0.0, 0.0);
mahony.update(gyr, acc, mag);
madgwick.update(gyr, acc, mag);
vqf.update(gyr, acc, mag);
// Get orientation as UnitQuaternion
let q_mahony = mahony.orientation();
let q_madgwick = madgwick.orientation();
let q_vqf = vqf.orientation();
// std::println used only for example purposes, library itself
// is fully no_std compatible.
println!("Mahony: {:?}", q_mahony.euler_angles());
println!("Madgwick: {:?}", q_madgwick.euler_angles());
println!("VQF: {:?}", q_vqf.euler_angles());
}The results below are from evaluations on the Berlin Robust Orientation Estimation Assessment Dataset (BROAD). For context, BROAD contains 39 trials with synchronized IMU and optical ground-truth orientation: 23 undisturbed trials (rotation, translation, and combined motion at slow/fast speeds) and 16 disturbed trials (e.g., tapping, vibration, stationary/attached magnets, office environment, and mixed conditions). Dataset publication: https://www.mdpi.com/2306-5729/6/7/72.
Reported metrics are dataset-averaged orientation errors in degrees:
AVG Total RMSE, AVG Heading RMSE, and AVG Inclination RMSE.
Algorithm: Vqf
AVG Total RMSE: 2.0776 deg
AVG Heading RMSE: 1.9205 deg
AVG Inclination RMSE: 0.6963 deg
Algorithm: Mahony
AVG Total RMSE: 7.4884 deg
AVG Heading RMSE: 6.2993 deg
AVG Inclination RMSE: 3.6971 deg
Algorithm: Madgwick
AVG Total RMSE: 5.0831 deg
AVG Heading RMSE: 4.3588 deg
AVG Inclination RMSE: 2.3404 degThis project is licensed under the Apache 2.0. See the LICENSE file for details.
This library incorporates ideas and data from the following projects and publications.
-
BROAD - A benchmark for robust inertial orientation estimation D. Laidig, M. Caruso, A. Cereatti, and T. Seel, Data, vol. 6, no. 7, p. 72, 2021.
-
Nonlinear complementary filters on the special orthogonal group R. Mahony, T. Hamel, and J.-M. Pflimlin, IEEE Transactions on Automatic Control, vol. 53, no. 5, pp. 1203–1218, 2008.
-
An efficient orientation filter for inertial and inertial/magnetic sensor arrays S. O. H. Madgwick et al., 2010.
-
VQF: Highly accurate IMU orientation estimation with bias estimation and magnetic disturbance rejection D. Laidig and T. Seel, Information Fusion, vol. 91, pp. 187–204, 2023.
-
ahrs-rs: alternative Mahony and Madgwick filter implementation in Rust. https://github.com/jmagnuson/ahrs-rs
-
vqf-rs: alternative VQF filter implementation in Rust. https://github.com/vgskye/vqf-rs
-
vqf: another VQF filter implementation in Rust. https://github.com/oxkitsune/vqf
-
broad: Berlin Robust Orientation Estimation Assessment Dataset (BROAD). https://github.com/dlaidig/broad