2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
6 See LICENSE for the license information
8 KalmanFilter unit tests.
9 Author: Frank Dellaert & Duy Nguyen Ta (Python)
23 Kalman Filter Definitions:
24 F - State Transition Model
25 B - Control Input Model
27 modelQ - Covariance of the process Noise (input for KalmanFilter object) - sigma as input
28 Q - Covariance of the process Noise (for reference calculation) - sigma^2 as input
30 z1 - Observation iteration 1
31 z2 - Observation iteration 2
32 z3 - observation iteration 3
33 modelR - Covariance of the observation Noise (input for KalmanFilter object) - sigma as input
34 R - Covariance of the observation Noise (for reference calculation) - sigma^2 as input
39 u = np.array([1.0, 0.0])
43 z1 = np.array([1.0, 0.0])
44 z2 = np.array([2.0, 0.0])
45 z3 = np.array([3.0, 0.0])
50 expected0 = np.array([0.0, 0.0])
51 P00 = 0.01 * np.eye(2)
53 expected1 = np.array([1.0, 0.0])
55 I11 = np.linalg.inv(P01) + np.linalg.inv(R)
57 expected2 = np.array([2.0, 0.0])
58 P12 = np.linalg.inv(I11) + Q
59 I22 = np.linalg.inv(P12) + np.linalg.inv(R)
61 expected3 = np.array([3.0, 0.0])
62 P23 = np.linalg.inv(I22) + Q
63 I33 = np.linalg.inv(P23) + np.linalg.inv(R)
69 x_initial = np.array([0.0, 0.0])
70 P_initial = 0.01 * np.eye(2)
73 state = KF.init(x_initial, P_initial)
74 self.assertTrue(np.allclose(expected0, state.mean()))
75 self.assertTrue(np.allclose(P00, state.covariance()))
78 state = KF.predict(state, F, B, u, modelQ)
79 self.assertTrue(np.allclose(expected1, state.mean()))
80 self.assertTrue(np.allclose(P01, state.covariance()))
81 state = KF.update(state, H, z1, modelR)
82 self.assertTrue(np.allclose(expected1, state.mean()))
83 self.assertTrue(np.allclose(I11, state.information()))
86 state = KF.predict(state, F, B, u, modelQ)
87 self.assertTrue(np.allclose(expected2, state.mean()))
88 state = KF.update(state, H, z2, modelR)
89 self.assertTrue(np.allclose(expected2, state.mean()))
92 state = KF.predict(state, F, B, u, modelQ)
93 self.assertTrue(np.allclose(expected3, state.mean()))
94 state = KF.update(state, H, z3, modelR)
95 self.assertTrue(np.allclose(expected3, state.mean()))
97 if __name__ ==
"__main__":