1#![deny(missing_docs)]
38#![deny(unsafe_code)]
39#![cfg_attr(not(feature = "std"), no_std)]
40
41use core::ops::{AddAssign, SubAssign};
42use nalgebra::{
43 base::allocator::Allocator, DefaultAllocator, Dim, Matrix2, Matrix3, MatrixMN, MatrixN, Point3,
44 UnitQuaternion, Vector2, Vector3, VectorN, U1, U18, U2, U3, U5,
45};
46
47#[derive(Copy, Clone, Debug)]
49pub enum Error {
50 InversionError,
58}
59
60pub type Result<T> = core::result::Result<T, Error>;
62#[cfg(feature = "std")]
64pub type Delta = std::time::Duration;
65#[cfg(not(feature = "std"))]
67pub type Delta = f32;
68
69#[derive(Copy, Clone, Default, Debug)]
71pub struct Builder {
72 var_acc: Vector3<f32>,
73 var_rot: Vector3<f32>,
74 var_acc_bias: Vector3<f32>,
75 var_rot_bias: Vector3<f32>,
76 process_covariance: f32,
77}
78
79impl Builder {
80 pub fn new() -> Self {
82 Builder::default()
83 }
84
85 pub fn acceleration_variance(mut self, var: f32) -> Self {
89 self.var_acc = Vector3::from_element(var.powi(2));
90 self
91 }
92
93 pub fn acceleration_variance_from_vec(mut self, var: Vector3<f32>) -> Self {
97 self.var_acc = var.map(|e| e.powi(2));
98 self
99 }
100
101 pub fn rotation_variance(mut self, var: f32) -> Self {
105 self.var_rot = Vector3::from_element(var.powi(2));
106 self
107 }
108
109 pub fn rotation_variance_from_vec(mut self, var: Vector3<f32>) -> Self {
113 self.var_rot = var.map(|e| e.powi(2));
114 self
115 }
116
117 pub fn acceleration_bias(mut self, bias: f32) -> Self {
121 self.var_acc_bias = Vector3::from_element(bias.powi(2));
122 self
123 }
124
125 pub fn acceleration_bias_from_vec(mut self, bias: Vector3<f32>) -> Self {
129 self.var_acc_bias = bias.map(|e| e.powi(2));
130 self
131 }
132
133 pub fn rotation_bias(mut self, bias: f32) -> Self {
137 self.var_rot_bias = Vector3::from_element(bias.powi(2));
138 self
139 }
140
141 pub fn rotation_bias_from_vec(mut self, bias: Vector3<f32>) -> Self {
145 self.var_rot_bias = bias.map(|e| e.powi(2));
146 self
147 }
148
149 pub fn initial_covariance(mut self, covar: f32) -> Self {
155 self.process_covariance = covar;
156 self
157 }
158
159 pub fn build(self) -> ESKF {
161 ESKF {
162 position: Point3::origin(),
163 velocity: Vector3::zeros(),
164 orientation: UnitQuaternion::identity(),
165 accel_bias: Vector3::zeros(),
166 rot_bias: Vector3::zeros(),
167 gravity: Vector3::new(0f32, 0f32, 9.81),
168 covariance: MatrixN::<f32, U18>::identity() * self.process_covariance,
169 var_acc: self.var_acc,
170 var_rot: self.var_rot,
171 var_acc_bias: self.var_acc_bias,
172 var_rot_bias: self.var_rot_bias,
173 }
174 }
175}
176
177#[derive(Copy, Clone, Debug)]
191pub struct ESKF {
192 pub position: Point3<f32>,
194 pub velocity: Vector3<f32>,
196 pub orientation: UnitQuaternion<f32>,
198 pub accel_bias: Vector3<f32>,
200 pub rot_bias: Vector3<f32>,
202 pub gravity: Vector3<f32>,
204 covariance: MatrixN<f32, U18>,
206 var_acc: Vector3<f32>,
208 var_rot: Vector3<f32>,
210 var_acc_bias: Vector3<f32>,
212 var_rot_bias: Vector3<f32>,
214}
215
216impl ESKF {
217 pub fn variance_from_element(var: f32) -> Matrix3<f32> {
222 Matrix3::from_diagonal_element(var)
223 }
224
225 pub fn variance_from_diagonal(var: Vector3<f32>) -> Matrix3<f32> {
230 Matrix3::from_diagonal(&var)
231 }
232
233 fn uncertainty3(&self, start: usize) -> Vector3<f32> {
235 self.covariance
236 .diagonal()
237 .fixed_slice::<U3, U1>(start, 0)
238 .map(|var| var.sqrt())
239 }
240
241 pub fn position_uncertainty(&self) -> Vector3<f32> {
243 self.uncertainty3(0)
244 }
245
246 pub fn velocity_uncertainty(&self) -> Vector3<f32> {
248 self.uncertainty3(3)
249 }
250
251 pub fn orientation_uncertainty(&self) -> Vector3<f32> {
253 self.uncertainty3(6)
254 }
255
256 pub fn predict(&mut self, acceleration: Vector3<f32>, rotation: Vector3<f32>, delta: Delta) {
259 #[cfg(feature = "std")]
260 let delta_t = delta.as_secs_f32();
261 #[cfg(not(feature = "std"))]
262 let delta_t = delta;
263
264 let rot_acc_grav = self
265 .orientation
266 .transform_vector(&(acceleration - self.accel_bias))
267 + self.gravity;
268 let norm_rot = UnitQuaternion::from_scaled_axis((rotation - self.rot_bias) * delta_t);
269 let orient_mat = self.orientation.to_rotation_matrix().into_inner();
270 self.position += self.velocity * delta_t + 0.5 * rot_acc_grav * delta_t.powi(2);
272 self.velocity += rot_acc_grav * delta_t;
273 self.orientation *= norm_rot;
274
275 let ident_delta = Matrix3::<f32>::identity() * delta_t;
278 let mut error_jacobian = MatrixN::<f32, U18>::identity();
279 error_jacobian
280 .fixed_slice_mut::<U3, U3>(0, 3)
281 .copy_from(&ident_delta);
282 error_jacobian
283 .fixed_slice_mut::<U3, U3>(3, 6)
284 .copy_from(&(-orient_mat * skew(&(acceleration - self.accel_bias)) * delta_t));
285 error_jacobian
286 .fixed_slice_mut::<U3, U3>(3, 9)
287 .copy_from(&(-orient_mat * delta_t));
288 error_jacobian
289 .fixed_slice_mut::<U3, U3>(3, 15)
290 .copy_from(&ident_delta);
291 error_jacobian
292 .fixed_slice_mut::<U3, U3>(6, 6)
293 .copy_from(&norm_rot.to_rotation_matrix().into_inner().transpose());
294 error_jacobian
295 .fixed_slice_mut::<U3, U3>(6, 12)
296 .copy_from(&-ident_delta);
297 self.covariance = error_jacobian * self.covariance * error_jacobian.transpose();
298 let mut diagonal = self.covariance.diagonal();
300 diagonal
301 .fixed_slice_mut::<U3, U1>(3, 0)
302 .add_assign(self.var_acc * delta_t.powi(2));
303 diagonal
304 .fixed_slice_mut::<U3, U1>(6, 0)
305 .add_assign(self.var_rot * delta_t.powi(2));
306 diagonal
307 .fixed_slice_mut::<U3, U1>(9, 0)
308 .add_assign(self.var_acc_bias * delta_t);
309 diagonal
310 .fixed_slice_mut::<U3, U1>(12, 0)
311 .add_assign(self.var_rot_bias * delta_t);
312 self.covariance.set_diagonal(&diagonal);
313 }
314
315 pub fn update<R: Dim>(
323 &mut self,
324 jacobian: MatrixMN<f32, R, U18>,
325 difference: VectorN<f32, R>,
326 variance: MatrixN<f32, R>,
327 ) -> Result<()>
328 where
329 DefaultAllocator: Allocator<f32, R>
330 + Allocator<f32, R, R>
331 + Allocator<f32, R, U18>
332 + Allocator<f32, U18, R>,
333 {
334 let kalman_gain = self.covariance
336 * &jacobian.transpose()
337 * (&jacobian * self.covariance * &jacobian.transpose() + &variance)
338 .try_inverse()
339 .ok_or(Error::InversionError)?;
340 let error_state = &kalman_gain * difference;
341 if cfg!(feature = "cov-symmetric") {
343 self.covariance -= &kalman_gain
344 * (&jacobian * self.covariance * &jacobian.transpose() + &variance)
345 * &kalman_gain.transpose();
346 } else if cfg!(feature = "cov-joseph") {
347 let step1 = MatrixN::<f32, U18>::identity() - &kalman_gain * &jacobian;
348 let step2 = &kalman_gain * &variance * &kalman_gain.transpose();
349 self.covariance = step1 * self.covariance * step1.transpose() + step2;
350 } else {
351 self.covariance =
352 (MatrixN::<f32, U18>::identity() - &kalman_gain * &jacobian) * self.covariance;
353 }
354 self.position += error_state.fixed_slice::<U3, U1>(0, 0);
356 self.velocity += error_state.fixed_slice::<U3, U1>(3, 0);
357 self.orientation *=
358 UnitQuaternion::from_scaled_axis(error_state.fixed_slice::<U3, U1>(6, 0));
359 self.accel_bias += error_state.fixed_slice::<U3, U1>(9, 0);
360 self.rot_bias += error_state.fixed_slice::<U3, U1>(12, 0);
361 self.gravity += error_state.fixed_slice::<U3, U1>(15, 0);
362 if cfg!(feature = "full-reset") {
367 let mut g = MatrixN::<f32, U18>::identity();
368 g.fixed_slice_mut::<U3, U3>(6, 6)
369 .sub_assign(0.5 * skew(&error_state.fixed_slice::<U3, U1>(6, 0).clone_owned()));
370 self.covariance = g * self.covariance * g.transpose();
371 }
372 Ok(())
373 }
374
375 pub fn observe_position_velocity2d(
381 &mut self,
382 position: Point3<f32>,
383 position_var: Matrix3<f32>,
384 velocity: Vector2<f32>,
385 velocity_var: Matrix2<f32>,
386 ) -> Result<()> {
387 let mut jacobian = MatrixMN::<f32, U5, U18>::zeros();
388 jacobian
389 .fixed_slice_mut::<U5, U5>(0, 0)
390 .fill_with_identity();
391
392 let mut diff = VectorN::<f32, U5>::zeros();
393 diff.fixed_slice_mut::<U3, U1>(0, 0)
394 .copy_from(&(position - self.position));
395 diff.fixed_slice_mut::<U2, U1>(3, 0)
396 .copy_from(&(velocity - self.velocity.xy()));
397
398 let mut var = MatrixN::<f32, U5>::zeros();
399 var.fixed_slice_mut::<U3, U3>(0, 0).copy_from(&position_var);
400 var.fixed_slice_mut::<U2, U2>(3, 3).copy_from(&velocity_var);
401
402 self.update(jacobian, diff, var)
403 }
404
405 pub fn observe_position(
407 &mut self,
408 measurement: Point3<f32>,
409 variance: Matrix3<f32>,
410 ) -> Result<()> {
411 let mut jacobian = MatrixMN::<f32, U3, U18>::zeros();
412 jacobian
413 .fixed_slice_mut::<U3, U3>(0, 0)
414 .fill_with_identity();
415 let diff = measurement - self.position;
416 self.update(jacobian, diff, variance)
417 }
418
419 pub fn observe_height(&mut self, measured: f32, variance: f32) -> Result<()> {
421 let mut jacobian = MatrixMN::<f32, U1, U18>::zeros();
422 jacobian
423 .fixed_slice_mut::<U1, U1>(0, 2)
424 .fill_with_identity();
425 let diff = VectorN::<f32, U1>::new(measured - self.position.z);
426 let var = MatrixMN::<f32, U1, U1>::new(variance);
427 self.update(jacobian, diff, var)
428 }
429
430 pub fn observe_velocity(
437 &mut self,
438 measurement: Vector3<f32>,
439 variance: Matrix3<f32>,
440 ) -> Result<()> {
441 let mut jacobian = MatrixMN::<f32, U3, U18>::zeros();
442 jacobian
443 .fixed_slice_mut::<U3, U3>(0, 3)
444 .fill_with_identity();
445 let diff = measurement - self.velocity;
446 self.update(jacobian, diff, variance)
447 }
448
449 pub fn observe_velocity2d(
456 &mut self,
457 measurement: Vector2<f32>,
458 variance: Matrix2<f32>,
459 ) -> Result<()> {
460 let mut jacobian = MatrixMN::<f32, U2, U18>::zeros();
461 jacobian
462 .fixed_slice_mut::<U2, U2>(0, 3)
463 .fill_with_identity();
464 let diff = Vector2::new(
465 measurement.x - self.velocity.x,
466 measurement.y - self.velocity.y,
467 );
468 self.update(jacobian, diff, variance)
469 }
470
471 pub fn observe_orientation(
473 &mut self,
474 measurement: UnitQuaternion<f32>,
475 variance: Matrix3<f32>,
476 ) -> Result<()> {
477 let mut jacobian = MatrixMN::<f32, U3, U18>::zeros();
478 jacobian
479 .fixed_slice_mut::<U3, U3>(0, 6)
480 .fill_with_identity();
481 let diff = measurement * self.orientation;
482 self.update(jacobian, diff.scaled_axis(), variance)
483 }
484}
485
486#[rustfmt::skip]
488fn skew(v: &Vector3<f32>) -> Matrix3<f32> {
489 Matrix3::new(0., -v.z, v.y,
490 v.z, 0., -v.x,
491 -v.y, v.x, 0.)
492}
493
494#[cfg(test)]
495mod test {
496 use super::Builder;
497 use approx::assert_relative_eq;
498 use nalgebra::{Point3, UnitQuaternion, Vector3};
499 use std::f32::consts::FRAC_PI_2;
500 use std::time::Duration;
501
502 #[test]
503 fn creation() {
504 let filter = Builder::new().build();
505 assert_relative_eq!(filter.position, Point3::origin());
506 assert_relative_eq!(filter.velocity, Vector3::zeros());
507 }
508
509 #[test]
510 fn linear_motion() {
511 let mut filter = Builder::new().build();
512 filter.predict(
514 Vector3::new(1.0, 0.0, -9.81),
515 Vector3::zeros(),
516 Duration::from_millis(1000),
517 );
518 assert_relative_eq!(filter.position, Point3::new(0.5, 0.0, 0.0));
519 assert_relative_eq!(filter.velocity, Vector3::new(1.0, 0.0, 0.0));
520 assert_relative_eq!(filter.orientation, UnitQuaternion::identity());
522 filter.predict(
524 Vector3::new(0.0, 0.0, -9.81),
525 Vector3::zeros(),
526 Duration::from_millis(500),
527 );
528 assert_relative_eq!(filter.position, Point3::new(1.0, 0.0, 0.0));
529 assert_relative_eq!(filter.velocity, Vector3::new(1.0, 0.0, 0.0));
530 assert_relative_eq!(filter.orientation, UnitQuaternion::identity());
531 filter.predict(
532 Vector3::new(-1.0, -1.0, -9.81),
533 Vector3::zeros(),
534 Duration::from_millis(1000),
535 );
536 assert_relative_eq!(filter.position, Point3::new(1.5, -0.5, 0.0));
537 assert_relative_eq!(filter.velocity, Vector3::new(0.0, -1.0, 0.0));
538 assert_relative_eq!(filter.orientation, UnitQuaternion::identity());
539 }
540
541 #[test]
542 fn rotational_motion() {
543 let mut filter = Builder::new().build();
544 filter.predict(
546 Vector3::zeros(),
547 Vector3::new(FRAC_PI_2, 0.0, 0.0),
548 Duration::from_millis(1000),
549 );
550 assert_relative_eq!(
551 filter.orientation,
552 UnitQuaternion::from_euler_angles(FRAC_PI_2, 0.0, 0.0)
553 );
554 filter.predict(
555 Vector3::zeros(),
556 Vector3::new(-FRAC_PI_2, 0.0, 0.0),
557 Duration::from_millis(1000),
558 );
559 assert_relative_eq!(
560 filter.orientation,
561 UnitQuaternion::from_euler_angles(0.0, 0.0, 0.0)
562 );
563 let mut filter = Builder::new().build();
566 filter.predict(
567 Vector3::zeros(),
568 Vector3::new(0.0, -FRAC_PI_2, 0.0),
569 Duration::from_millis(1000),
570 );
571 assert_relative_eq!(
572 filter.orientation,
573 UnitQuaternion::from_euler_angles(0.0, -FRAC_PI_2, 0.0)
574 );
575 }
576}