Robot Control Library
kalman.h
Go to the documentation of this file.
1 /**
2  * <rc/math/kalman.h>
3  *
4  * @brief Kalman filter implementation
5  *
6  * This may be used to implement a discrete time linear or extended kalman
7  * filter.
8  *
9  * For the linear case, initialize the filter with rc_kalman_alloc_lin() which
10  * takes in the linear state matrices. These are then saved and used by
11  * rc_kalman_update_lin to calculate the predicted state x_pre and predicted
12  * sensor measurements h internally each step.
13  *
14  *
15  * Basic loop structure for Linear case:
16  *
17  * ```C
18  * rc_kalman_t kf = rc_kalman_empty();
19  * rc_kalman_alloc_lin(&kf,F,G,H,Q,R,Pi);
20  * while(running){
21  * measure sensors, calculate y;
22  * rc_kalman_update_lin(&kf, u, y);
23  * calculate new actuator control output u;
24  * save u for next loop;
25  * }
26  * rc_kalman_free(&kf);
27  * return;
28  * ```
29  *
30  * For the non-linear EKF case, the user should initialize the filter with
31  * rc_kalman_alloc_ekf() which does NOT take in the state transition matrices
32  * F,G,H. Instead it's up to the user to calculate the new predicted state x_pre
33  * and predicted sensor measurement h for their own non-linear system model each
34  * step. Those user-calculated predictions are then given to the non-linear
35  * rc_kalman_update_ekf() function.
36  *
37  *
38  * Basic loop structure for non-linear EKF case:
39  *
40  * ```C
41  * rc_kalman_t kf = rc_kalman_empty();
42  * rc_kalman_alloc_ekf(&kf,Q,R,Pi);
43  * while(running){
44  * measure sensors, calculate y
45  * calculate new Jacobian F given x_est from previous loop;
46  * calculate new predicted x_pre using x_est from previous
47  * loop;
48  * calulate new predicted sensor readings h from x_pre above;
49  * calculate new Jacobian H given x_pre;
50  * rc_kalman_update_ekf(&kf, F, x_pre, H, y, h);
51  * calculate new actuator control output u;
52  * save u for next loop;
53  * }
54  * rc_kalman_free(&kf);
55  * return;
56  * ```
57  *
58  * @date April 2018
59  * @author Eric Nauli Sihite & James Strawson
60  *
61  * @addtogroup Kalman
62  * @ingroup Math
63  * @{
64  */
65 
66 
67 #ifndef RC_KALMAN_H
68 #define RC_KALMAN_H
69 
70 #ifdef __cplusplus
71 extern "C" {
72 #endif
73 
74 #include <stdint.h>
75 #include <rc/math/vector.h>
76 #include <rc/math/matrix.h>
77 
78 
79 /*
80  * @brief Struct to contain full state of kalman filter
81  */
82 typedef struct rc_kalman_t {
83  /** @name State Transition Matrices for linear filter only */
84  ///@{
85  rc_matrix_t F; ///< undriven state-transition model
86  rc_matrix_t G; ///< control input model
87  rc_matrix_t H; ///< observation-model
88  ///@}
89 
90  /** @name Covariance Matrices */
91  ///@{
92  rc_matrix_t Q; ///< Process noise covariance set by user
93  rc_matrix_t R; ///< Measurement noise covariance set by user
94  rc_matrix_t P; ///< Predicted state error covariance calculated by the update functions
95  rc_matrix_t Pi; ///< Initial P matrix set by user
96  ///@}
97 
98  /** @name State estimates */
99  ///@{
100  rc_vector_t x_est; ///< Estimated state x[k|k] = x[k|k-1],y[k])
101  rc_vector_t x_pre; ///< Predicted state x[k|k-1] = f(x[k-1],u[k])
102  ///@}
103 
104  /** @name other */
105  ///@{
106  int initialized; ///< set to 1 once initialized with rc_kalman_alloc
107  uint64_t step; ///< counts times rc_kalman_measurement_update has been called
108  ///@}
109 } rc_kalman_t;
110 
111 #define RC_KALMAN_INITIALIZER {\
112  .F = RC_MATRIX_INITIALIZER,\
113  .G = RC_MATRIX_INITIALIZER,\
114  .H = RC_MATRIX_INITIALIZER,\
115  .Q = RC_MATRIX_INITIALIZER,\
116  .R = RC_MATRIX_INITIALIZER,\
117  .P = RC_MATRIX_INITIALIZER,\
118  .Pi = RC_MATRIX_INITIALIZER,\
119  .x_est = RC_VECTOR_INITIALIZER,\
120  .x_pre = RC_VECTOR_INITIALIZER,\
121  .initialized = 0,\
122  .step = 0}
123 
124 /**
125  * @brief Critical function for initializing rc_kalman_t structs
126  *
127  * This is a very important function. If your rc_kalman_t struct is not a global
128  * variable, then its initial contents cannot be guaranteed to be anything in
129  * particular. Therefore it could contain problematic contents which could
130  * interfere with functions in this library. Therefore, you should always
131  * initialize your filters with rc_kalman_empty() before using with any other
132  * function in this library such as rc_kalman_alloc. This serves the same
133  * purpose as rc_matrix_empty, rc_vector_empty, rc_filter_empty, and
134  * rc_ringbuf_empty.
135  *
136  * @return Empty zero-filled rc_kalman_t struct
137  */
139 
140 /**
141  * @brief Allocates memory for a Kalman filter of given dimensions
142  *
143  * @param kf pointer to struct to be allocated
144  * @param[in] F undriven state-transition model
145  * @param[in] G control input model
146  * @param[in] H observation model
147  * @param[in] Q Process noise covariance, can be updated later
148  * @param[in] R Measurement noise covariance, can be updated later
149  * @param[in] Pi Initial P matrix
150  *
151  * @return 0 on success, -1 on failure
152  */
154 
155 /**
156  * @brief Allocates memory for a Kalman filter of given dimensions
157  *
158  * @param kf pointer to struct to be allocated
159  * @param[in] Q Process noise covariance, can be updated later
160  * @param[in] R Measurement noise covariance, can be updated later
161  * @param[in] Pi Initial P matrix
162  *
163  * @return 0 on success, -1 on failure
164  */
166 
167 
168 /**
169  * @brief Frees the memory allocated by a kalman filter's matrices and
170  * vectors. Also resets all values to 0 like rc_kalman_empty().
171  *
172  * @param kf pointer to user's rc_kalman_t struct
173  *
174  * @return 0 on success or -1 on failure.
175  */
176 int rc_kalman_free(rc_kalman_t* kf);
177 
178 
179 /**
180  * @brief reset state and dynamics of the filter to 0
181  *
182  * Q and R are constant, and therefore not reset. P is set to identity*P_init.
183  *
184  * @param kf pointer to struct to be reset
185  *
186  * @return 0 on success, -1 on failure
187  */
189 
190 
191 /**
192  * @brief Kalman Filter state prediction step based on physical model.
193  *
194  * Uses the state estimate and control input from the previous timestep to
195  * produce an estimate of the state at the current timestep. This step pdates P
196  * and the estimated state x. Assume that you have calculated f(x[k|k],u[k]) and
197  * F(x[k|k],u[k]) before calling this function.
198  *
199  * - Kalman linear state prediction
200  * - x_pre[k|k-1] = F*x[k-1|k-1] + G*u[k-1]
201  * - P[k|k-1] = F*P[k-1|k-1]*F^T + Q
202  * - Kalman measurement Update:
203  * - h[k] = H * x_pre[k]
204  * - S = H*P*H^T + R
205  * - L = P*(H^T)*(S^-1)
206  * - x_est[k|k] = x[k|k-1] + L*(y[k]-h[k])
207  * - P[k|k] = (I - L*H)*P[k|k-1]
208  *
209  * @param kf pointer to struct to be updated
210  * @param u control input
211  * @param[in] y sensor measurement
212  *
213  * @return 0 on success, -1 on failure
214  */
216 
217 
218 /**
219  * @brief Kalman Filter measurement update step.
220  *
221  * Updates L, P, & x_est. Assumes that you have done the non-linear prediction
222  * step in your own function which should calculate the Jacobians F(x[k|k-1]) &
223  * H(x[k|k-1]), the predicted sensor value h(x[k|k-1]), and of course the
224  * predicted state x_pre[k|k-1]
225  *
226  * -Kalman measurement Update:
227  * - P[k|k-1] = F*P[k-1|k-1]*F^T + Q
228  * - S = H*P*H^T + R
229  * - L = P*(H^T)*(S^-1)
230  * - x[k|k] = x[k|k-1] + L*y
231  * - P[k|k] = (I - L*H)*P
232  *
233  * Also updates the step counter in the rc_kalman_t struct
234  *
235  * @param kf pointer to struct to be updated
236  * @param[in] F Jacobian of state transition matrix linearized at x_pre
237  * @param[in] H Jacobian of observation matrix linearized at x_pre
238  * @param[in] x_pre predicted state
239  * @param[in] y new sensor data
240  * @param[in] h Ideal estimate of y, usually h=H*x_pre.
241  *
242  * @return 0 on success, -1 on failure
243  */
245 
246 
247 #ifdef __cplusplus
248 }
249 #endif
250 
251 #endif // RC_KALMAN_H
252 
253 /** @} end group math*/
rc_vector_t x_est
Estimated state x[k|k] = x[k|k-1],y[k])
Definition: kalman.h:100
rc_kalman_t rc_kalman_empty(void)
Critical function for initializing rc_kalman_t structs.
int rc_kalman_reset(rc_kalman_t *kf)
reset state and dynamics of the filter to 0
int rc_kalman_alloc_lin(rc_kalman_t *kf, rc_matrix_t F, rc_matrix_t G, rc_matrix_t H, rc_matrix_t Q, rc_matrix_t R, rc_matrix_t Pi)
Allocates memory for a Kalman filter of given dimensions.
rc_matrix_t Q
Process noise covariance set by user.
Definition: kalman.h:92
int rc_kalman_update_ekf(rc_kalman_t *kf, rc_matrix_t F, rc_matrix_t H, rc_vector_t x_pre, rc_vector_t y, rc_vector_t h)
Kalman Filter measurement update step.
int rc_kalman_alloc_ekf(rc_kalman_t *kf, rc_matrix_t Q, rc_matrix_t R, rc_matrix_t Pi)
Allocates memory for a Kalman filter of given dimensions.
rc_vector_t x_pre
Predicted state x[k|k-1] = f(x[k-1],u[k])
Definition: kalman.h:101
rc_matrix_t P
Predicted state error covariance calculated by the update functions.
Definition: kalman.h:94
rc_matrix_t G
control input model
Definition: kalman.h:86
rc_matrix_t Pi
Initial P matrix set by user.
Definition: kalman.h:95
int rc_kalman_free(rc_kalman_t *kf)
Frees the memory allocated by a kalman filter&#39;s matrices and vectors. Also resets all values to 0 lik...
Struct containing the state of a vector and a pointer to dynamically allocated memory to hold its con...
Definition: vector.h:41
rc_matrix_t H
observation-model
Definition: kalman.h:87
struct rc_kalman_t rc_kalman_t
int initialized
set to 1 once initialized with rc_kalman_alloc
Definition: kalman.h:106
rc_matrix_t F
undriven state-transition model
Definition: kalman.h:85
rc_matrix_t R
Measurement noise covariance set by user.
Definition: kalman.h:93
Definition: kalman.h:82
Struct containing the state of a matrix and a pointer to dynamically allocated memory to hold its con...
Definition: matrix.h:32
uint64_t step
counts times rc_kalman_measurement_update has been called
Definition: kalman.h:107
int rc_kalman_update_lin(rc_kalman_t *kf, rc_vector_t u, rc_vector_t y)
Kalman Filter state prediction step based on physical model.