Skip to main content

mpu6050_dmp/
gyro.rs

1//! Gyroscope Data Processing
2//!
3//! The MPU6050's gyroscope measures angular velocity (rotation speed)
4//! around three axes:
5//! - X: Roll rate (side-to-side rotation)
6//! - Y: Pitch rate (forward/backward rotation)
7//! - Z: Yaw rate (horizontal rotation)
8
9/// Raw gyroscope readings from the sensor.
10/// Values represent rotation rate in ADC units.
11#[derive(Copy, Clone, Debug, PartialEq, Eq)]
12#[cfg_attr(feature = "defmt-03", derive(defmt::Format))]
13#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
14#[cfg_attr(feature = "postcard-experimental", derive(postcard::experimental::max_size::MaxSize))]
15pub struct Gyro {
16    pub(crate) x: i16,
17    pub(crate) y: i16,
18    pub(crate) z: i16,
19}
20
21impl Gyro {
22    pub const fn new(x: i16, y: i16, z: i16) -> Self {
23        Self { x, y, z }
24    }
25
26    pub const fn from_bytes(data: [u8; 6]) -> Self {
27        let x = [data[0], data[1]];
28        let y = [data[2], data[3]];
29        let z = [data[4], data[5]];
30        Self {
31            x: i16::from_be_bytes(x),
32            y: i16::from_be_bytes(y),
33            z: i16::from_be_bytes(z),
34        }
35    }
36
37    pub const fn to_bytes(&self) -> [u8; 6] {
38        let x = self.x.to_be_bytes();
39        let y = self.y.to_be_bytes();
40        let z = self.z.to_be_bytes();
41        [x[0], x[1], y[0], y[1], z[0], z[1]]
42    }
43
44    pub const fn x(&self) -> i16 {
45        self.x
46    }
47
48    pub const fn y(&self) -> i16 {
49        self.y
50    }
51
52    pub const fn z(&self) -> i16 {
53        self.z
54    }
55
56    pub const fn scaled(&self, scale: GyroFullScale) -> GyroF32 {
57        GyroF32 {
58            x: scale.scale_value(self.x),
59            y: scale.scale_value(self.y),
60            z: scale.scale_value(self.z),
61        }
62    }
63}
64
65impl From<Gyro> for [i16; 3] {
66    fn from(value: Gyro) -> Self {
67        [value.x, value.y, value.z]
68    }
69}
70
71/// Full-scale range settings for the gyroscope.
72///
73/// Each setting defines the maximum measurable rotation rate:
74/// - Deg250: ±250 degrees/second
75/// - Deg500: ±500 degrees/second
76/// - Deg1000: ±1000 degrees/second
77/// - Deg2000: ±2000 degrees/second
78#[derive(Copy, Clone, Debug)]
79#[cfg_attr(feature = "defmt-03", derive(defmt::Format))]
80#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
81#[cfg_attr(feature = "postcard-experimental", derive(postcard::experimental::max_size::MaxSize))]
82pub enum GyroFullScale {
83    /// ±250°/s range (131 LSB/°/s)
84    Deg250 = 0,
85    /// ±500°/s range (65.5 LSB/°/s)
86    Deg500 = 1,
87    /// ±1000°/s range (32.8 LSB/°/s)
88    Deg1000 = 2,
89    /// ±2000°/s range (16.4 LSB/°/s)
90    Deg2000 = 3,
91}
92
93impl GyroFullScale {
94    pub const fn scale(self) -> f32 {
95        match self {
96            Self::Deg250 => 131.0,
97            Self::Deg500 => 65.5,
98            Self::Deg1000 => 32.8,
99            Self::Deg2000 => 16.4,
100        }
101    }
102
103    pub const fn scale_value(self, value: i16) -> f32 {
104        (value as f32) / self.scale()
105    }
106}
107
108/// Gyroscope readings in degrees per second.
109///
110/// After scaling, values represent actual rotation rates:
111/// - Positive: Clockwise rotation
112/// - Negative: Counter-clockwise rotation
113#[derive(Copy, Clone, Debug)]
114#[cfg_attr(feature = "defmt-03", derive(defmt::Format))]
115#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
116#[cfg_attr(feature = "postcard-experimental", derive(postcard::experimental::max_size::MaxSize))]
117pub struct GyroF32 {
118    /// Roll rate (°/s)
119    x: f32,
120    /// Pitch rate (°/s)
121    y: f32,
122    /// Yaw rate (°/s)
123    z: f32,
124}
125
126impl GyroF32 {
127    pub const fn new(x: f32, y: f32, z: f32) -> Self {
128        Self { x, y, z }
129    }
130
131    pub const fn x(&self) -> f32 {
132        self.x
133    }
134
135    pub const fn y(&self) -> f32 {
136        self.y
137    }
138
139    pub const fn z(&self) -> f32 {
140        self.z
141    }
142}
143
144impl From<GyroF32> for [f32; 3] {
145    fn from(value: GyroF32) -> Self {
146        [value.x, value.y, value.z]
147    }
148}