linearkalman/lib.rs
1//! This crate implements a standard linear Kalman filter and smoothing for
2//! vectors of arbitrary dimension. Implementation method relies on `rulinalg`
3//! library for linear algebra computations. Most inputs and outputs rely
4//! therefore on (derived) constructs from
5//! [rulinalg](https://athemathmo.github.io/rulinalg/doc/rulinalg/index.html)
6//! library, in particular
7//! [`Vector<f64>`](https://athemathmo.github.io/rulinalg/doc/rulinalg/vector/struct.Vector.html)
8//! and
9//! [`Matrix<f64>`](https://athemathmo.github.io/rulinalg/doc/rulinalg/matrix/struct.Matrix.html)
10//! structs.
11//!
12//! Currently, implementation method assumes that Kalman filter is time-invariant
13//! and is based on the equations detailed below. Notations in the below equations
14//! correspond to annotations in the source code.
15//!
16//! Measurement and state equations:
17//!
18//! * `z_{t} = H_{t} x_{t} + v_{t}` where `v_{t} ~ N(0, R_{t})`
19//! * `x_{t} = F_{t} x_{t-1} + B_{t} u_{t} + w_{t}` where `w_{t} ~ N(0, Q_{t})`
20//!
21//! Kalman filter equations:
22//!
23//! * `P_{t|t-1} = F_{t} P_{t-1|t-1} F'_{t} + Q_{t}`
24//! * `x_{t|t-1} = F_{t} x_{t-1|t-1} + B_{t} u_{t}`
25//! * `K_{t} = P_{t|t-1} H'_{t} * (H_{t} P_{t|t-1} H'_{t} + R_{t})^{-1}`
26//! * `P_{t|t} = (Id - K_{t} H_{t}) * P_{t|t-1}`
27//! * `x_{t|t} = x_{t|t-1} + K_{t} * (z_{t} - H_{t} x_{t|t-1})`
28//!
29//! Kalman smoothing equations:
30//!
31//! * `J_{t} = P_{t|t} F'_{t} P_{t+1|t}^{-1}`
32//! * `x_{t|T} = x_{t|t} + J_{t} * (x_{t+1|T} - x_{t+1|t})`
33//! * `P_{t|T} = P_{t|t} + J_{t} * (P_{t+1|T} - P_{t+1|t}) * J'_{t}`
34//!
35//! Nomenclature:
36//!
37//! * `(x_{t+1|t}, P_{t+1|t})` will be referred to as predicted state variables.
38//! * `(x_{t|t}, P_{t|t})` will be referred to as filtered state variables.
39//! * `(x_{t|T}, P_{t|T})` will be referred to as smoothed state variables.
40//!
41//! For now, it is assumed here that `B_{t}` matrix is null and that `Q_{t},
42//! R_{t}, H_{t}` and `F_{t}` matrices are constant over time.
43//!
44//! Besides real data, algorithm takes as inputs `H`, `R`, `F` and `Q` matrices
45//! as well as initial guesses for state mean `x0 = x_{1|0}`and covariance
46//! matrix `P0 = P_{1|0}`. Covariance matrix `P0` indicates the uncertainty
47//! related to the guess of `x0`.
48
49
50extern crate rulinalg;
51
52use rulinalg::matrix::{BaseMatrix, Matrix};
53use rulinalg::vector::Vector;
54
55/// Container object with values for matrices used in the Kalman filtering
56/// procedure as well as initial values for state variables.
57///
58/// # Fields
59/// * `q`: process noise covariance
60/// * `r`: measurement noise covariance
61/// * `h`: observation matrix
62/// * `f`: state transition matrix
63/// * `x0`: initial guess for state mean at time 1
64/// * `p0`: initial guess for state covariance at time 1
65#[derive(Debug)]
66pub struct KalmanFilter {
67 pub q: Matrix<f64>, // Process noise covariance
68 pub r: Matrix<f64>, // Measurement noise covariance
69 pub h: Matrix<f64>, // Observation matrix
70 pub f: Matrix<f64>, // State transition matrix
71 pub x0: Vector<f64>, // State variable initial value
72 pub p0: Matrix<f64> // State covariance initial value
73}
74
75
76/// Container with the value of state variable and its covariance. This struct
77/// is used throughout all parts of Kalman procedure and may refer to predicted,
78/// filtered and smoothed variables depending on the context.
79#[derive(Clone, Debug)]
80pub struct KalmanState {
81 pub x: Vector<f64>, // State vector
82 pub p: Matrix<f64> // State covariance
83}
84
85impl KalmanFilter {
86 /// Takes in measurement data and returns filtered data based on specified
87 /// `KalmanFilter` struct. `filter` actually returns a 2-uple with the first
88 /// coordinate being filtered data whereas the second coordinate is the (a
89 /// priori) prediction data that can be used later in the smoothing
90 /// procedure.
91 ///
92 /// # Examples
93 ///
94 /// ```
95 /// extern crate rulinalg;
96 /// extern crate linearkalman;
97 ///
98 /// use rulinalg::matrix::Matrix;
99 /// use rulinalg::vector::Vector;
100 /// use linearkalman::KalmanFilter;
101 ///
102 /// fn main() {
103 ///
104 /// let kalman_filter = KalmanFilter {
105 /// // All matrices are identity matrices
106 /// q: Matrix::from_diag(&vec![1.0, 1.0]),
107 /// r: Matrix::from_diag(&vec![1.0, 1.0]),
108 /// h: Matrix::from_diag(&vec![1.0, 1.0]),
109 /// f: Matrix::from_diag(&vec![1.0, 1.0]),
110 /// x0: Vector::new(vec![1.0, 1.0]),
111 /// p0: Matrix::from_diag(&vec![1.0, 1.0])
112 /// };
113 ///
114 /// let data: Vec<Vector<f64>> = vec![Vector::new(vec![1.0, 1.0]),
115 /// Vector::new(vec![1.0, 1.0])];
116 ///
117 /// let run_filter = kalman_filter.filter(&data);
118 ///
119 /// // Due to the setup, filtering is equal to the data
120 /// assert_eq!(data[0], run_filter.0[0].x);
121 /// assert_eq!(data[1], run_filter.0[1].x);
122 /// }
123 /// ```
124 pub fn filter(&self, data: &Vec<Vector<f64>>) -> (Vec<KalmanState>, Vec<KalmanState>) {
125
126 let t: usize = data.len();
127
128 // Containers for predicted and filtered estimates
129 let mut predicted: Vec<KalmanState> = Vec::with_capacity(t+1);
130 let mut filtered: Vec<KalmanState> = Vec::with_capacity(t);
131
132 predicted.push(KalmanState { x: (self.x0).clone(),
133 p: (self.p0).clone() });
134
135 for k in 0..t {
136 filtered.push(update_step(self, &predicted[k], &data[k]));
137 predicted.push(predict_step(self, &filtered[k]));
138 }
139
140 (filtered, predicted)
141 }
142
143 /// Takes in output from `filter` method and returns smoothed data.
144 /// Smoothing procedure uses not only past values as is done by `filter` but
145 /// also future values to better predict value of the underlying state
146 /// variable. Underlying algorithm is known as Rauch-Tung-Striebel smoother
147 /// for a fixed interval. Contrary to the filtering process, incremental
148 /// smoothing would require re-running Kalman filter on the entire dataset.
149 ///
150 /// # Examples
151 ///
152 /// ```
153 /// extern crate rulinalg;
154 /// extern crate linearkalman;
155 ///
156 /// use rulinalg::matrix::Matrix;
157 /// use rulinalg::vector::Vector;
158 /// use linearkalman::KalmanFilter;
159 ///
160 /// fn main() {
161 ///
162 /// let kalman_filter = KalmanFilter {
163 /// // All matrices are identity matrices
164 /// q: Matrix::from_diag(&vec![1.0, 1.0]),
165 /// r: Matrix::from_diag(&vec![1.0, 1.0]),
166 /// h: Matrix::from_diag(&vec![1.0, 1.0]),
167 /// f: Matrix::from_diag(&vec![1.0, 1.0]),
168 /// x0: Vector::new(vec![1.0, 1.0]),
169 /// p0: Matrix::from_diag(&vec![1.0, 1.0])
170 /// };
171 ///
172 /// let data: Vec<Vector<f64>> = vec![Vector::new(vec![1.0, 1.0]),
173 /// Vector::new(vec![1.0, 1.0])];
174 ///
175 /// let run_filter = kalman_filter.filter(&data);
176 /// let run_smooth = kalman_filter.smooth(&run_filter.0, &run_filter.1);
177 ///
178 /// // Due to the setup, smoothing is equal to the data
179 /// assert_eq!(data[0], run_smooth[0].x);
180 /// assert_eq!(data[1], run_smooth[0].x);
181 /// }
182 /// ```
183 pub fn smooth(&self,
184 filtered: &Vec<KalmanState>,
185 predicted: &Vec<KalmanState>)
186 -> Vec<KalmanState> {
187
188 let t: usize = filtered.len();
189 let mut smoothed: Vec<KalmanState> = Vec::with_capacity(t);
190
191 // Do Kalman smoothing in reverse order
192 let mut init = (filtered[t - 1]).clone();
193 smoothed.push((filtered[t - 1]).clone());
194
195 for k in 1..t {
196 smoothed.push(smoothing_step(self, &init,
197 &filtered[t-k-1],
198 &predicted[t-k]));
199 init = (&smoothed[k]).clone();
200 }
201
202 smoothed.reverse();
203 smoothed
204 }
205}
206
207/// Returns a predicted state variable mean and covariance. If prediction for
208/// time `t` is desired, then `KalmanState` object with initial conditions
209/// contains state mean and covariance at time `t-1` given information up to
210/// time `t-1`.
211pub fn predict_step(kalman_filter: &KalmanFilter,
212 init: &KalmanState)
213 -> KalmanState {
214
215 // Predict state variable and covariance
216 let xp: Vector<f64> = &kalman_filter.f * &init.x;
217 let pp: Matrix<f64> = &kalman_filter.f * &init.p * &kalman_filter.f.transpose() +
218 &kalman_filter.q;
219
220 KalmanState { x: xp, p: pp}
221}
222
223/// Returns an updated state variable mean and covariance given predicted and
224/// observed data. Typically, update step will be called after prediction step,
225/// data of which will be consequently used as input in updating.
226pub fn update_step(kalman_filter: &KalmanFilter,
227 pred: &KalmanState,
228 measure: &Vector<f64>)
229 -> KalmanState {
230
231 let identity = Matrix::<f64>::identity(kalman_filter.x0.size());
232
233 // Compute Kalman gain
234 let k: Matrix<f64> = &pred.p * &kalman_filter.h.transpose() *
235 (&kalman_filter.h * &pred.p * &kalman_filter.h.transpose() + &kalman_filter.r)
236 .inverse()
237 .expect("Kalman gain computation failed due to failure to invert.");
238
239 // Update state variable and covariance
240 let x = &pred.x + &k * (measure - &kalman_filter.h * &pred.x);
241 let p = (identity - &k * &kalman_filter.h) * &pred.p;
242
243 KalmanState { x: x, p: p }
244
245}
246
247/// Returns a tuple containing updated and predicted estimates (in that order)
248/// of the state variable and its covariance. This function might be useful for
249/// cases where data is incoming and being updated in real-time so that Kalman
250/// filtering is run incrementally. Note that given some initial values for `x`
251/// and `P`, `filter_step` makes a prediction and then runs the update step to
252/// correct the prediction based on the observed data.
253pub fn filter_step(kalman_filter: &KalmanFilter,
254 init: &KalmanState,
255 measure: &Vector<f64>)
256 -> (KalmanState, KalmanState) {
257
258 let pred = predict_step(kalman_filter, init);
259 let upd = update_step(kalman_filter, &pred, measure);
260
261 (KalmanState { x: upd.x, p: upd.p }, KalmanState { x: pred.x, p: pred.p })
262}
263
264
265fn smoothing_step(kalman_filter: &KalmanFilter,
266 init: &KalmanState,
267 filtered: &KalmanState,
268 predicted: &KalmanState)
269 -> KalmanState {
270
271 let j: Matrix<f64> = &filtered.p * &kalman_filter.f.transpose() *
272 &predicted.p.clone().inverse()
273 .expect("Predicted state covariance matrix could not be inverted.");
274 let x: Vector<f64> = &filtered.x + &j * (&init.x - &predicted.x);
275 let p: Matrix<f64> = &filtered.p + &j * (&init.p - &predicted.p) * &j.transpose();
276
277 KalmanState { x: x, p: p }
278
279}