Skip to content

Commit 635157c

Browse files
committed
fixes formatting
1 parent 8911396 commit 635157c

File tree

17 files changed

+512
-415
lines changed

17 files changed

+512
-415
lines changed

drivers/neo6m/src/lib.rs

Lines changed: 18 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,8 @@
11
//! NEO-6M GPS NMEA Parser
22
//!
3-
//! This crate provides a pure Rust parser for NMEA sentences from NEO-6M GPS receivers.
4-
//! It supports GPRMC and GNRMC sentences and provides position, velocity, and time information.
3+
//! This crate provides a pure Rust parser for NMEA sentences from NEO-6M GPS
4+
//! receivers. It supports GPRMC and GNRMC sentences and provides position,
5+
//! velocity, and time information.
56
//!
67
//! # Features
78
//!
@@ -25,7 +26,11 @@
2526
//! if parser.feed_byte(byte) {
2627
//! // New sentence parsed
2728
//! if parser.last_fix().valid {
28-
//! println!("Position: {}, {}", parser.last_fix().lat, parser.last_fix().lon);
29+
//! println!(
30+
//! "Position: {}, {}",
31+
//! parser.last_fix().lat,
32+
//! parser.last_fix().lon
33+
//! );
2934
//! println!("Speed: {:.1} m/s", parser.last_fix().speed);
3035
//! }
3136
//! }
@@ -34,12 +39,11 @@
3439
3540
#![cfg_attr(not(test), no_std)]
3641

42+
// Import libm for no-std floating point operations
43+
use libm::{cos, floor, sin};
3744
#[cfg(feature = "logging")]
3845
use log::warn;
3946

40-
// Import libm for no-std floating point operations
41-
use libm::{cos, sin, floor};
42-
4347
/// GPS coordinate transformations
4448
pub mod transforms {
4549
use libm::{cos, sqrtf};
@@ -258,7 +262,8 @@ impl NmeaParser {
258262
/// Update position-based speed with new timestamp
259263
///
260264
/// Call this from your application's time source when a new fix arrives.
261-
/// This allows position-based speed calculation to work in no_std environments.
265+
/// This allows position-based speed calculation to work in no_std
266+
/// environments.
262267
///
263268
/// # Arguments
264269
///
@@ -372,8 +377,8 @@ impl NmeaParser {
372377
#[cfg(not(any(test, feature = "std")))]
373378
fn parse_rmc(&mut self, _line: &str) {
374379
// no_std: Simplified implementation
375-
// For a full no_std implementation, you would need to add libm dependency for floor()
376-
// and implement manual field parsing without Vec
380+
// For a full no_std implementation, you would need to add libm dependency for
381+
// floor() and implement manual field parsing without Vec
377382
self.last_fix.valid = false;
378383
}
379384
}
@@ -426,7 +431,10 @@ mod tests {
426431
// North latitude
427432
assert_eq!(parse_coordinate("3723.2475", "N"), Some(37.387458333333336));
428433
// South latitude
429-
assert_eq!(parse_coordinate("3723.2475", "S"), Some(-37.387458333333336));
434+
assert_eq!(
435+
parse_coordinate("3723.2475", "S"),
436+
Some(-37.387458333333336)
437+
);
430438
// East longitude
431439
assert_eq!(parse_coordinate("12158.3416", "E"), Some(121.97236));
432440
// West longitude

drivers/wt901/src/lib.rs

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414
//! # Example
1515
//!
1616
//! ```no_run
17-
//! use wt901::{Wt901Parser, PacketType};
17+
//! use wt901::{PacketType, Wt901Parser};
1818
//!
1919
//! let mut parser = Wt901Parser::new();
2020
//!
@@ -181,8 +181,10 @@ impl Wt901Parser {
181181

182182
if checksum != self.buffer[10] {
183183
#[cfg(feature = "logging")]
184-
warn!("WT901 checksum failed: expected 0x{:02X}, got 0x{:02X}",
185-
self.buffer[10], checksum);
184+
warn!(
185+
"WT901 checksum failed: expected 0x{:02X}, got 0x{:02X}",
186+
self.buffer[10], checksum
187+
);
186188
return None;
187189
}
188190

framework/src/ekf.rs

Lines changed: 34 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
/// Extended Kalman Filter for vehicle state estimation
22
/// 7-state: [x, y, ψ, vx, vy, bax, bay]
3-
43
use core::f32::consts::PI;
54

65
const N: usize = 7; // State dimension
@@ -10,17 +9,17 @@ const N: usize = 7; // State dimension
109
#[derive(Debug, Clone, Copy)]
1110
pub struct EkfConfig {
1211
// Process noise parameters
13-
pub q_acc: f32, // (m/s²)² - Acceleration process noise
14-
pub q_gyro: f32, // (rad/s)² - Gyro process noise
15-
pub q_bias: f32, // (m/s²)² - Bias evolution noise
12+
pub q_acc: f32, // (m/s²)² - Acceleration process noise
13+
pub q_gyro: f32, // (rad/s)² - Gyro process noise
14+
pub q_bias: f32, // (m/s²)² - Bias evolution noise
1615

1716
// Measurement noise parameters
18-
pub r_pos: f32, // (m)² - GPS position measurement noise
19-
pub r_vel: f32, // (m/s)² - GPS velocity measurement noise
20-
pub r_yaw: f32, // (rad)² - Magnetometer yaw measurement noise
17+
pub r_pos: f32, // (m)² - GPS position measurement noise
18+
pub r_vel: f32, // (m/s)² - GPS velocity measurement noise
19+
pub r_yaw: f32, // (rad)² - Magnetometer yaw measurement noise
2120

2221
// Model parameters
23-
pub min_speed: f32, // m/s - Minimum speed for CTRA model
22+
pub min_speed: f32, // m/s - Minimum speed for CTRA model
2423
}
2524

2625
impl Default for EkfConfig {
@@ -61,38 +60,38 @@ impl Ekf {
6160
config,
6261
}
6362
}
64-
63+
6564
/// Get position (x, y)
6665
pub fn position(&self) -> (f32, f32) {
6766
(self.x[0], self.x[1])
6867
}
69-
68+
7069
/// Get yaw (ψ)
7170
pub fn yaw(&self) -> f32 {
7271
self.x[2]
7372
}
74-
73+
7574
/// Get velocity (vx, vy)
7675
pub fn velocity(&self) -> (f32, f32) {
7776
(self.x[3], self.x[4])
7877
}
79-
78+
8079
/// Get speed (magnitude of velocity)
8180
pub fn speed(&self) -> f32 {
8281
(self.x[3] * self.x[3] + self.x[4] * self.x[4]).sqrt()
8382
}
84-
83+
8584
/// Get accelerometer biases (bax, bay)
8685
#[allow(dead_code)]
8786
pub fn biases(&self) -> (f32, f32) {
8887
(self.x[5], self.x[6])
8988
}
90-
89+
9190
/// Prediction step using CTRA or constant acceleration model
9291
pub fn predict(&mut self, ax_earth: f32, ay_earth: f32, wz: f32, dt: f32) {
9392
let speed = self.speed();
9493
let use_ctra = speed > self.config.min_speed;
95-
94+
9695
// Copy values to avoid borrowing issues
9796
let mut x = self.x[0];
9897
let mut y = self.x[1];
@@ -101,7 +100,7 @@ impl Ekf {
101100
let mut vy = self.x[4];
102101
let bax = self.x[5];
103102
let bay = self.x[6];
104-
103+
105104
// Predict position
106105
if use_ctra && wz.abs() > 1e-4 {
107106
// CTRA model (Constant Turn Rate and Acceleration)
@@ -114,23 +113,23 @@ impl Ekf {
114113
x += vx * dt + 0.5 * (ax_earth - bax) * dt * dt;
115114
y += vy * dt + 0.5 * (ay_earth - bay) * dt * dt;
116115
}
117-
116+
118117
// Predict yaw
119118
psi += wz * dt;
120119
psi = wrap_angle(psi);
121-
120+
122121
// Predict velocity
123122
vx += (ax_earth - bax) * dt;
124123
vy += (ay_earth - bay) * dt;
125-
124+
126125
// Write back to state
127126
self.x[0] = x;
128127
self.x[1] = y;
129128
self.x[2] = psi;
130129
self.x[3] = vx;
131130
self.x[4] = vy;
132131
// Biases remain constant (self.x[5] and self.x[6] unchanged)
133-
132+
134133
// Update covariance (diagonal approximation)
135134
let qx = 0.25 * self.config.q_acc * dt * dt;
136135
let qv = self.config.q_acc * dt * dt;
@@ -142,7 +141,7 @@ impl Ekf {
142141
self.p[5] += self.config.q_bias * dt + 1e-6;
143142
self.p[6] += self.config.q_bias * dt + 1e-6;
144143
}
145-
144+
146145
/// Update with GPS position measurement
147146
pub fn update_position(&mut self, z_x: f32, z_y: f32) {
148147
// X position update
@@ -172,34 +171,34 @@ impl Ekf {
172171
self.x[4] += k_y * (z_vy - self.x[4]);
173172
self.p[4] *= 1.0 - k_y;
174173
}
175-
174+
176175
/// Update with scalar speed measurement
177176
pub fn update_speed(&mut self, z_speed: f32) {
178177
let r_spd = if z_speed < 0.3 { 0.20 } else { 0.04 }; // Adaptive R
179-
178+
180179
let v_est = self.speed().max(0.05); // Avoid division by zero
181-
180+
182181
// Jacobian H = [vx/v, vy/v]
183182
let h_x = self.x[3] / v_est;
184183
let h_y = self.x[4] / v_est;
185-
184+
186185
// Innovation covariance
187186
let s = h_x * h_x * self.p[3] + h_y * h_y * self.p[4] + r_spd;
188-
187+
189188
// Kalman gains
190189
let k_x = self.p[3] * h_x / s;
191190
let k_y = self.p[4] * h_y / s;
192-
191+
193192
// Innovation
194193
let y = z_speed - v_est;
195-
194+
196195
// Update
197196
self.x[3] += k_x * y;
198197
self.x[4] += k_y * y;
199198
self.p[3] -= k_x * h_x * self.p[3];
200199
self.p[4] -= k_y * h_y * self.p[4];
201200
}
202-
201+
203202
/// Update with IMU yaw measurement (from magnetometer)
204203
pub fn update_yaw(&mut self, z_yaw: f32) {
205204
// Wrap innovation to [-π, π]
@@ -212,24 +211,24 @@ impl Ekf {
212211
self.x[2] = wrap_angle(self.x[2]);
213212
self.p[2] *= 1.0 - k;
214213
}
215-
214+
216215
/// Update accelerometer biases when stationary
217216
pub fn update_bias(&mut self, z_ax: f32, z_ay: f32) {
218217
const R_BIAS: f32 = 0.05 * 0.05; // (0.05 m/s²)²
219-
218+
220219
// BAX update
221220
let s_x = self.p[5] + R_BIAS;
222221
let k_x = self.p[5] / s_x;
223222
self.x[5] += k_x * (z_ax - self.x[5]);
224223
self.p[5] *= 1.0 - k_x;
225-
224+
226225
// BAY update
227226
let s_y = self.p[6] + R_BIAS;
228227
let k_y = self.p[6] / s_y;
229228
self.x[6] += k_y * (z_ay - self.x[6]);
230229
self.p[6] *= 1.0 - k_y;
231230
}
232-
231+
233232
/// Zero-velocity update (ZUPT) - force velocity to zero
234233
pub fn zupt(&mut self) {
235234
self.update_velocity(0.0, 0.0);
@@ -252,14 +251,14 @@ fn wrap_angle(angle: f32) -> f32 {
252251
#[cfg(test)]
253252
mod tests {
254253
use super::*;
255-
254+
256255
#[test]
257256
fn test_ekf_init() {
258257
let ekf = Ekf::new();
259258
assert_eq!(ekf.position(), (0.0, 0.0));
260259
assert_eq!(ekf.speed(), 0.0);
261260
}
262-
261+
263262
#[test]
264263
fn test_wrap_angle() {
265264
assert!((wrap_angle(0.0) - 0.0).abs() < 0.001);

0 commit comments

Comments
 (0)