-
Notifications
You must be signed in to change notification settings - Fork 2
/
kalman_meschach.c
159 lines (129 loc) · 3.65 KB
/
kalman_meschach.c
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
/*
* file: kalman_meschach.c
*
* implements kalman filter for linear system:
*
* | 1 dt | * | p | + | 0.5 * dt ^ 2 | * | a | = | p |
* | 0 1 | * | v | | dt | | v |
*
* authors:
* Tobias Simon, Ilmenau University of Technology
* Jan Roemisch, Ilmenau University of Technology
*/
#include <meschach/matrix.h>
#include <meschach/matrix2.h>
#include "kalman.h"
struct kalman
{
/* configuration and constant matrices: */
MAT *Q; /* process noise */
MAT *R; /* measurement noise */
MAT *I; /* identity matrix */
/* state and transition vectors/matrices: */
VEC *x; /* state (location and velocity) */
VEC *z; /* measurement (location) */
MAT *A; /* system matrix */
MAT *B; /* control matrix */
MAT *P; /* error covariance */
VEC *u; /* control (acceleration) */
MAT *H; /* observer matrix */
MAT *K; /* kalman gain */
/* vectors and matrices for calculations: */
VEC *t0;
VEC *t1;
MAT *T0;
MAT *T1;
};
static void kalman_init(kalman_t *kf, float dt, float q, float r, float pos, float speed)
{
kf->t0 = v_get(2);
kf->t1 = v_get(2);
kf->T0 = m_get(2, 2);
kf->T1 = m_get(2, 2);
kf->I = m_get(2, 2);
m_ident(kf->I);
/* set initial state: */
kf->x = v_get(2);
v_set_val(kf->x, 0, pos);
v_set_val(kf->x, 1, speed);
/* no measurement or control yet: */
kf->z = v_get(2);
kf->u = v_get(1);
kf->P = m_get(2, 2);
m_ident(kf->P);
/* set up noise: */
kf->Q = m_get(2, 2);
sm_mlt(q, kf->I, kf->Q);
kf->R = m_get(2, 2);
sm_mlt(r, kf->I, kf->R);
kf->K = m_get(2, 1);
kf->H = m_get(2, 2);
m_set_val(kf->H, 0, 0, 1.0);
//m_ident(kf->H);
/* A = | 1.0 dt |
| 0.0 1.0 | */
kf->A = m_get(2, 2);
m_set_val(kf->A, 0, 0, 1.0);
m_set_val(kf->A, 0, 1, dt);
m_set_val(kf->A, 1, 0, 0.0);
m_set_val(kf->A, 1, 1, 1.0);
/* B = | 0.5 * dt ^ 2 |
| dt | */
kf->B = m_get(2, 1);
m_set_val(kf->B, 0, 0, 0.5 * dt * dt);
m_set_val(kf->B, 1, 0, dt);
}
static void kalman_predict(kalman_t *kf, float a)
{
/* x = A * x + B * u */
v_set_val(kf->u, 0, a);
mv_mlt(kf->A, kf->x, kf->t0);
mv_mlt(kf->B, kf->u, kf->t1);
v_add(kf->t0, kf->t1, kf->x);
/* P = A * P * AT + Q */
m_mlt(kf->A, kf->P, kf->T0);
mmtr_mlt(kf->T0, kf->A, kf->T1);
m_add(kf->T1, kf->Q, kf->P);
}
static void kalman_correct(kalman_t *kf, float p, float v)
{
/* K = P * HT * inv(H * P * HT + R) */
m_mlt(kf->H, kf->P, kf->T0);
mmtr_mlt(kf->T0, kf->H, kf->T1);
m_add(kf->T1, kf->R, kf->T0);
m_inverse(kf->T0, kf->T1);
mmtr_mlt(kf->P, kf->H, kf->T0);
m_mlt(kf->T0, kf->T1, kf->K);
/* x = x + K * (z - H * x) */
mv_mlt(kf->H, kf->x, kf->t0);
v_set_val(kf->z, 0, p);
v_set_val(kf->z, 1, v);
v_sub(kf->z, kf->t0, kf->t1);
mv_mlt(kf->K, kf->t1, kf->t0);
v_add(kf->x, kf->t0, kf->t1);
v_copy(kf->t1, kf->x);
/* P = (I - K * H) * P */
m_mlt(kf->K, kf->H, kf->T0);
m_sub(kf->I, kf->T0, kf->T1);
m_mlt(kf->T1, kf->P, kf->T0);
m_copy(kf->T0, kf->P);
}
/*
* executes kalman predict and correct step
*/
void kalman_run(kalman_out_t *out, kalman_t *kalman, const kalman_in_t *in)
{
kalman_predict(kalman, in->acc);
kalman_correct(kalman, in->pos, 0.0);
out->pos = v_entry(kalman->x, 0);
out->speed = v_entry(kalman->x, 1);
}
/*
* allocates and initializes a kalman filter
*/
kalman_t *kalman_create(const kalman_config_t *config, const kalman_out_t *init_state)
{
kalman_t *kalman = (kalman_t *)malloc(sizeof(kalman_t));
kalman_init(kalman, config->dt, config->process_var, config->measurement_var, init_state->pos, init_state->speed);
return kalman;
}