Skip to main content

eskf/
lib.rs

1//! # Error State Kalman Filter (ESKF)
2//! An [Error State Kalman Filter](https://arxiv.org/abs/1711.02508) is a navigation filter based
3//! on regular Kalman filters, more specifically [Extended Kalman
4//! Filters](https://en.wikipedia.org/wiki/Extended_Kalman_filter), that model the "error state" of
5//! the system instead of modelling the movement of the system.
6//!
7//! The navigation filter is used to track `position`, `velocity` and `orientation` of an object
8//! which is sensing its state through an [Inertial Measurement Unit
9//! (IMU)](https://en.wikipedia.org/wiki/Inertial_measurement_unit) and some means of observing the
10//! true state of the filter such as GPS, LIDAR or visual odometry.
11//!
12//! ## Usage
13//! ```
14//! use eskf;
15//! use nalgebra::{Vector3, Point3};
16//! use std::time::Duration;
17//!
18//! // Create a default filter, modelling a perfect IMU without drift
19//! let mut filter = eskf::Builder::new().build();
20//! // Read measurements from IMU
21//! let imu_acceleration = Vector3::new(0.0, 0.0, -9.81);
22//! let imu_rotation = Vector3::zeros();
23//! // Tell the filter what we just measured
24//! filter.predict(imu_acceleration, imu_rotation, Duration::from_millis(1000));
25//! // Check the new state of the filter
26//! // filter.position or filter.velocity...
27//! // ...
28//! // After some time we get an observation of the actual state
29//! filter.observe_position(
30//!     Point3::new(0.0, 0.0, 0.0),
31//!     eskf::ESKF::variance_from_element(0.1))
32//!         .expect("Filter update failed");
33//! // Since we have supplied an observation of the actual state of the filter the states have now
34//! // been updated. The uncertainty of the filter is also updated to reflect this new information.
35//! ```
36
37#![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/// Potential errors raised during operations
48#[derive(Copy, Clone, Debug)]
49pub enum Error {
50    /// It is not always [the case that a matrix is
51    /// invertible](https://en.wikipedia.org/wiki/Invertible_matrix) which can lead to errors. It
52    /// is difficult to handle this both for the library and for the users. In the case of the
53    /// [`ESKF`], if this happens, it may be caused by an irregular shaped variance matrix for the
54    /// update step. In such cases, inspect the variance matrix. If this happens irregularly it can
55    /// be a sign that the uncertainty update is not stable, if possible try one of `cov-symmetric`
56    /// or `cov-joseph` features for a more stable update.
57    InversionError,
58}
59
60/// Helper definition to make it easier to work with errors
61pub type Result<T> = core::result::Result<T, Error>;
62/// Time delta as a duration, used when `std` is available
63#[cfg(feature = "std")]
64pub type Delta = std::time::Duration;
65/// Time delta in seconds, used in `no_std` environments
66#[cfg(not(feature = "std"))]
67pub type Delta = f32;
68
69/// Builder for [`ESKF`]
70#[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    /// Create a new `ESKF` builder with which to configure an `ESKF`
81    pub fn new() -> Self {
82        Builder::default()
83    }
84
85    /// Set the acceleration variance of the IMU system being modeled
86    ///
87    /// The variance should be `m/s²`
88    pub fn acceleration_variance(mut self, var: f32) -> Self {
89        self.var_acc = Vector3::from_element(var.powi(2));
90        self
91    }
92
93    /// Set the acceleration variance of the IMU system being modeled
94    ///
95    /// The variance should be a vector in [`m/s²`, 3]
96    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    /// Set the rotation variance of the IMU system being modeled
102    ///
103    /// The variance should be `rad/s`
104    pub fn rotation_variance(mut self, var: f32) -> Self {
105        self.var_rot = Vector3::from_element(var.powi(2));
106        self
107    }
108
109    /// Set the rotation variance of the IMU system being modeled
110    ///
111    /// The variance should a vector in [`rad/s`, 3]
112    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    /// Set the acceleration bias of the IMU system being modeled
118    ///
119    /// The bias should be `m/(s²sqrt(s))`
120    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    /// Set the acceleration bias of the IMU system being modeled
126    ///
127    /// The bias should be a vector in [`m/(s²sqrt(s))`, 3]
128    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    /// Set the rotation bias of the IMU system being modeled
134    ///
135    /// The bias should be `rad/(s sqrt(s))`
136    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    /// Set the rotation bias of the IMU system being modeled
142    ///
143    /// The bias should a vector in [`rad/(s sqrt(s))`, 3]
144    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    /// Set the initial covariance for the process matrix
150    ///
151    /// The covariance value should be a small process value so that the covariance of the filter
152    /// quickly converges to the correct value. Too small values could lead to the filter taking a
153    /// long time to converge and report a lower covariance than what it should.
154    pub fn initial_covariance(mut self, covar: f32) -> Self {
155        self.process_covariance = covar;
156        self
157    }
158
159    /// Convert the builder into a new filter
160    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/// Error State Kalman Filter
178///
179/// The filter works by calling [`predict`](ESKF::predict) and one or more of the
180/// [`observe_`](ESKF::observe_position) methods when data is available. It is expected that
181/// several calls to [`predict`](ESKF::predict) will be in between calls to `observe_`.
182///
183/// The [`predict`](ESKF::predict) step updates the internal state of the filter based on measured
184/// acceleration and rotation coming from an IMU. This step updates the states in the filter based
185/// on kinematic equations while increasing the uncertainty of the filter. When one of the
186/// `observe_` methods are called, the filter updates the internal state based on this observation,
187/// which exposes the error state to the filter, which we can then use to correct the internal
188/// state. The uncertainty of the filter is also updated to reflect the variance of the observation
189/// and the updated state.
190#[derive(Copy, Clone, Debug)]
191pub struct ESKF {
192    /// Estimated position in filter
193    pub position: Point3<f32>,
194    /// Estimated velocity in filter
195    pub velocity: Vector3<f32>,
196    /// Estimated orientation in filter
197    pub orientation: UnitQuaternion<f32>,
198    /// Estimated acceleration bias
199    pub accel_bias: Vector3<f32>,
200    /// Estimated rotation bias
201    pub rot_bias: Vector3<f32>,
202    /// Estimated gravity vector
203    pub gravity: Vector3<f32>,
204    /// Covariance of filter state
205    covariance: MatrixN<f32, U18>,
206    /// Acceleration variance
207    var_acc: Vector3<f32>,
208    /// Rotation variance
209    var_rot: Vector3<f32>,
210    /// Acceleration variance bias
211    var_acc_bias: Vector3<f32>,
212    /// Rotation variance bias
213    var_rot_bias: Vector3<f32>,
214}
215
216impl ESKF {
217    /// Create a symmetric variance matrix based on a single variance element
218    ///
219    /// This helper method can be used when the sensor being modelled has a symmetric variance
220    /// around its three axis. Or if only an estimate of the variance is known.
221    pub fn variance_from_element(var: f32) -> Matrix3<f32> {
222        Matrix3::from_diagonal_element(var)
223    }
224
225    /// Create a symmetric variance matrix based on the diagonal vector
226    ///
227    /// This helper method can be used when the sensor being modelled has a independent variance
228    /// around its three axis.
229    pub fn variance_from_diagonal(var: Vector3<f32>) -> Matrix3<f32> {
230        Matrix3::from_diagonal(&var)
231    }
232
233    /// Internal helper method to extract 3 dimensional uncertainty from the covariance state
234    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    /// Get the uncertainty of the position estimate
242    pub fn position_uncertainty(&self) -> Vector3<f32> {
243        self.uncertainty3(0)
244    }
245
246    /// Get the uncertainty of the velocity estimate
247    pub fn velocity_uncertainty(&self) -> Vector3<f32> {
248        self.uncertainty3(3)
249    }
250
251    /// Get the uncertainty of the orientation estimate
252    pub fn orientation_uncertainty(&self) -> Vector3<f32> {
253        self.uncertainty3(6)
254    }
255
256    /// Update the filter, predicting the new state, based on measured acceleration and rotation
257    /// from an `IMU`
258    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        // Update internal state kinematics
271        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        // Propagate uncertainty, since we have not observed any new information about the state of
276        // the filter we need to update our estimate of the uncertainty of the filer
277        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        // Add noise variance
299        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    /// Update the filter with a generic observation
316    ///
317    /// # Arguments
318    /// - `jacobian` is the measurement Jacobian matrix
319    /// - `difference` is the difference between the measured sensor and the filter's internal
320    /// state
321    /// - `variance` is the uncertainty of the observation
322    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        // Correct filter based on Kalman gain
335        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        // Update the covariance based on the observed filter state
342        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        // Inject error state into nominal
355        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        // Perform full ESKF reset
363        //
364        // Since the orientation error is usually relatively small this step can be skipped, but
365        // the full formulation can lead to better stability of the filter
366        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    /// Observe the position and velocity in the X and Y axis
376    ///
377    /// Most GPS units are capable of observing both position and velocity, by combining these two
378    /// measurements into one update we should be able to reduce the computational complexity. Also
379    /// note that GPS velocity tends to be more precise than position.
380    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    /// Update the filter with an observation of the position
406    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    /// Update the filter with an observation of the height alone
420    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    /// Update the filter with an observation of the velocity
431    ///
432    /// # Note
433    /// If the observation comes from a sensor relative to the filter, e.g. an optical flow sensor
434    /// that turns with the UAV, the sensor values **needs** to be rotated into the same frame as
435    /// the filter, e.g. `filter.orientation.transform_vector(&relative_measurement)`.
436    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    /// Update the filter with an observation of the velocity in only the `[X, Y]` axis
450    ///
451    /// # Note
452    /// If the observation comes from a sensor relative to the filter, e.g. an optical flow sensor
453    /// that turns with the UAV, the sensor values **needs** to be rotated into the same frame as
454    /// the filter, e.g. `filter.orientation.transform_vector(&relative_measurement)`.
455    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    /// Update the filter with an observation of the orientation
472    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/// Create the skew-symmetric matrix from a vector
487#[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        // Some initial motion to move the filter
513        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        // There should be no orientation change from the above motion
521        assert_relative_eq!(filter.orientation, UnitQuaternion::identity());
522        // Acceleration has stopped, but there will still be inertia in the filter
523        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        // Note that this motion is a free fall rotation
545        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        // We reset the filter here so that the following equalities are not affected by existing
564        // motion in the filter
565        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}