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,\ 251 #endif // RC_KALMAN_H 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'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
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.