pub struct MadgwickFilter<T> { /* private fields */ }Expand description
Implementations§
Source§impl<T> MadgwickFilter<T>where
T: Copy + One + Zero + Neg<Output = T> + PartialOrd + Sub<Output = T> + Div<Output = T> + Vector3dMath + QuaternionMath + SqrtMethods + SensorFusionMath,
impl<T> MadgwickFilter<T>where
T: Copy + One + Zero + Neg<Output = T> + PartialOrd + Sub<Output = T> + Div<Output = T> + Vector3dMath + QuaternionMath + SqrtMethods + SensorFusionMath,
Trait Implementations§
Source§impl<T: Clone> Clone for MadgwickFilter<T>
impl<T: Clone> Clone for MadgwickFilter<T>
Source§fn clone(&self) -> MadgwickFilter<T>
fn clone(&self) -> MadgwickFilter<T>
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl<T: Debug> Debug for MadgwickFilter<T>
impl<T: Debug> Debug for MadgwickFilter<T>
Source§impl<T> Default for MadgwickFilter<T>
impl<T> Default for MadgwickFilter<T>
Source§impl<T: PartialEq> PartialEq for MadgwickFilter<T>
impl<T: PartialEq> PartialEq for MadgwickFilter<T>
Source§impl<T> SensorFusion<T> for MadgwickFilter<T>
Madgwick AHRS algorithm, calculates orientation by fusing output from gyroscope and accelerometer.
(No magnetometer is used in this implementation.)
impl<T> SensorFusion<T> for MadgwickFilter<T>
Madgwick AHRS algorithm, calculates orientation by fusing output from gyroscope and accelerometer. (No magnetometer is used in this implementation.)
The orientation is calculated as the integration of the gyroscope measurements summed with the measurement from the accelerometer multiplied by a gain. A low gain gives more weight to the gyroscope more and so is more susceptible to drift. A high gain gives more weight to the accelerometer and so is more susceptible to accelerometer noise, lag, and other accelerometer errors. A gain of zero means that orientation is determined by solely by the gyroscope.
See Sebastian Madgwick’s Phd thesis and also x-io Technologies sensor fusion library.
For computation efficiency this code refactors the code used in many implementations (Arduino, Adafruit, M5 Stack, Reefwing-AHRS), see Madgwick refactoring.
Source§fn fuse_acc_gyro(
&mut self,
acc: Vector3d<T>,
gyro_rps: Vector3d<T>,
delta_t: T,
) -> Quaternion<T>
fn fuse_acc_gyro( &mut self, acc: Vector3d<T>, gyro_rps: Vector3d<T>, delta_t: T, ) -> Quaternion<T>
Fuses accelerometer and gyroscope readings to give the orientation quaternion.
Source§fn fuse_acc_gyro_mag(
&mut self,
acc: Vector3d<T>,
gyro_rps: Vector3d<T>,
mag: Vector3d<T>,
delta_t: T,
) -> Quaternion<T>
fn fuse_acc_gyro_mag( &mut self, acc: Vector3d<T>, gyro_rps: Vector3d<T>, mag: Vector3d<T>, delta_t: T, ) -> Quaternion<T>
Fuses accelerometer, gyroscope, and magnetometer readings to give the orientation quaternion.