11/// Extended Kalman Filter for vehicle state estimation
22/// 7-state: [x, y, ψ, vx, vy, bax, bay]
3-
43use core:: f32:: consts:: PI ;
54
65const N : usize = 7 ; // State dimension
@@ -10,17 +9,17 @@ const N: usize = 7; // State dimension
109#[ derive( Debug , Clone , Copy ) ]
1110pub 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
2625impl 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) ]
253252mod 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