ESP-IDF Firmware
Firmware architecture and call graph
Loading...
Searching...
No Matches
ekf.cpp
Go to the documentation of this file.
1// Copyright 2020-2021 Espressif Systems (Shanghai) PTE LTD
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#include "ekf.h"
16#include <cmath>
17#include <float.h>
18
19ekf::ekf(int x, int w) : NUMX(x),
20 NUMW(w),
21 X(*new dspm::Mat(x, 1)),
22
23 F(*new dspm::Mat(x, x)),
24 G(*new dspm::Mat(x, w)),
25 P(*new dspm::Mat(x, x)),
26 Q(*new dspm::Mat(w, w))
27{
28
29 this->P *= 0;
30 this->Q *= 0;
31 this->X *= 0;
32 this->X.data[0] = 1; // direction to 0
33 this->HP = new float[this->NUMX];
34 this->Km = new float[this->NUMX];
35 for (size_t i = 0; i < this->NUMX; i++) {
36 this->HP[i] = 0;
37 this->Km[i] = 0;
38 }
39}
40
42{
43 delete &X;
44 delete &F;
45 delete &G;
46 delete &P;
47 delete &Q;
48
49 delete this->HP;
50 delete this->Km;
51}
52
53void ekf::Process(float *u, float dt)
54{
55 this->LinearizeFG(this->X, (float *)u);
56 this->RungeKutta(this->X, u, dt);
57 this->CovariancePrediction(dt);
58}
59
60void ekf::RungeKutta(dspm::Mat &x, float *U, float dt)
61{
62
63 float dt2 = dt / 2.0f;
64
65 dspm::Mat Xlast = x; // make a working copy
66 dspm::Mat K1 = StateXdot(x, U); // k1 = f(x, u)
67 x = Xlast + (K1 * dt2);
68
69 dspm::Mat K2 = StateXdot(x, U); // k2 = f(x + 0.5*dT*k1, u)
70 x = Xlast + K2 * dt2;
71
72 dspm::Mat K3 = StateXdot(x, U); // k3 = f(x + 0.5*dT*k2, u)
73 x = Xlast + K3 * dt;
74
75 dspm::Mat K4 = StateXdot(x, U); // k4 = f(x + dT * k3, u)
76
77 // Xnew = X + dT * (k1 + 2 * k2 + 2 * k3 + k4) / 6
78 x = Xlast + (K1 + 2.0f * K2 + 2.0f * K3 + K4) * (dt / 6.0f);
79}
80
82{
83 //={ 0, -w[0], -w[1], -w[2],
84 // w[0], 0, w[2], -w[1],
85 // w[1], -w[2], 0, w[0],
86 // w[2], w[1], -w[0], 0 };
87
88 dspm::Mat result(4, 4);
89 result.data[0] = 0;
90 result.data[1] = -w[0];
91 result.data[2] = -w[1];
92 result.data[3] = -w[2];
93
94 result.data[4] = w[0];
95 result.data[5] = 0;
96 result.data[6] = w[2];
97 result.data[7] = -w[1];
98
99 result.data[8] = w[1];
100 result.data[9] = -w[2];
101 result.data[10] = 0;
102 result.data[11] = w[0];
103
104 result.data[12] = w[2];
105 result.data[13] = w[1];
106 result.data[14] = -w[0];
107 result.data[15] = 0;
108
109 return result;
110}
111
113{
114 dspm::Mat result(4, 4);
115
116 result.data[0] = q[0];
117 result.data[1] = -q[1];
118 result.data[2] = -q[2];
119 result.data[3] = -q[3];
120
121 result.data[4] = q[1];
122 result.data[5] = q[0];
123 result.data[6] = -q[3];
124 result.data[7] = q[2];
125
126 result.data[8] = q[2];
127 result.data[9] = q[3];
128 result.data[10] = q[0];
129 result.data[11] = -q[1];
130
131 result.data[12] = q[3];
132 result.data[13] = -q[2];
133 result.data[14] = q[1];
134 result.data[15] = q[0];
135
136 return result;
137}
138
140{
141 dspm::Mat f = this->F * dt;
142
143 f = f + dspm::Mat::eye(this->NUMX);
144
145 dspm::Mat f_t = f.t();
146 this->P = ((f * this->P) * f_t) + (dt * dt) * ((G * Q) * G.t());
147}
148
149void ekf::Update(dspm::Mat &H, float *measured, float *expected, float *R)
150{
151 float HPHR, Error;
152 dspm::Mat Y(measured, H.rows, 1);
153 dspm::Mat Z(expected, H.rows, 1);
154
155 for (int m = 0; m < H.rows; m++) {
156 for (int j = 0; j < this->NUMX; j++) {
157 // Find Hp = H*P
158 HP[j] = 0;
159 }
160 for (int k = 0; k < this->NUMX; k++) {
161 for (int j = 0; j < this->NUMX; j++) {
162 // Find Hp = H*P
163 HP[j] += H(m, k) * P(k, j);
164 }
165 }
166 HPHR = R[m]; // Find HPHR = H*P*H' + R
167 for (int k = 0; k < this->NUMX; k++) {
168 HPHR += HP[k] * H(m, k);
169 }
170 float invHPHR = 1.0f / HPHR;
171 for (int k = 0; k < this->NUMX; k++) {
172 Km[k] = HP[k] * invHPHR; // find K = HP/HPHR
173 }
174 for (int i = 0; i < this->NUMX; i++) {
175 // Find P(m)= P(m-1) + K*HP
176 for (int j = i; j < NUMX; j++) {
177 P(i, j) = P(j, i) = P(i, j) - Km[i] * HP[j];
178 }
179 }
180
181 Error = Y(m, 0) - Z(m, 0);
182 for (int i = 0; i < this->NUMX; i++) {
183 // Find X(m)= X(m-1) + K*Error
184 X(i, 0) = X(i, 0) + Km[i] * Error;
185 }
186 }
187}
188
189void ekf::UpdateRef(dspm::Mat &H, float *measured, float *expected, float *R)
190{
191 dspm::Mat h_t = H.t();
192 dspm::Mat S = H * P * h_t; // +diag(R);
193 for (size_t i = 0; i < H.rows; i++) {
194 S(i, i) += R[i];
195 }
196
197 dspm::Mat S_ = S.pinv(); // 1 / S
198
199 dspm::Mat K = (P * h_t) * S_;
200 this->P = (dspm::Mat::eye(this->NUMX) - K * H) * P;
201
202 dspm::Mat Y(measured, H.rows, 1);
203 dspm::Mat Z(expected, H.rows, 1);
204
205 dspm::Mat Err = Y - Z;
206 this->X += (K * Err);
207}
208
210{
211 float q0 = q[0];
212 float q1 = q[1];
213 float q2 = q[2];
214 float q3 = q[3];
215 dspm::Mat Rm(3, 3);
216
217 Rm(0, 0) = q0 * q0 + q1 * q1 - q2 * q2 - q3 * q3;
218 Rm(1, 0) = 2.0f * (q1 * q2 + q0 * q3);
219 Rm(2, 0) = 2.0f * (q1 * q3 - q0 * q2);
220 Rm(0, 1) = 2.0f * (q1 * q2 - q0 * q3);
221 Rm(1, 1) = (q0 * q0 - q1 * q1 + q2 * q2 - q3 * q3);
222 Rm(2, 1) = 2.0f * (q2 * q3 + q0 * q1);
223 Rm(0, 2) = 2.0f * (q1 * q3 + q0 * q2);
224 Rm(1, 2) = 2.0f * (q2 * q3 - q0 * q1);
225 Rm(2, 2) = (q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3);
226
227 return Rm;
228}
229
230dspm::Mat ekf::quat2eul(const float q[4])
231{
232 dspm::Mat result(3, 1);
233 float R13, R11, R12, R23, R33;
234 float q0s = q[0] * q[0];
235 float q1s = q[1] * q[1];
236 float q2s = q[2] * q[2];
237 float q3s = q[3] * q[3];
238
239 R13 = 2.0f * (q[1] * q[3] + q[0] * q[2]);
240 R11 = q0s + q1s - q2s - q3s;
241 R12 = -2.0f * (q[1] * q[2] - q[0] * q[3]);
242 R23 = -2.0f * (q[2] * q[3] - q[0] * q[1]);
243 R33 = q0s - q1s - q2s + q3s;
244
245 result.data[1] = (asinf(R13));
246 result.data[2] = (atan2f(R12, R11));
247 result.data[0] = (atan2f(R23, R33));
248 return result;
249}
250
252{
253 dspm::Mat result(3, 3);
254 float Cx = std::cos(xyz[0]);
255 float Sx = std::sin(xyz[0]);
256 float Cy = std::cos(xyz[1]);
257 float Sy = std::sin(xyz[1]);
258 float Cz = std::cos(xyz[2]);
259 float Sz = std::sin(xyz[2]);
260
261 result(0, 0) = Cy * Cz;
262 result(0, 1) = -Cy * Sz;
263 result(0, 2) = Sy;
264
265 result(1, 0) = Cz * Sx * Sy + Cx * Sz;
266 result(1, 1) = Cx * Cz - Sx * Sy * Sz;
267 result(1, 2) = -Cy * Sx;
268
269 result(2, 0) = -Cx * Cz * Sy + Sx * Sz;
270 result(2, 1) = Cz * Sx + Cx * Sy * Sz;
271 result(2, 2) = Cx * Cy;
272 return result;
273}
274
275#ifndef FLT_EPSILON
276#define FLT_EPSILON 1.192092896e-07F
277#endif // FLT_EPSILON
278
280{
281 dspm::Mat result(3, 1);
282 float x, y, z;
283// float cy = sqrtf(rotm(2, 2) * rotm(2, 2) + rotm(2, 0) * rotm(2, 0));
284 float cy = sqrtf(rotm(2, 2) * rotm(2, 2) + rotm(1, 2) * rotm(1, 2));
285 if (cy > 16 * FLT_EPSILON) {
286 x = -atan2f(rotm(1, 2), rotm(2, 2));
287 y = -atan2f(-rotm(0, 2), (float)cy);
288 z = -atan2f(rotm(0, 1), rotm(0, 0));
289 } else {
290 z = -atan2f(-rotm(1, 0), rotm(1, 1));
291 y = -atan2f(-rotm(0, 2), (float)cy);
292 x = 0;
293 }
294 result(0, 0) = x;
295 result(1, 0) = y;
296 result(2, 0) = z;
297 return result;
298}
299
300static inline float SIGN(float x)
301{
302 return (x >= 0.0f) ? +1.0f : -1.0f;
303}
304
306{
307 float r11 = m(0, 0);
308 float r12 = m(0, 1);
309 float r13 = m(0, 2);
310 float r21 = m(1, 0);
311 float r22 = m(1, 1);
312 float r23 = m(1, 2);
313 float r31 = m(2, 0);
314 float r32 = m(2, 1);
315 float r33 = m(2, 2);
316 float q0 = (r11 + r22 + r33 + 1.0f) / 4.0f;
317 float q1 = (r11 - r22 - r33 + 1.0f) / 4.0f;
318 float q2 = (-r11 + r22 - r33 + 1.0f) / 4.0f;
319 float q3 = (-r11 - r22 + r33 + 1.0f) / 4.0f;
320 if (q0 < 0.0f) {
321 q0 = 0.0f;
322 }
323 if (q1 < 0.0f) {
324 q1 = 0.0f;
325 }
326 if (q2 < 0.0f) {
327 q2 = 0.0f;
328 }
329 if (q3 < 0.0f) {
330 q3 = 0.0f;
331 }
332 q0 = sqrt(q0);
333 q1 = sqrt(q1);
334 q2 = sqrt(q2);
335 q3 = sqrt(q3);
336 if (q0 >= q1 && q0 >= q2 && q0 >= q3) {
337 q0 *= +1.0f;
338 q1 *= SIGN(r32 - r23);
339 q2 *= SIGN(r13 - r31);
340 q3 *= SIGN(r21 - r12);
341 } else if (q1 >= q0 && q1 >= q2 && q1 >= q3) {
342 q0 *= SIGN(r32 - r23);
343 q1 *= +1.0f;
344 q2 *= SIGN(r21 + r12);
345 q3 *= SIGN(r13 + r31);
346 } else if (q2 >= q0 && q2 >= q1 && q2 >= q3) {
347 q0 *= SIGN(r13 - r31);
348 q1 *= SIGN(r21 + r12);
349 q2 *= +1.0f;
350 q3 *= SIGN(r32 + r23);
351 } else if (q3 >= q0 && q3 >= q1 && q3 >= q2) {
352 q0 *= SIGN(r21 - r12);
353 q1 *= SIGN(r31 + r13);
354 q2 *= SIGN(r32 + r23);
355 q3 *= +1.0f;
356 }
357
358 dspm::Mat res(4, 1);
359 res(0, 0) = q0;
360 res(1, 0) = q1;
361 res(2, 0) = q2;
362 res(3, 0) = q3;
363 res /= res.norm();
364 return res;
365}
366
368{
369 dspm::Mat result(3, 4);
370 result(0, 0) = q.data[0] * vector.data[0] - q.data[3] * vector.data[1] + q.data[2] * vector.data[2];
371 result(0, 1) = q.data[1] * vector.data[0] + q.data[2] * vector.data[1] + q.data[3] * vector.data[2];
372 result(0, 2) = -q.data[2] * vector.data[0] + q.data[1] * vector.data[1] + q.data[0] * vector.data[2];
373 result(0, 3) = -q.data[3] * vector.data[0] - q.data[0] * vector.data[1] + q.data[1] * vector.data[2];
374
375 result(1, 0) = q.data[3] * vector.data[0] + q.data[0] * vector.data[1] - q.data[1] * vector.data[2];
376 result(1, 1) = q.data[2] * vector.data[0] - q.data[1] * vector.data[1] - q.data[0] * vector.data[2];
377 result(1, 2) = q.data[1] * vector.data[0] + q.data[2] * vector.data[1] + q.data[3] * vector.data[2];
378 result(1, 3) = q.data[0] * vector.data[0] - q.data[3] * vector.data[1] + q.data[2] * vector.data[2];
379
380 result(2, 0) = -q.data[2] * vector.data[0] + q.data[1] * vector.data[1] + q.data[0] * vector.data[2];
381 result(2, 1) = q.data[3] * vector.data[0] + q.data[0] * vector.data[1] - q.data[1] * vector.data[2];
382 result(2, 2) = -q.data[0] * vector.data[0] + q.data[3] * vector.data[1] - q.data[2] * vector.data[2];
383 result(2, 3) = q.data[1] * vector.data[0] + q.data[2] * vector.data[1] + q.data[3] * vector.data[2];
384
385 result *= 2;
386 return result;
387}
388
390{
391 dspm::Mat result(3, 4);
392 result(0, 0) = q.data[0] * vector.data[0] + q.data[3] * vector.data[1] - q.data[2] * vector.data[2];
393 result(0, 1) = q.data[1] * vector.data[0] + q.data[2] * vector.data[1] + q.data[3] * vector.data[2];
394 result(0, 2) = -q.data[2] * vector.data[0] + q.data[1] * vector.data[1] - q.data[0] * vector.data[2];
395 result(0, 3) = -q.data[3] * vector.data[0] + q.data[0] * vector.data[1] + q.data[1] * vector.data[2];
396
397 result(1, 0) = -q.data[3] * vector.data[0] + q.data[0] * vector.data[1] + q.data[1] * vector.data[2];
398 result(1, 1) = q.data[2] * vector.data[0] - q.data[1] * vector.data[1] + q.data[0] * vector.data[2];
399 result(1, 2) = q.data[1] * vector.data[0] + q.data[2] * vector.data[1] + q.data[3] * vector.data[2];
400 result(1, 3) = -q.data[0] * vector.data[0] - q.data[3] * vector.data[1] + q.data[2] * vector.data[2];
401
402 result(2, 0) = q.data[2] * vector.data[0] - q.data[1] * vector.data[1] + q.data[0] * vector.data[2];
403 result(2, 1) = q.data[3] * vector.data[0] - q.data[0] * vector.data[1] - q.data[1] * vector.data[2];
404 result(2, 2) = q.data[0] * vector.data[0] + q.data[3] * vector.data[1] - q.data[2] * vector.data[2];
405 result(2, 3) = q.data[1] * vector.data[0] + q.data[2] * vector.data[1] + q.data[3] * vector.data[2];
406
407 result *= 2;
408 return result;
409}
410
412{
413 dspm::Mat U(u, this->G.cols, 1);
414 dspm::Mat Xdot = (this->F * x + this->G * U);
415 return Xdot;
416}
Matrix.
Definition mat.h:30
float * data
Definition mat.h:37
float norm(void)
Definition mat.cpp:456
Mat pinv()
Definition mat.cpp:707
static Mat eye(int size)
Definition mat.cpp:394
int rows
Definition mat.h:33
Mat t()
Definition mat.cpp:383
virtual dspm::Mat StateXdot(dspm::Mat &x, float *u)
Definition ekf.cpp:411
int NUMW
Definition ekf.h:68
static dspm::Mat rotm2quat(dspm::Mat &R)
Definition ekf.cpp:305
static dspm::Mat dFdq(dspm::Mat &vector, dspm::Mat &quat)
Definition ekf.cpp:367
virtual void LinearizeFG(dspm::Mat &x, float *u)=0
dspm::Mat & F
Definition ekf.h:78
static dspm::Mat dFdq_inv(dspm::Mat &vector, dspm::Mat &quat)
Definition ekf.cpp:389
virtual void Process(float *u, float dt)
Definition ekf.cpp:53
ekf(int x, int w)
Definition ekf.cpp:19
virtual ~ekf()
Definition ekf.cpp:41
static dspm::Mat quat2rotm(float q[4])
Definition ekf.cpp:209
float * HP
Definition ekf.h:157
virtual void CovariancePrediction(float dt)
Definition ekf.cpp:139
int NUMX
Definition ekf.h:63
static dspm::Mat eul2rotm(float xyz[3])
Definition ekf.cpp:251
static dspm::Mat rotm2eul(dspm::Mat &rotm)
Definition ekf.cpp:279
dspm::Mat & G
Definition ekf.h:82
virtual void Update(dspm::Mat &H, float *measured, float *expected, float *R)
Definition ekf.cpp:149
void RungeKutta(dspm::Mat &x, float *u, float dt)
Definition ekf.cpp:60
static dspm::Mat quat2eul(const float q[4])
Definition ekf.cpp:230
dspm::Mat & X
Definition ekf.h:73
virtual void UpdateRef(dspm::Mat &H, float *measured, float *expected, float *R)
Definition ekf.cpp:189
dspm::Mat & Q
Definition ekf.h:92
static dspm::Mat qProduct(float *q)
Definition ekf.cpp:112
dspm::Mat & P
Definition ekf.h:87
float * Km
Definition ekf.h:161
static dspm::Mat SkewSym4x4(float *w)
Definition ekf.cpp:81
#define FLT_EPSILON
Definition ekf.cpp:276
static float SIGN(float x)
Definition ekf.cpp:300
DSP matrix namespace.
Definition mat.h:24
float y[1024]
Definition test_fir.c:11
float x[1024]
Definition test_fir.c:10
const int m
Definition test_mmult.c:16
#define K
Definition test_mmult.c:14
const int k
Definition test_mmult.c:18