#![cfg_attr(not(feature = "std"), no_std)]
#![cfg_attr(not(feature = "f32"), allow(clippy::unnecessary_cast))]
#[cfg(feature = "f32")]
pub type Float = f32;
#[cfg(not(feature = "f32"))]
pub type Float = f64;
#[cfg(any(feature = "std", feature = "micromath"))]
mod math {
use crate::Float;
#[cfg(feature = "micromath")]
use micromath::F32Ext;
pub fn sqrt(value: Float) -> Float {
value.sqrt()
}
pub fn fabs(value: Float) -> Float {
value.abs()
}
pub fn exp(value: Float) -> Float {
value.exp()
}
pub fn sin(value: Float) -> Float {
value.sin()
}
pub fn cos(value: Float) -> Float {
value.cos()
}
#[cfg(feature = "std")]
pub fn tan_f64(value: f64) -> f64 {
value.tan()
}
#[cfg(feature = "micromath")]
pub fn tan_f64(value: f64) -> f64 {
(value as f32).tan() as f64
}
pub fn asin(value: Float) -> Float {
value.asin()
}
pub fn acos(value: Float) -> Float {
value.acos()
}
pub fn atan2(value: Float, other: Float) -> Float {
value.atan2(other)
}
}
#[cfg(feature = "libm")]
mod math {
use crate::Float;
pub fn sqrt(value: Float) -> Float {
libm::Libm::<Float>::sqrt(value)
}
pub fn fabs(value: Float) -> Float {
libm::Libm::<Float>::fabs(value)
}
pub fn exp(value: Float) -> Float {
libm::Libm::<Float>::exp(value)
}
pub fn sin(value: Float) -> Float {
libm::Libm::<Float>::sin(value)
}
pub fn cos(value: Float) -> Float {
libm::Libm::<Float>::cos(value)
}
pub fn tan_f64(value: f64) -> f64 {
libm::tan(value)
}
pub fn asin(value: Float) -> Float {
libm::Libm::<Float>::asin(value)
}
pub fn acos(value: Float) -> Float {
libm::Libm::<Float>::acos(value)
}
pub fn atan2(value: Float, other: Float) -> Float {
libm::Libm::<Float>::atan2(value, other)
}
}
#[cfg(feature = "f32")]
use core::f32::consts as fc;
#[cfg(not(feature = "f32"))]
use core::f64::consts as fc;
use core::{
f64::consts as f64c,
ops::{Add, AddAssign, Mul, MulAssign, Sub, SubAssign},
};
fn flatten<const N: usize, const M: usize, const R: usize>(value: &mut [[Float; N]; M]) -> &mut [Float; R] {
assert_eq!(N * M, R);
unsafe { core::mem::transmute(value) }
}
#[derive(Clone, Copy, Default)]
pub struct Quaternion(pub Float, pub Float, pub Float, pub Float);
impl Mul for Quaternion {
type Output = Quaternion;
fn mul(self, rhs: Self) -> Self::Output {
let w = self.0 * rhs.0 - self.1 * rhs.1 - self.2 * rhs.2 - self.3 * rhs.3;
let x = self.0 * rhs.1 + self.1 * rhs.0 + self.2 * rhs.3 - self.3 * rhs.2;
let y = self.0 * rhs.2 - self.1 * rhs.3 + self.2 * rhs.0 + self.3 * rhs.1;
let z = self.0 * rhs.3 + self.1 * rhs.2 - self.2 * rhs.1 + self.3 * rhs.0;
Self(w, x, y, z)
}
}
impl MulAssign for Quaternion {
fn mul_assign(&mut self, rhs: Self) {
*self = *self * rhs;
}
}
impl From<[Float; 4]> for Quaternion {
fn from(value: [Float; 4]) -> Self {
Self(value[0], value[1], value[2], value[3])
}
}
impl Quaternion {
pub fn norm(&self) -> Float {
math::sqrt(square(self.0) + square(self.1) + square(self.2) + square(self.3))
}
pub fn normalize(&mut self) {
let n = self.norm();
if n < Float::EPSILON {
return;
}
self.0 /= n;
self.1 /= n;
self.2 /= n;
self.3 /= n;
}
pub fn rotate(&self, v: [Float; 3]) -> [Float; 3] {
let x = (1.0 - 2.0 * self.2 * self.2 - 2.0 * self.3 * self.3) * v[0]
+ 2.0 * v[1] * (self.2 * self.1 - self.0 * self.3)
+ 2.0 * v[2] * (self.0 * self.2 + self.3 * self.1);
let y = 2.0 * v[0] * (self.0 * self.3 + self.2 * self.1)
+ v[1] * (1.0 - 2.0 * self.1 * self.1 - 2.0 * self.3 * self.3)
+ 2.0 * v[2] * (self.2 * self.3 - self.1 * self.0);
let z = 2.0 * v[0] * (self.3 * self.1 - self.0 * self.2)
+ 2.0 * v[1] * (self.0 * self.1 + self.3 * self.2)
+ v[2] * (1.0 - 2.0 * self.1 * self.1 - 2.0 * self.2 * self.2);
[x, y, z]
}
pub fn apply_delta(&self, delta: Float) -> Quaternion {
let c = math::cos(delta / 2.0);
let s = math::sin(delta / 2.0);
let w = c * self.0 - s * self.3;
let x = c * self.1 - s * self.2;
let y = c * self.2 + s * self.1;
let z = c * self.3 + s * self.0;
Self(w, x, y, z)
}
}
#[derive(Clone, Copy)]
pub struct Matrix<const W: usize, const H: usize>(pub [[Float; W]; H]);
impl<const W: usize, const H: usize> Default for Matrix<W, H> {
fn default() -> Self {
Self([[0.0; W]; H])
}
}
impl<const W: usize, const H: usize> From<[[Float; W]; H]> for Matrix<W, H> {
fn from(value: [[Float; W]; H]) -> Self {
Self(value)
}
}
impl<const M: usize, const N: usize, const P: usize> Mul<Matrix<P, N>> for Matrix<N, M> {
type Output = Matrix<P, M>;
fn mul(self, rhs: Matrix<P, N>) -> Self::Output {
let mut out: Matrix<P, M> = Default::default();
for i in 0..M {
for j in 0..P {
let mut val = 0.0;
for k in 0..N {
val += self.0[i][k] * rhs.0[k][j];
}
out.0[i][j] = val;
}
}
out
}
}
impl<const X: usize> MulAssign for Matrix<X, X> {
fn mul_assign(&mut self, rhs: Self) {
*self = *self * rhs;
}
}
impl<const W: usize, const H: usize> Add for Matrix<W, H> {
type Output = Self;
fn add(self, rhs: Self) -> Self::Output {
let mut out: Self = Default::default();
for i in 0..W {
for j in 0..H {
out.0[j][i] = self.0[j][i] + rhs.0[j][i];
}
}
out
}
}
impl<const W: usize, const H: usize> AddAssign for Matrix<W, H> {
fn add_assign(&mut self, rhs: Self) {
*self = *self + rhs;
}
}
impl<const W: usize, const H: usize> Sub for Matrix<W, H> {
type Output = Self;
fn sub(self, rhs: Self) -> Self::Output {
let mut out: Self = Default::default();
for i in 0..W {
for j in 0..H {
out.0[j][i] = self.0[j][i] - rhs.0[j][i];
}
}
out
}
}
impl<const W: usize, const H: usize> SubAssign for Matrix<W, H> {
fn sub_assign(&mut self, rhs: Self) {
*self = *self - rhs;
}
}
impl<const W: usize, const H: usize> Matrix<W, H> {
pub fn transpose(self) -> Matrix<H, W> {
let mut out: Matrix<H, W> = Default::default();
for i in 0..W {
for j in 0..H {
out.0[i][j] = self.0[j][i];
}
}
out
}
}
impl Matrix<3, 3> {
pub fn invert(self) -> Option<Self> {
let a =
self.0[1][1] as f64 * self.0[2][2] as f64 - self.0[1][2] as f64 * self.0[2][1] as f64; let d =
self.0[0][2] as f64 * self.0[2][1] as f64 - self.0[0][1] as f64 * self.0[2][2] as f64; let g =
self.0[0][1] as f64 * self.0[1][2] as f64 - self.0[0][2] as f64 * self.0[1][1] as f64; let b =
self.0[1][2] as f64 * self.0[2][0] as f64 - self.0[1][0] as f64 * self.0[2][2] as f64; let e =
self.0[0][0] as f64 * self.0[2][2] as f64 - self.0[0][2] as f64 * self.0[2][0] as f64; let h =
self.0[0][2] as f64 * self.0[1][0] as f64 - self.0[0][0] as f64 * self.0[1][2] as f64; let c =
self.0[1][0] as f64 * self.0[2][1] as f64 - self.0[1][1] as f64 * self.0[2][0] as f64; let f =
self.0[0][1] as f64 * self.0[2][0] as f64 - self.0[0][0] as f64 * self.0[2][1] as f64; let i =
self.0[0][0] as f64 * self.0[1][1] as f64 - self.0[0][1] as f64 * self.0[1][0] as f64;
let det = self.0[0][0] as f64 * a + self.0[0][1] as f64 * b + self.0[0][2] as f64 * c;
if (-f64::EPSILON..=f64::EPSILON).contains(&det) {
return None;
}
Some(
[
[(a / det) as Float, (d / det) as Float, (g / det) as Float],
[(b / det) as Float, (e / det) as Float, (h / det) as Float],
[(c / det) as Float, (f / det) as Float, (i / det) as Float],
]
.into(),
)
}
}
#[cfg_attr(doc, doc = include_str!("../katex.html"))]
#[derive(Clone, Copy)]
pub struct Params {
pub tau_acc: Float,
pub tau_mag: Float,
#[cfg(feature = "motion-bias-estimation")]
pub motion_bias_est_enabled: bool,
pub rest_bias_est_enabled: bool,
pub mag_dist_rejection_enabled: bool,
pub bias_sigma_init: Float,
pub bias_forgetting_time: Float,
pub bias_clip: Float,
#[cfg(feature = "motion-bias-estimation")]
pub bias_sigma_motion: Float,
#[cfg(feature = "motion-bias-estimation")]
pub bias_vertical_forgetting_factor: Float,
pub bias_sigma_rest: Float,
pub rest_min_t: Float,
pub rest_filter_tau: Float,
pub rest_th_gyr: Float,
pub rest_th_acc: Float,
pub mag_current_tau: Float,
pub mag_ref_tau: Float,
pub mag_norm_th: Float,
pub mag_dip_th: Float,
pub mag_new_time: Float,
pub mag_new_first_time: Float,
pub mag_new_min_gyr: Float,
pub mag_min_undisturbed_time: Float,
pub mag_max_rejection_time: Float,
pub mag_rejection_factor: Float,
}
impl Default for Params {
fn default() -> Self {
Self {
tau_acc: 3.0,
tau_mag: 9.0,
#[cfg(feature = "motion-bias-estimation")]
motion_bias_est_enabled: true,
rest_bias_est_enabled: true,
mag_dist_rejection_enabled: true,
bias_sigma_init: 0.5,
bias_forgetting_time: 100.0,
bias_clip: 2.0,
#[cfg(feature = "motion-bias-estimation")]
bias_sigma_motion: 0.1,
#[cfg(feature = "motion-bias-estimation")]
bias_vertical_forgetting_factor: 0.0001,
bias_sigma_rest: 0.03,
rest_min_t: 1.5,
rest_filter_tau: 0.5,
rest_th_gyr: 2.0,
rest_th_acc: 0.5,
mag_current_tau: 0.05,
mag_ref_tau: 20.0,
mag_norm_th: 0.1,
mag_dip_th: 10.0,
mag_new_time: 20.0,
mag_new_first_time: 5.0,
mag_new_min_gyr: 20.0,
mag_min_undisturbed_time: 0.5,
mag_max_rejection_time: 60.0,
mag_rejection_factor: 2.0,
}
}
}
#[cfg_attr(doc, doc = include_str!("../katex.html"))]
#[derive(Clone, Copy, Default)]
pub struct State {
pub gyr_quat: Quaternion,
pub acc_quat: Quaternion,
pub delta: Float,
pub rest_detected: bool,
pub mag_dist_detected: bool,
pub last_acc_lp: [Float; 3],
pub acc_lp_state: [[f64; 2]; 3],
pub last_acc_corr_angular_rate: Float,
pub k_mag_init: Float,
pub last_mag_dis_angle: Float,
pub last_mag_corr_angular_rate: Float,
pub bias: [Float; 3],
#[cfg(feature = "motion-bias-estimation")]
pub bias_p: Matrix<3, 3>,
#[cfg(not(feature = "motion-bias-estimation"))]
pub bias_p: Float,
#[cfg(feature = "motion-bias-estimation")]
pub motion_bias_est_rlp_state: [[f64; 2]; 9],
#[cfg(feature = "motion-bias-estimation")]
pub motion_bias_est_bias_lp_state: [[f64; 2]; 2],
pub rest_last_squared_deviations: [Float; 2],
pub rest_t: Float,
pub rest_last_gyr_lp: [Float; 3],
pub rest_gyr_lp_state: [[f64; 2]; 3],
pub rest_last_acc_lp: [Float; 3],
pub rest_acc_lp_state: [[f64; 2]; 3],
pub mag_ref_norm: Float,
pub mag_ref_dip: Float,
pub mag_undisturbed_t: Float,
pub mag_reject_t: Float,
pub mag_candidate_norm: Float,
pub mag_candidate_dip: Float,
pub mag_candidate_t: Float,
pub mag_norm_dip: [Float; 2],
pub mag_norm_dip_lp_state: [[f64; 2]; 2],
}
#[cfg_attr(doc, doc = include_str!("../katex.html"))]
#[derive(Clone, Copy, Default)]
pub struct Coefficients {
pub gyr_ts: Float,
pub acc_ts: Float,
pub mag_ts: Float,
pub acc_lp_b: [f64; 3],
pub acc_lp_a: [f64; 2],
pub k_mag: Float,
pub bias_p0: Float,
pub bias_v: Float,
#[cfg(feature = "motion-bias-estimation")]
pub bias_motion_w: Float,
#[cfg(feature = "motion-bias-estimation")]
pub bias_vertical_w: Float,
pub bias_rest_w: Float,
pub rest_gyr_lp_b: [f64; 3],
pub rest_gyr_lp_a: [f64; 2],
pub rest_acc_lp_b: [f64; 3],
pub rest_acc_lp_a: [f64; 2],
pub k_mag_ref: Float,
pub mag_norm_dip_lp_b: [f64; 3],
pub mag_norm_dip_lp_a: [f64; 2],
}
pub struct VQF {
params: Params,
state: State,
coeffs: Coefficients,
}
#[inline(always)]
fn square(t: Float) -> Float {
t * t
}
#[cfg_attr(doc, doc = include_str!("../katex.html"))]
impl VQF {
pub fn new(
gyr_ts: Float,
acc_ts: Option<Float>,
mag_ts: Option<Float>,
params: Option<Params>,
) -> Self {
let mut ret = Self {
params: params.unwrap_or_default(),
state: Default::default(),
coeffs: Default::default(),
};
ret.coeffs.gyr_ts = gyr_ts;
ret.coeffs.acc_ts = acc_ts.unwrap_or(gyr_ts);
ret.coeffs.mag_ts = mag_ts.unwrap_or(gyr_ts);
ret.setup();
ret
}
pub fn update_gyr(&mut self, gyr: [Float; 3]) {
if self.params.rest_bias_est_enabled || self.params.mag_dist_rejection_enabled {
Self::filter_vec(
gyr,
self.params.rest_filter_tau,
self.coeffs.gyr_ts,
self.coeffs.rest_gyr_lp_b,
self.coeffs.rest_gyr_lp_a,
&mut self.state.rest_gyr_lp_state,
&mut self.state.rest_last_gyr_lp,
);
self.state.rest_last_squared_deviations[0] =
square(gyr[0] - self.state.rest_last_gyr_lp[0])
+ square(gyr[1] - self.state.rest_last_gyr_lp[1])
+ square(gyr[2] - self.state.rest_last_gyr_lp[2]);
let bias_clip = self.params.bias_clip * (fc::PI / 180.0);
if self.state.rest_last_squared_deviations[0]
>= square(self.params.rest_th_gyr * (fc::PI / 180.0))
|| math::fabs(self.state.rest_last_gyr_lp[0]) > bias_clip
|| math::fabs(self.state.rest_last_gyr_lp[1]) > bias_clip
|| math::fabs(self.state.rest_last_gyr_lp[2]) > bias_clip
{
self.state.rest_t = 0.0;
self.state.rest_detected = false;
}
}
let gyr_no_bias = [
gyr[0] - self.state.bias[0],
gyr[1] - self.state.bias[1],
gyr[2] - self.state.bias[2],
];
let gyr_norm = Self::norm(&gyr_no_bias);
let angle = gyr_norm * self.coeffs.gyr_ts;
if gyr_norm > Float::EPSILON {
let c = math::cos(angle / 2.0);
let s = math::sin(angle / 2.0) / gyr_norm;
let gyr_step_quat = [
c,
s * gyr_no_bias[0],
s * gyr_no_bias[1],
s * gyr_no_bias[2],
];
self.state.gyr_quat *= gyr_step_quat.into();
self.state.gyr_quat.normalize();
}
}
pub fn update_acc(&mut self, acc: [Float; 3]) {
if acc == [0.0; 3] {
return;
}
if self.params.rest_bias_est_enabled {
Self::filter_vec(
acc,
self.params.rest_filter_tau,
self.coeffs.acc_ts,
self.coeffs.rest_acc_lp_b,
self.coeffs.rest_acc_lp_a,
&mut self.state.rest_acc_lp_state,
&mut self.state.rest_last_acc_lp,
);
self.state.rest_last_squared_deviations[1] =
square(acc[0] - self.state.rest_last_acc_lp[0])
+ square(acc[1] - self.state.rest_last_acc_lp[1])
+ square(acc[2] - self.state.rest_last_acc_lp[2]);
if self.state.rest_last_squared_deviations[1] >= square(self.params.rest_th_acc) {
self.state.rest_t = 0.0;
self.state.rest_detected = false;
} else {
self.state.rest_t += self.coeffs.acc_ts;
if self.state.rest_t >= self.params.rest_min_t {
self.state.rest_detected = true;
}
}
}
let acc_earth = self.state.gyr_quat.rotate(acc);
Self::filter_vec(
acc_earth,
self.params.tau_acc,
self.coeffs.acc_ts,
self.coeffs.acc_lp_b,
self.coeffs.acc_lp_a,
&mut self.state.acc_lp_state,
&mut self.state.last_acc_lp,
);
let mut acc_earth = self.state.acc_quat.rotate(self.state.last_acc_lp);
Self::normalize(&mut acc_earth);
let q_w = math::sqrt((acc_earth[2] + 1.0) / 2.0);
let acc_corr_quat: Quaternion = if q_w > 1e-6 {
[
q_w,
0.5 * acc_earth[1] / q_w,
-0.5 * acc_earth[0] / q_w,
0.0,
]
.into()
} else {
[0.0, 1.0, 0.0, 1.0].into()
};
self.state.acc_quat = acc_corr_quat * self.state.acc_quat;
self.state.acc_quat.normalize();
self.state.last_acc_corr_angular_rate =
math::acos(acc_earth[2]) / self.coeffs.acc_ts;
#[cfg(feature = "motion-bias-estimation")]
{
if self.params.motion_bias_est_enabled || self.params.rest_bias_est_enabled {
let bias_clip = self.params.bias_clip * (fc::PI / 180.0);
let acc_gyr_quat = self.quat_6d();
let mut r: Matrix<3, 3> = [
[
1.0 - 2.0 * square(acc_gyr_quat.2) - 2.0 * square(acc_gyr_quat.3), 2.0 * (acc_gyr_quat.2 * acc_gyr_quat.1 - acc_gyr_quat.0 * acc_gyr_quat.3), 2.0 * (acc_gyr_quat.0 * acc_gyr_quat.2 + acc_gyr_quat.3 * acc_gyr_quat.1), ],
[
2.0 * (acc_gyr_quat.0 * acc_gyr_quat.3 + acc_gyr_quat.2 * acc_gyr_quat.1), 1.0 - 2.0 * square(acc_gyr_quat.1) - 2.0 * square(acc_gyr_quat.3), 2.0 * (acc_gyr_quat.2 * acc_gyr_quat.3 - acc_gyr_quat.1 * acc_gyr_quat.0), ],
[
2.0 * (acc_gyr_quat.3 * acc_gyr_quat.1 - acc_gyr_quat.0 * acc_gyr_quat.2), 2.0 * (acc_gyr_quat.0 * acc_gyr_quat.1 + acc_gyr_quat.3 * acc_gyr_quat.2), 1.0 - 2.0 * square(acc_gyr_quat.1) - 2.0 * square(acc_gyr_quat.2), ],
]
.into();
let mut bias_lp = [
r.0[0][0] * self.state.bias[0]
+ r.0[0][1] * self.state.bias[1]
+ r.0[0][2] * self.state.bias[2],
r.0[1][0] * self.state.bias[0]
+ r.0[1][1] * self.state.bias[1]
+ r.0[1][2] * self.state.bias[2],
];
let r_arr: &mut [Float; 9] = flatten(&mut r.0);
Self::filter_vec(
*r_arr,
self.params.tau_acc,
self.coeffs.acc_ts,
self.coeffs.acc_lp_b,
self.coeffs.acc_lp_a,
&mut self.state.motion_bias_est_rlp_state,
r_arr,
);
Self::filter_vec(
bias_lp,
self.params.tau_acc,
self.coeffs.acc_ts,
self.coeffs.acc_lp_b,
self.coeffs.acc_lp_a,
&mut self.state.motion_bias_est_bias_lp_state,
&mut bias_lp,
);
let (mut e, w) = if self.state.rest_detected && self.params.rest_bias_est_enabled {
let e = [
self.state.rest_last_gyr_lp[0] - self.state.bias[0],
self.state.rest_last_gyr_lp[1] - self.state.bias[1],
self.state.rest_last_gyr_lp[2] - self.state.bias[2],
];
r = [[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0]].into();
let w = [self.coeffs.bias_rest_w; 3];
(e, w)
} else if self.params.motion_bias_est_enabled {
let e = [
-acc_earth[1] / self.coeffs.acc_ts + bias_lp[0]
- r.0[0][0] * self.state.bias[0]
- r.0[0][1] * self.state.bias[1]
- r.0[0][2] * self.state.bias[2],
acc_earth[0] / self.coeffs.acc_ts + bias_lp[1]
- r.0[1][0] * self.state.bias[0]
- r.0[1][1] * self.state.bias[1]
- r.0[1][2] * self.state.bias[2],
-r.0[2][0] * self.state.bias[0]
- r.0[2][1] * self.state.bias[1]
- r.0[2][2] * self.state.bias[2],
];
let w = [
self.coeffs.bias_motion_w,
self.coeffs.bias_motion_w,
self.coeffs.bias_vertical_w,
];
(e, w)
} else {
([0.0; 3], [-1.0; 3])
};
if self.state.bias_p.0[0][0] < self.coeffs.bias_p0 {
self.state.bias_p.0[0][0] += self.coeffs.bias_v;
}
if self.state.bias_p.0[1][1] < self.coeffs.bias_p0 {
self.state.bias_p.0[1][1] += self.coeffs.bias_v;
}
if self.state.bias_p.0[2][2] < self.coeffs.bias_p0 {
self.state.bias_p.0[2][2] += self.coeffs.bias_v;
}
if w[0] >= 0.0 {
Self::clip(&mut e, -bias_clip, bias_clip);
let mut k = self.state.bias_p * r.transpose(); k = r * k; k.0[0][0] += w[0];
k.0[1][1] += w[1];
k.0[2][2] += w[2]; k = k.invert().unwrap(); k = r.transpose() * k; k = self.state.bias_p * k;
self.state.bias[0] += k.0[0][0] * e[0] + k.0[0][1] * e[1] + k.0[0][2] * e[2];
self.state.bias[1] += k.0[1][0] * e[0] + k.0[1][1] * e[1] + k.0[1][2] * e[2];
self.state.bias[2] += k.0[2][0] * e[0] + k.0[2][1] * e[1] + k.0[2][2] * e[2];
k *= r; k *= self.state.bias_p; self.state.bias_p -= k;
Self::clip(&mut self.state.bias, -bias_clip, bias_clip);
}
}
}
#[cfg(not(feature = "motion-bias-estimation"))]
{
if self.params.rest_bias_est_enabled {
let bias_clip = self.params.bias_clip * (fc::PI / 180.0);
if self.state.bias_p < self.coeffs.bias_p0 {
self.state.bias_p += self.coeffs.bias_v;
}
if self.state.rest_detected {
let mut e = [
self.state.rest_last_gyr_lp[0] - self.state.bias[0],
self.state.rest_last_gyr_lp[1] - self.state.bias[1],
self.state.rest_last_gyr_lp[2] - self.state.bias[2],
];
Self::clip(&mut e, -bias_clip, bias_clip);
let k = self.state.bias_p / (self.coeffs.bias_rest_w + self.state.bias_p);
self.state.bias[0] += k * e[0];
self.state.bias[1] += k * e[1];
self.state.bias[2] += k * e[2];
self.state.bias_p -= k * self.state.bias_p;
Self::clip(&mut self.state.bias, -bias_clip, bias_clip);
}
}
}
}
pub fn update_mag(&mut self, mag: [Float; 3]) {
if mag == [0.0; 3] {
return;
}
let acc_gyr_quat = self.quat_6d();
let mag_earth = acc_gyr_quat.rotate(mag);
if self.params.mag_dist_rejection_enabled {
self.state.mag_norm_dip[0] = Self::norm(&mag_earth);
self.state.mag_norm_dip[1] =
-math::asin(mag_earth[2] / self.state.mag_norm_dip[0]);
if self.params.mag_current_tau > 0.0 {
Self::filter_vec(
self.state.mag_norm_dip,
self.params.mag_current_tau,
self.coeffs.mag_ts,
self.coeffs.mag_norm_dip_lp_b,
self.coeffs.mag_norm_dip_lp_a,
&mut self.state.mag_norm_dip_lp_state,
&mut self.state.mag_norm_dip,
);
}
if math::fabs(self.state.mag_norm_dip[0] - self.state.mag_ref_norm)
< self.params.mag_norm_th * self.state.mag_ref_norm
&& math::fabs(self.state.mag_norm_dip[1] - self.state.mag_ref_dip)
< self.params.mag_dip_th * (fc::PI / 180.0)
{
self.state.mag_undisturbed_t += self.coeffs.mag_ts;
if self.state.mag_undisturbed_t >= self.params.mag_min_undisturbed_time {
self.state.mag_dist_detected = false;
self.state.mag_ref_norm += self.coeffs.k_mag_ref
* (self.state.mag_norm_dip[0] - self.state.mag_ref_norm);
self.state.mag_ref_dip += self.coeffs.k_mag_ref
* (self.state.mag_norm_dip[1] - self.state.mag_ref_dip);
}
} else {
self.state.mag_undisturbed_t = 0.0;
self.state.mag_dist_detected = true;
}
if math::fabs(self.state.mag_norm_dip[0] - self.state.mag_candidate_norm)
< self.params.mag_norm_th * self.state.mag_candidate_norm
&& math::fabs(self.state.mag_norm_dip[1] - self.state.mag_candidate_dip)
< self.params.mag_dip_th * (fc::PI / 180.0)
{
if Self::norm(&self.state.rest_last_gyr_lp)
>= self.params.mag_new_min_gyr * fc::PI / 180.0
{
self.state.mag_candidate_t += self.coeffs.mag_ts;
}
self.state.mag_candidate_norm += self.coeffs.k_mag_ref
* (self.state.mag_norm_dip[0] - self.state.mag_candidate_norm);
self.state.mag_candidate_dip += self.coeffs.k_mag_ref
* (self.state.mag_norm_dip[1] - self.state.mag_candidate_dip);
if self.state.mag_dist_detected
&& (self.state.mag_candidate_t >= self.params.mag_new_time
|| (self.state.mag_ref_norm == 0.0
&& self.state.mag_candidate_t >= self.params.mag_new_first_time))
{
self.state.mag_ref_norm = self.state.mag_candidate_norm;
self.state.mag_ref_dip = self.state.mag_candidate_dip;
self.state.mag_dist_detected = false;
self.state.mag_undisturbed_t = self.params.mag_min_undisturbed_time;
}
} else {
self.state.mag_candidate_t = 0.0;
self.state.mag_candidate_norm = self.state.mag_norm_dip[0];
self.state.mag_candidate_dip = self.state.mag_norm_dip[1];
}
}
self.state.last_mag_dis_angle =
math::atan2(mag_earth[0], mag_earth[1]) - self.state.delta;
if self.state.last_mag_dis_angle > fc::PI {
self.state.last_mag_dis_angle -= 2.0 * fc::PI;
} else if self.state.last_mag_dis_angle < (-fc::PI) {
self.state.last_mag_dis_angle += 2.0 * fc::PI;
}
let mut k = self.coeffs.k_mag;
if self.params.mag_dist_rejection_enabled {
if self.state.mag_dist_detected {
if self.state.mag_reject_t <= self.params.mag_max_rejection_time {
self.state.mag_reject_t += self.coeffs.mag_ts;
k = 0.0;
} else {
k /= self.params.mag_rejection_factor;
}
} else {
self.state.mag_reject_t = (0.0 as Float).max(
self.state.mag_reject_t - self.params.mag_rejection_factor * self.coeffs.mag_ts,
);
}
}
if self.state.k_mag_init != 0.0 {
if k < self.state.k_mag_init {
k = self.state.k_mag_init;
}
self.state.k_mag_init = self.state.k_mag_init / (self.state.k_mag_init + 1.0);
if self.state.k_mag_init * self.params.tau_mag < self.coeffs.mag_ts {
self.state.k_mag_init = 0.0;
}
}
self.state.delta += k * self.state.last_mag_dis_angle;
self.state.last_mag_corr_angular_rate =
k * self.state.last_mag_dis_angle / self.coeffs.mag_ts;
if self.state.delta > fc::PI {
self.state.delta -= 2.0 * fc::PI;
} else if self.state.delta < -fc::PI {
self.state.delta += 2.0 * fc::PI;
}
}
pub fn update(&mut self, gyr: [Float; 3], acc: [Float; 3], mag: Option<[Float; 3]>) {
self.update_gyr(gyr);
self.update_acc(acc);
if let Some(mag) = mag {
self.update_mag(mag);
}
}
pub fn quat_3d(&self) -> Quaternion {
self.state.gyr_quat
}
pub fn quat_6d(&self) -> Quaternion {
self.state.acc_quat * self.state.gyr_quat
}
pub fn quat_9d(&self) -> Quaternion {
(self.state.acc_quat * self.state.gyr_quat).apply_delta(self.state.delta)
}
pub fn delta(&self) -> Float {
self.state.delta
}
#[cfg(feature = "motion-bias-estimation")]
pub fn bias_estimate(&self) -> ([Float; 3], Float) {
let sum1 = math::fabs(self.state.bias_p.0[0][0])
+ math::fabs(self.state.bias_p.0[0][1])
+ math::fabs(self.state.bias_p.0[0][2]);
let sum2 = math::fabs(self.state.bias_p.0[1][0])
+ math::fabs(self.state.bias_p.0[1][1])
+ math::fabs(self.state.bias_p.0[1][2]);
let sum3 = math::fabs(self.state.bias_p.0[2][0])
+ math::fabs(self.state.bias_p.0[2][1])
+ math::fabs(self.state.bias_p.0[2][2]);
let p = sum1.max(sum2).max(sum3).min(self.coeffs.bias_p0);
(
self.state.bias,
math::sqrt(p) * (fc::PI / 100.0 / 180.0),
)
}
#[cfg(not(feature = "motion-bias-estimation"))]
pub fn bias_estimate(&self) -> ([Float; 3], Float) {
(
self.state.bias,
math::sqrt(self.state.bias_p) * (fc::PI / 100.0 / 180.0),
)
}
pub fn set_bias_estimate(&mut self, bias: [Float; 3], sigma: Option<Float>) {
self.state.bias = bias;
if let Some(sigma) = sigma {
let p = square(sigma * (180.0 * 100.0 / fc::PI));
#[cfg(feature = "motion-bias-estimation")]
{
self.state.bias_p = [[p, 0.0, 0.0], [0.0, p, 0.0], [0.0, 0.0, p]].into();
}
#[cfg(not(feature = "motion-bias-estimation"))]
{
self.state.bias_p = p;
}
}
}
pub fn rest_detected(&self) -> bool {
self.state.rest_detected
}
pub fn mag_dist_detected(&self) -> bool {
self.state.mag_dist_detected
}
pub fn relative_rest_deviations(&self) -> [Float; 2] {
[
math::sqrt(self.state.rest_last_squared_deviations[0])
/ (self.params.rest_th_gyr * (fc::PI / 180.0)),
math::sqrt(self.state.rest_last_squared_deviations[1])
/ self.params.rest_th_acc,
]
}
pub fn mag_ref_norm(&self) -> Float {
self.state.mag_ref_norm
}
pub fn mag_ref_dip(&self) -> Float {
self.state.mag_ref_dip
}
pub fn set_mag_ref(&mut self, norm: Float, dip: Float) {
self.state.mag_ref_norm = norm;
self.state.mag_ref_dip = dip;
}
pub fn set_tau_acc(&mut self, tau_acc: Float) {
if self.params.tau_acc == tau_acc {
return;
}
self.params.tau_acc = tau_acc;
let mut new_b = [0.0; 3];
let mut new_a = [0.0; 2];
Self::filter_coeffs(
self.params.tau_acc,
self.coeffs.acc_ts,
&mut new_b,
&mut new_a,
);
Self::filter_adapt_state_for_coeff_change(
self.state.last_acc_lp,
self.coeffs.acc_lp_b,
self.coeffs.acc_lp_a,
new_b,
new_a,
&mut self.state.acc_lp_state,
);
#[cfg(feature = "motion-bias-estimation")]
{
let mut r: [Float; 9] = [0.0; 9];
for (i, val) in r.iter_mut().enumerate() {
*val = self.state.motion_bias_est_rlp_state[i][0] as Float;
}
Self::filter_adapt_state_for_coeff_change(
r,
self.coeffs.acc_lp_b,
self.coeffs.acc_lp_a,
new_b,
new_a,
&mut self.state.motion_bias_est_rlp_state,
);
let mut bias_lp: [Float; 2] = [0.0; 2];
for (i, val) in bias_lp.iter_mut().enumerate() {
*val = self.state.motion_bias_est_bias_lp_state[i][0] as Float;
}
Self::filter_adapt_state_for_coeff_change(
bias_lp,
self.coeffs.acc_lp_b,
self.coeffs.acc_lp_a,
new_b,
new_a,
&mut self.state.motion_bias_est_bias_lp_state,
);
}
self.coeffs.acc_lp_b = new_b;
self.coeffs.acc_lp_a = new_a;
}
pub fn set_tau_mag(&mut self, tau_mag: Float) {
self.params.tau_mag = tau_mag;
self.coeffs.k_mag = Self::gain_from_tau(self.params.tau_mag, self.coeffs.mag_ts)
}
#[cfg(feature = "motion-bias-estimation")]
pub fn set_motion_bias_est_enabled(&mut self, enabled: bool) {
if self.params.motion_bias_est_enabled == enabled {
return;
}
self.params.motion_bias_est_enabled = enabled;
self.state.motion_bias_est_rlp_state = [[f64::NAN; 2]; 9];
self.state.motion_bias_est_bias_lp_state = [[f64::NAN; 2]; 2];
}
pub fn set_rest_bias_est_enabled(&mut self, enabled: bool) {
if self.params.rest_bias_est_enabled == enabled {
return;
}
self.params.rest_bias_est_enabled = enabled;
self.state.rest_detected = false;
self.state.rest_last_squared_deviations = [0.0; 2];
self.state.rest_t = 0.0;
self.state.rest_last_gyr_lp = [0.0; 3];
self.state.rest_gyr_lp_state = [[f64::NAN; 2]; 3];
self.state.rest_last_acc_lp = [0.0; 3];
self.state.rest_acc_lp_state = [[f64::NAN; 2]; 3];
}
pub fn set_mag_dist_rejection_enabled(&mut self, enabled: bool) {
if self.params.mag_dist_rejection_enabled == enabled {
return;
}
self.params.mag_dist_rejection_enabled = enabled;
self.state.mag_dist_detected = true;
self.state.mag_ref_norm = 0.0;
self.state.mag_ref_dip = 0.0;
self.state.mag_undisturbed_t = 0.0;
self.state.mag_reject_t = self.params.mag_max_rejection_time;
self.state.mag_candidate_norm = -1.0;
self.state.mag_candidate_dip = 0.0;
self.state.mag_candidate_t = 0.0;
self.state.mag_norm_dip_lp_state = [[f64::NAN; 2]; 2];
}
pub fn set_rest_detection_thresholds(&mut self, th_gyr: Float, th_acc: Float) {
self.params.rest_th_gyr = th_gyr;
self.params.rest_th_acc = th_acc;
}
pub fn params(&self) -> &Params {
&self.params
}
pub fn coeffs(&self) -> &Coefficients {
&self.coeffs
}
pub fn state(&self) -> &State {
&self.state
}
pub fn state_mut(&mut self) -> &mut State {
&mut self.state
}
pub fn reset_state(&mut self) {
self.state.gyr_quat = [1.0, 0.0, 0.0, 0.0].into();
self.state.acc_quat = [1.0, 0.0, 0.0, 0.0].into();
self.state.delta = 0.0;
self.state.rest_detected = false;
self.state.mag_dist_detected = true;
self.state.last_acc_lp = [0.0; 3];
self.state.acc_lp_state = [[f64::NAN; 2]; 3];
self.state.last_acc_corr_angular_rate = 0.0;
self.state.k_mag_init = 1.0;
self.state.last_mag_dis_angle = 0.0;
self.state.last_mag_corr_angular_rate = 0.0;
self.state.bias = [0.0; 3];
#[cfg(feature = "motion-bias-estimation")]
{
self.state.bias_p = [
[self.coeffs.bias_p0, 0.0, 0.0],
[0.0, self.coeffs.bias_p0, 0.0],
[0.0, 0.0, self.coeffs.bias_p0],
]
.into();
}
#[cfg(not(feature = "motion-bias-estimation"))]
{
self.state.bias_p = self.coeffs.bias_p0;
}
#[cfg(feature = "motion-bias-estimation")]
{
self.state.motion_bias_est_rlp_state = [[f64::NAN; 2]; 9];
self.state.motion_bias_est_bias_lp_state = [[f64::NAN; 2]; 2];
}
self.state.rest_last_squared_deviations = [0.0; 2];
self.state.rest_t = 0.0;
self.state.rest_last_gyr_lp = [0.0; 3];
self.state.rest_gyr_lp_state = [[f64::NAN; 2]; 3];
self.state.rest_last_acc_lp = [0.0; 3];
self.state.rest_acc_lp_state = [[f64::NAN; 2]; 3];
self.state.mag_ref_norm = 0.0;
self.state.mag_ref_dip = 0.0;
self.state.mag_undisturbed_t = 0.0;
self.state.mag_reject_t = self.params.mag_max_rejection_time;
self.state.mag_candidate_norm = -1.0;
self.state.mag_candidate_dip = 0.0;
self.state.mag_candidate_t = 0.0;
self.state.mag_norm_dip = [0.0; 2];
self.state.mag_norm_dip_lp_state = [[f64::NAN; 2]; 2];
}
fn norm<const N: usize>(vec: &[Float; N]) -> Float {
let mut s = 0.0;
for i in vec {
s += i * i;
}
math::sqrt(s)
}
fn normalize<const N: usize>(vec: &mut [Float; N]) {
let n = Self::norm(vec);
if n < Float::EPSILON {
return;
}
for i in vec.iter_mut() {
*i /= n;
}
}
fn clip<const N: usize>(vec: &mut [Float; N], min: Float, max: Float) {
for i in vec.iter_mut() {
if *i < min {
*i = min;
} else if *i > max {
*i = max;
}
}
}
fn gain_from_tau(tau: Float, ts: Float) -> Float {
assert!(ts > 0.0);
if tau < 0.0 {
0.0 } else if tau == 0.0 {
1.0 } else {
1.0 - math::exp(-ts / tau) }
}
fn filter_coeffs(tau: Float, ts: Float, out_b: &mut [f64; 3], out_a: &mut [f64; 2]) {
assert!(tau > 0.0);
assert!(ts > 0.0);
let fc = (f64c::SQRT_2 / (2.0 * f64c::PI)) / (tau as f64); let c = math::tan_f64(f64c::PI * fc * ts as f64);
let d = c * c + f64c::SQRT_2 * c + 1.0;
let b0 = c * c / d;
out_b[0] = b0;
out_b[1] = 2.0 * b0;
out_b[2] = b0;
out_a[0] = 2.0 * (c * c - 1.0) / d; out_a[1] = (1.0 - f64c::SQRT_2 * c + c * c) / d; }
fn filter_initial_state(x0: Float, b: [f64; 3], a: [f64; 2], out: &mut [f64; 2]) {
out[0] = (x0 as f64) * (1.0 - b[0]);
out[1] = (x0 as f64) * (b[2] - a[1]);
}
fn filter_adapt_state_for_coeff_change<const N: usize>(
last_y: [Float; N],
b_old: [f64; 3],
a_old: [f64; 2],
b_new: [f64; 3],
a_new: [f64; 2],
state: &mut [[f64; 2]; N],
) {
if state[0][0].is_nan() {
return;
}
for (i, row) in state.iter_mut().enumerate() {
row[0] += (b_old[0] - b_new[0]) * last_y[i] as f64;
row[1] += (b_old[1] - b_new[1] - a_old[0] + a_new[0]) * last_y[i] as f64;
}
}
fn filter_step(x: Float, b: [f64; 3], a: [f64; 2], state: &mut [f64; 2]) -> Float {
let y = b[0] * (x as f64) + state[0];
state[0] = b[1] * (x as f64) - a[0] * y + state[1];
state[1] = b[2] * (x as f64) - a[1] * y;
y as Float
}
fn filter_vec<const N: usize>(
x: [Float; N],
tau: Float,
ts: Float,
b: [f64; 3],
a: [f64; 2],
state: &mut [[f64; 2]; N],
out: &mut [Float; N],
) {
assert!(N >= 2);
if state[0][0].is_nan() {
if state[1][0].is_nan() {
state[1][0] = 0.0; for row in state.iter_mut() {
row[1] = 0.0; }
}
state[1][0] += 1.0;
for i in 0..N {
state[i][1] += x[i] as f64;
out[i] = (state[i][1] / state[1][0]) as Float;
}
if (state[1][0] as Float) * ts >= tau {
for i in 0..N {
Self::filter_initial_state(out[i], b, a, &mut state[i]);
}
}
return;
}
for i in 0..N {
out[i] = Self::filter_step(x[i], b, a, &mut state[i]);
}
}
fn setup(&mut self) {
assert!(self.coeffs.gyr_ts > 0.0);
assert!(self.coeffs.acc_ts > 0.0);
assert!(self.coeffs.mag_ts > 0.0);
Self::filter_coeffs(
self.params.tau_acc,
self.coeffs.acc_ts,
&mut self.coeffs.acc_lp_b,
&mut self.coeffs.acc_lp_a,
);
self.coeffs.k_mag = Self::gain_from_tau(self.params.tau_mag, self.coeffs.mag_ts);
self.coeffs.bias_p0 = square(self.params.bias_sigma_init * 100.0);
self.coeffs.bias_v =
square(0.1 * 100.0) * self.coeffs.acc_ts / self.params.bias_forgetting_time;
#[cfg(feature = "motion-bias-estimation")]
{
let p_motion = square(self.params.bias_sigma_motion * 100.0);
self.coeffs.bias_motion_w = square(p_motion) / self.coeffs.bias_v + p_motion;
self.coeffs.bias_vertical_w =
self.coeffs.bias_motion_w / self.params.bias_vertical_forgetting_factor.max(1e-10);
}
let p_rest = square(self.params.bias_sigma_rest * 100.0);
self.coeffs.bias_rest_w = square(p_rest) / self.coeffs.bias_v + p_rest;
Self::filter_coeffs(
self.params.rest_filter_tau,
self.coeffs.gyr_ts,
&mut self.coeffs.rest_gyr_lp_b,
&mut self.coeffs.rest_gyr_lp_a,
);
Self::filter_coeffs(
self.params.rest_filter_tau,
self.coeffs.acc_ts,
&mut self.coeffs.rest_acc_lp_b,
&mut self.coeffs.rest_acc_lp_a,
);
self.coeffs.k_mag_ref = Self::gain_from_tau(self.params.mag_ref_tau, self.coeffs.mag_ts);
if self.params.mag_current_tau > 0.0 {
Self::filter_coeffs(
self.params.mag_current_tau,
self.coeffs.mag_ts,
&mut self.coeffs.mag_norm_dip_lp_b,
&mut self.coeffs.mag_norm_dip_lp_a,
);
} else {
self.coeffs.mag_norm_dip_lp_b = [f64::NAN; 3];
self.coeffs.mag_norm_dip_lp_a = [f64::NAN; 2];
}
self.reset_state();
}
}
#[cfg(test)]
mod tests {
use crate::{Params, Quaternion, VQF};
#[test]
fn basic_parity() {
for mode in 0..=5 {
let params = match mode {
0 => Default::default(),
1 => Params {
mag_dist_rejection_enabled: false,
..Default::default()
},
2 => Params {
rest_bias_est_enabled: false,
..Default::default()
},
3 => Params {
motion_bias_est_enabled: false,
..Default::default()
},
4 => Params {
rest_bias_est_enabled: false,
motion_bias_est_enabled: false,
..Default::default()
},
5 => Params {
mag_dist_rejection_enabled: false,
rest_bias_est_enabled: false,
motion_bias_est_enabled: false,
..Default::default()
},
_ => panic!(),
};
let expected: Quaternion = match mode {
0 => [0.499988, 0.499988, 0.500012, 0.500012].into(),
1 => [0.5, 0.5, 0.5, 0.5].into(),
2 => [0.451372, 0.453052, 0.543672, 0.543533].into(),
3 => [0.499988, 0.499988, 0.500012, 0.500012].into(),
4 => [0.424513, 0.454375, 0.555264, 0.55228].into(),
5 => [0.44869, 0.478654, 0.534476, 0.532825].into(),
_ => panic!(),
};
let mut vqf = VQF::new(0.01, None, None, Some(params));
let gyr = [0.01; 3];
let acc = [0.0, 9.8, 0.0];
let mag = [0.5, 0.8, 0.0];
for _ in 0..10000 {
vqf.update(gyr, acc, Some(mag))
}
let quat = vqf.quat_9d();
assert!((quat.0 - expected.0).abs() < 1e-6);
assert!((quat.1 - expected.1).abs() < 1e-6);
assert!((quat.2 - expected.2).abs() < 1e-6);
assert!((quat.3 - expected.3).abs() < 1e-6);
}
}
#[allow(clippy::approx_constant)]
#[allow(non_snake_case)]
mod wigwagwent_tests {
use crate::{Params, VQF};
#[test]
fn single_same_3D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
vqf.update_gyr(gyr);
let quat = vqf.quat_3d();
assert!((quat.0 - 1.0).abs() < 1e-6);
assert!((quat.1 - 0.000105).abs() < 1e-6);
assert!((quat.2 - 0.000105).abs() < 1e-6);
assert!((quat.3 - 0.000105).abs() < 1e-6);
}
#[test]
fn single_x_3D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.25, 0.0, 0.0];
vqf.update_gyr(gyr);
let quat = vqf.quat_3d();
assert!((quat.0 - 0.9999999).abs() < 1e-6);
assert!((quat.1 - 0.00125).abs() < 1e-6);
assert!((quat.2 - 0.0).abs() < 1e-6);
assert!((quat.3 - 0.0).abs() < 1e-6);
}
#[test]
fn single_y_3D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.0, 0.25, 0.0];
vqf.update_gyr(gyr);
let quat = vqf.quat_3d();
assert!((quat.0 - 0.9999999).abs() < 1e-6);
assert!((quat.1 - 0.0).abs() < 1e-6);
assert!((quat.2 - 0.00125).abs() < 1e-6);
assert!((quat.3 - 0.0).abs() < 1e-6);
}
#[test]
fn single_z_3D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.0, 0.0, 0.25];
vqf.update_gyr(gyr);
let quat = vqf.quat_3d();
assert!((quat.0 - 0.9999999).abs() < 1e-6);
assert!((quat.1 - 0.0).abs() < 1e-6);
assert!((quat.2 - 0.0).abs() < 1e-6);
assert!((quat.3 - 0.00125).abs() < 1e-6);
}
#[test]
fn single_different_3D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.054, 0.012, -0.9];
vqf.update_gyr(gyr);
let quat = vqf.quat_3d();
assert!((quat.0 - 0.99999).abs() < 1e-6);
assert!((quat.1 - 0.000269999).abs() < 1e-6);
assert!((quat.2 - 5.99998e-5).abs() < 1e-6);
assert!((quat.3 - -0.00449998).abs() < 1e-6);
}
#[test]
fn many_same_3D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
for _ in 0..10_000 {
vqf.update_gyr(gyr);
}
let quat = vqf.quat_3d();
assert!((quat.0 - -0.245327).abs() < 1e-6); assert!((quat.1 - 0.559707).abs() < 1e-6);
assert!((quat.2 - 0.559707).abs() < 1e-6);
assert!((quat.3 - 0.559707).abs() < 1e-6);
}
#[test]
fn many_different_3D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.054, 0.012, -0.09];
for _ in 0..10_000 {
vqf.update_gyr(gyr);
}
let quat = vqf.quat_3d();
assert!((quat.0 - 0.539342).abs() < 1e-6); assert!((quat.1 - -0.430446).abs() < 1e-6);
assert!((quat.2 - -0.0956546).abs() < 1e-6);
assert!((quat.3 - 0.71741).abs() < 1e-6);
}
#[test]
fn single_same_6D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [5.663806, 5.663806, 5.663806];
vqf.update_gyr(gyr);
vqf.update_acc(acc);
let quat = vqf.quat_6d();
assert!((quat.0 - 0.888074).abs() < 1e-6);
assert!((quat.1 - 0.325117).abs() < 1e-6);
assert!((quat.2 - -0.324998).abs() < 1e-6);
assert!((quat.3 - 0.00016151).abs() < 1e-6);
}
#[test]
fn single_x_6D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [9.81, 0.0, 0.0];
vqf.update(gyr, acc, None);
let quat = vqf.quat_6d();
assert!((quat.0 - 0.707107).abs() < 1e-6);
assert!((quat.1 - 0.000148508).abs() < 1e-6);
assert!((quat.2 - -0.707107).abs() < 1e-6);
assert!((quat.3 - 0.000148508).abs() < 1e-6);
}
#[test]
fn single_y_6D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [0.0, 9.81, 0.0];
vqf.update(gyr, acc, None);
let quat = vqf.quat_6d();
assert!((quat.0 - 0.707107).abs() < 1e-6);
assert!((quat.1 - 0.707107).abs() < 1e-6);
assert!((quat.2 - 0.000148477).abs() < 1e-6);
assert!((quat.3 - 0.000148477).abs() < 1e-6);
}
#[test]
fn single_z_6D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [0.0, 0.0, 9.81];
vqf.update(gyr, acc, None);
let quat = vqf.quat_6d();
assert!((quat.0 - 1.0).abs() < 1e-6);
assert!((quat.1 - -1.72732e-20).abs() < 1e-6);
assert!((quat.2 - -4.06576e-20).abs() < 1e-6);
assert!((quat.3 - 0.000105).abs() < 1e-6);
}
#[test]
fn single_different_6D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [4.5, 6.7, 3.2];
vqf.update(gyr, acc, None);
let quat = vqf.quat_6d();
assert!((quat.0 - 0.827216).abs() < 1e-6);
assert!((quat.1 - 0.466506).abs() < 1e-6);
assert!((quat.2 - -0.313187).abs() < 1e-6);
assert!((quat.3 - 0.000168725).abs() < 1e-6);
}
#[test]
fn many_same_6D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [5.663806, 5.663806, 5.663806];
for _ in 0..10_000 {
vqf.update(gyr, acc, None);
}
let quat = vqf.quat_6d();
assert!((quat.0 - 0.887649).abs() < 1e-6); assert!((quat.1 - 0.334951).abs() < 1e-6); assert!((quat.2 - -0.314853).abs() < 1e-6); assert!((quat.3 - 0.0274545).abs() < 1e-6);
}
#[test]
fn many_different_6D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [4.5, 6.7, 3.2];
for _ in 0..10_000 {
vqf.update(gyr, acc, None);
}
let quat = vqf.quat_6d();
assert!((quat.0 - 0.826852).abs() < 1e-6); assert!((quat.1 - 0.475521).abs() < 1e-6); assert!((quat.2 - -0.299322).abs() < 1e-6); assert!((quat.3 - 0.0245133).abs() < 1e-6);
}
#[test]
fn single_same_9D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [5.663806, 5.663806, 5.663806];
let mag = [10.0, 10.0, 10.0];
vqf.update_gyr(gyr);
vqf.update_acc(acc);
vqf.update_mag(mag);
let quat = vqf.quat_9d();
assert!((quat.0 - 0.86428).abs() < 1e-6);
assert!((quat.1 - 0.391089).abs() < 1e-6);
assert!((quat.2 - -0.241608).abs() < 1e-6);
assert!((quat.3 - 0.204195).abs() < 1e-6);
}
#[test]
fn single_x_9D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [5.663806, 5.663806, 5.663806];
let mag = [10.0, 0.0, 0.0];
vqf.update(gyr, acc, Some(mag));
let quat = vqf.quat_9d();
assert!((quat.0 - 0.540625).abs() < 1e-6);
assert!((quat.1 - 0.455768).abs() < 1e-6);
assert!((quat.2 - 0.060003).abs() < 1e-6);
assert!((quat.3 - 0.704556).abs() < 1e-6);
}
#[test]
fn single_y_9D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [5.663806, 5.663806, 5.663806];
let mag = [0.0, 10.0, 0.0];
vqf.update(gyr, acc, Some(mag));
let quat = vqf.quat_9d();
assert!((quat.0 - 0.880476).abs() < 1e-6);
assert!((quat.1 - 0.279848).abs() < 1e-6);
assert!((quat.2 - -0.364705).abs() < 1e-6);
assert!((quat.3 - -0.115917).abs() < 1e-6);
}
#[test]
fn single_z_9D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [5.663806, 5.663806, 5.663806];
let mag = [0.0, 0.0, 10.0];
vqf.update(gyr, acc, Some(mag));
let quat = vqf.quat_9d();
assert!((quat.0 - 0.339851).abs() < 1e-6);
assert!((quat.1 - -0.17592).abs() < 1e-6);
assert!((quat.2 - -0.424708).abs() < 1e-6);
assert!((quat.3 - -0.820473).abs() < 1e-6);
}
#[test]
fn single_different_9D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [5.663806, 5.663806, 5.663806];
let mag = [3.54, 6.32, -2.34];
vqf.update(gyr, acc, Some(mag));
let quat = vqf.quat_9d();
assert!((quat.0 - 0.864117).abs() < 1e-6);
assert!((quat.1 - 0.391281).abs() < 1e-6);
assert!((quat.2 - -0.241297).abs() < 1e-6);
assert!((quat.3 - 0.204882).abs() < 1e-6);
}
#[test]
fn many_same_9D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [5.663806, 5.663806, 5.663806];
let mag = [10.0, 10.0, 10.0];
for _ in 0..10_000 {
vqf.update(gyr, acc, Some(mag));
}
let quat = vqf.quat_9d();
assert!((quat.0 - 0.338005).abs() < 1e-6); assert!((quat.1 - -0.176875).abs() < 1e-6); assert!((quat.2 - -0.424311).abs() < 1e-6); assert!((quat.3 - -0.821236).abs() < 1e-6);
}
#[test]
fn many_different_9D_quat() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.021, 0.021, 0.021];
let acc = [5.663806, 5.663806, 5.663806];
let mag = [3.54, 6.32, -2.34];
for _ in 0..10_000 {
vqf.update(gyr, acc, Some(mag));
}
let quat = vqf.quat_9d();
assert!((quat.0 - 0.864111).abs() < 1e-6); assert!((quat.1 - 0.391288).abs() < 1e-6); assert!((quat.2 - -0.241286).abs() < 1e-6); assert!((quat.3 - 0.204906).abs() < 1e-6);
}
#[test]
fn run_vqf_cpp_example() {
let mut vqf = VQF::new(0.01, None, None, None);
let gyr = [0.01745329; 3];
let acc = [5.663806; 3];
for _ in 0..6000 {
vqf.update(gyr, acc, None);
}
let quat = vqf.quat_6d();
assert!((quat.0 - 0.887781).abs() < 1e-6);
assert!((quat.1 - 0.333302).abs() < 1e-6);
assert!((quat.2 - -0.316598).abs() < 1e-6);
assert!((quat.3 - 0.0228175).abs() < 1e-6);
}
#[test]
fn run_vqf_cpp_example_basic() {
let mut vqf = VQF::new(0.01, None, None, Some(Params {
rest_bias_est_enabled: false,
motion_bias_est_enabled: false,
mag_dist_rejection_enabled: false,
..Default::default()
}));
let gyr = [0.01745329; 3];
let acc = [5.663806; 3];
for _ in 0..6000 {
vqf.update(gyr, acc, None);
}
let quat = vqf.quat_6d();
assert!((quat.0 - 0.547223).abs() < 1e-6);
assert!((quat.1 - 0.456312).abs() < 1e-6);
assert!((quat.2 - 0.055717).abs() < 1e-6);
assert!((quat.3 - 0.699444).abs() < 1e-6);
}
}
}