-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathyafl.h
708 lines (593 loc) · 33.2 KB
/
yafl.h
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
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
/*******************************************************************************
Copyright 2021 anonimous <[email protected]> and contributors.
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing,
software distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions
and limitations under the License.
******************************************************************************/
#ifndef YAFL_H
#define YAFL_H
#include <yafl_config.h>
#include "yafl_math.h"
/*=============================================================================
Basic UD-factorized Kalman filter Definitions
=============================================================================*/
typedef struct _yaflKalmanBaseSt yaflKalmanBaseSt;
typedef yaflStatusEn (* yaflKalmanFuncP)(yaflKalmanBaseSt *, yaflFloat *, \
yaflFloat *);
typedef yaflStatusEn (* yaflKalmanResFuncP)(yaflKalmanBaseSt *, yaflFloat *, \
yaflFloat *, yaflFloat *);
typedef yaflStatusEn (* yaflKalmanScalarUpdateP)(yaflKalmanBaseSt *, yaflInt);
typedef yaflStatusEn (* yaflKalmanUpdateCBP)(yaflKalmanBaseSt *);
/*
Function pointer for robust versions of filters.
Based on:
1. West M., "Robust Sequential Approximate Bayesian Estimation",
J. R. Statist. Soc. B (1981), 43, No. 2, pp. 157-166
2. Gaver, Donald Paul; Jacobs, Patricia A., "Robustifying the Kalman filter",
Naval Postgraduate School technical report. 1987
http://hdl.handle.net/10945/30147
*/
typedef yaflFloat (* yaflKalmanRobFuncP)(yaflKalmanBaseSt *, yaflFloat);
struct _yaflKalmanBaseSt {
yaflKalmanFuncP f; /*A state transition function*/
yaflKalmanFuncP h; /*A measurement function*/
yaflKalmanResFuncP zrf; /*Measurement residual function function*/
yaflKalmanUpdateCBP rcb; /*R update Call Back*/
yaflFloat * x; /*State vector*/
yaflFloat * y; /*Innovation vector*/
yaflFloat * Up; /*Upper triangular part of P*/
yaflFloat * Dp; /*Diagonal part of P*/
yaflFloat * Uq; /*Upper triangular part of Q*/
yaflFloat * Dq; /*Diagonal part of Q*/
yaflFloat * Ur; /*Upper triangular part of R*/
yaflFloat * Dr; /*Diagonal part of R*/
yaflFloat * l; /*likelihood*/
yaflFloat rff; /*R forgetting factor*/
yaflInt Nx; /*State vector size*/
yaflInt Nz; /*Measurement vector size*/
};
/*---------------------------------------------------------------------------*/
#define YAFL_KALMAN_BASE_MEMORY_MIXIN(nx, nz) \
yaflFloat x[nx]; \
yaflFloat y[nz]; \
\
yaflFloat Up[((nx - 1) * nx)/2]; \
yaflFloat Dp[nx]; \
\
yaflFloat Uq[((nx - 1) * nx)/2]; \
yaflFloat Dq[nx]; \
\
yaflFloat Ur[((nz - 1) * nz)/2]; \
yaflFloat Dr[nz]; \
yaflFloat l
/*---------------------------------------------------------------------------*/
/*TODO: make qff and rff parameters*/
#define YAFL_KALMAN_BASE_INITIALIZER(_f, _h, _zrf, _nx, _nz, _rff, _mem) \
{ \
.f = (yaflKalmanFuncP)_f, \
.h = (yaflKalmanFuncP)_h, \
.zrf = (yaflKalmanResFuncP)_zrf, \
\
.x = _mem.x, \
.y = _mem.y, \
\
.Up = _mem.Up, \
.Dp = _mem.Dp, \
\
.Uq = _mem.Uq, \
.Dq = _mem.Dq, \
\
.Ur = _mem.Ur, \
.Dr = _mem.Dr, \
\
.l = &_mem.l, \
\
.rff = _rff, \
\
.Nx = _nx, \
.Nz = _nz \
}
/*---------------------------------------------------------------------------*/
#define YAFL_KALMAN_PREDICT_WRAPPER(predict, base_type, func, self_type) \
static inline yaflStatusEn func(self_type * self) \
{ \
return predict((base_type *)self); \
}
/*---------------------------------------------------------------------------*/
#define YAFL_KALMAN_UPDATE_IMPL(update, base_type, func, self_type) \
extern yaflStatusEn func##_scalar(yaflKalmanBaseSt * self, yaflInt i); \
static inline yaflStatusEn func(self_type * self, yaflFloat * z) \
{ \
return update((base_type *)self, z, func##_scalar); \
}
/*=============================================================================
Basic UD-factorized EKF definitions
=============================================================================*/
typedef struct _yaflEKFBaseSt yaflEKFBaseSt;
struct _yaflEKFBaseSt {
yaflKalmanBaseSt base; /*Base type*/
yaflKalmanFuncP jf; /*Jacobian of a state transition function*/
yaflKalmanFuncP jh; /*Jacobian of a measurement function*/
yaflFloat * H; /*Measurement Jacobian values*/
yaflFloat * W; /*Scratchpad memory block matrix*/
yaflFloat * D; /*Scratchpad memory diagonal matrix*/
yaflFloat qff; /*Q forgetting factor*/
};
/*---------------------------------------------------------------------------*/
#define YAFL_EKF_BASE_MEMORY_MIXIN(nx, nz) \
YAFL_KALMAN_BASE_MEMORY_MIXIN(nx, nz); \
\
yaflFloat H[nz * nx]; \
union { \
yaflFloat x[2 * nx * nx]; \
yaflFloat z[(nx + nz) * nz]; \
} W; \
union { \
yaflFloat x[2 * nx]; \
yaflFloat z[nx + nz]; \
} D
/*---------------------------------------------------------------------------*/
#define YAFL_EKF_BASE_INITIALIZER(_f, _jf, _h, _jh, _zrf, _nx, _nz, \
_rff, _qff, _mem) \
{ \
.base = YAFL_KALMAN_BASE_INITIALIZER(_f, _h, _zrf, _nx, _nz, _rff, _mem), \
\
.jf = (yaflKalmanFuncP)_jf, \
.jh = (yaflKalmanFuncP)_jh, \
\
.H = _mem.H, \
.W = _mem.W.x, \
.D = _mem.D.x, \
\
.qff = _qff \
}
/*---------------------------------------------------------------------------*/
yaflStatusEn yafl_ekf_base_predict(yaflKalmanBaseSt * self);
yaflStatusEn yafl_ekf_base_update(yaflKalmanBaseSt * self, yaflFloat * z, \
yaflKalmanScalarUpdateP scalar_update);
/*---------------------------------------------------------------------------*/
#define YAFL_EKF_PREDICT_WRAPPER(func, self_type) \
YAFL_KALMAN_PREDICT_WRAPPER(yafl_ekf_base_predict, yaflKalmanBaseSt, \
func, self_type)
/*---------------------------------------------------------------------------*/
#define YAFL_EKF_UPDATE_IMPL(func, self_type) \
YAFL_KALMAN_UPDATE_IMPL(yafl_ekf_base_update, yaflKalmanBaseSt, \
func, self_type)
/*---------------------------------------------------------------------------*/
YAFL_EKF_PREDICT_WRAPPER(_yafl_ekf_predict_wrapper, yaflEKFBaseSt)
/*-----------------------------------------------------------------------------
Bierman filter
-----------------------------------------------------------------------------*/
#define YAFL_EKF_BIERMAN_PREDICT _yafl_ekf_predict_wrapper
YAFL_EKF_UPDATE_IMPL(yafl_ekf_bierman_update, yaflEKFBaseSt)
/*-----------------------------------------------------------------------------
Joseph filter
-----------------------------------------------------------------------------*/
#define YAFL_EKF_JOSEPH_PREDICT _yafl_ekf_predict_wrapper
YAFL_EKF_UPDATE_IMPL(yafl_ekf_joseph_update, yaflEKFBaseSt)
/*=============================================================================
Adaptive UD-factorized EKF definitions
=============================================================================*/
typedef struct {
yaflEKFBaseSt base;
yaflFloat chi2; /*Divergence test threshold (chi-squared criteria)*/
} yaflEKFAdaptiveSt; /*Adaptive kKalman-Hinfinity filter structure*/
/*---------------------------------------------------------------------------*/
#define YAFL_EKF_ADAPTIVE_INITIALIZER(_f, _jf, _h, _jh, _zrf, _nx, _nz, \
_rff, _qff, _chi2, _mem) \
{ \
.base = YAFL_EKF_BASE_INITIALIZER(_f, _jf, _h, _jh, _zrf, _nx, _nz, \
_rff, _qff, _mem), \
.chi2 = _chi2 \
}
/*
A good value of chi2 for yaflEKFAdaptiveSt is:
scipy.stats.chi2.ppf(0.999, 1) == 10.827566170662733
*/
/*---------------------------------------------------------------------------*/
YAFL_EKF_PREDICT_WRAPPER(_yafl_ada_ekf_predict_wrapper, yaflEKFAdaptiveSt)
/*-----------------------------------------------------------------------------
Adaptive Bierman filter
-----------------------------------------------------------------------------*/
#define YAFL_EKF_ADAPTIVE_BIERAMN_PREDICT _yafl_ada_ekf_predict_wrapper
YAFL_EKF_UPDATE_IMPL(yafl_ekf_adaptive_bierman_update, yaflEKFAdaptiveSt)
/*-----------------------------------------------------------------------------
Adaptive Joseph filter
-----------------------------------------------------------------------------*/
#define YAFL_EKF_ADAPTIVE_JOSEPH_PREDICT _yafl_ada_ekf_predict_wrapper
YAFL_EKF_UPDATE_IMPL(yafl_ekf_adaptive_joseph_update, yaflEKFAdaptiveSt)
/*-----------------------------------------------------------------------------
WARNING!!!
DO NOT USE THIS variant of Adaptive Joseph filter !!!
It was implemented to show some flaws of the corresponding algorithm!
-----------------------------------------------------------------------------*/
yaflStatusEn \
yafl_ekf_do_not_use_this_update_scalar(yaflKalmanBaseSt * self, yaflInt i);
static inline yaflStatusEn \
yafl_ekf_do_not_use_this_update(yaflEKFAdaptiveSt * self, yaflFloat * z)
{
return yafl_ekf_base_update((yaflKalmanBaseSt *)self, z, \
yafl_ekf_do_not_use_this_update_scalar);
}
/*=============================================================================
Robust UD-factorized EKF definitions
=============================================================================*/
/*
Based on:
1. West M., "Robust Sequential Approximate Bayesian Estimation",
J. R. Statist. Soc. B (1981), 43, No. 2, pp. 157-166
2. Gaver, Donald Paul; Jacobs, Patricia A., "Robustifying the Kalman filter",
Naval Postgraduate School technical report. 1987
http://hdl.handle.net/10945/30147
*/
typedef struct {
yaflEKFBaseSt base;
yaflKalmanRobFuncP g; /* g = -d(ln(pdf(y))) / dy */
yaflKalmanRobFuncP gdot; /* gdot = G = d(g) / dy */
} yaflEKFRobustSt; /*Robust EKF*/
/*---------------------------------------------------------------------------*/
#define YAFL_EKF_ROBUST_INITIALIZER(_f, _jf, _h, _jh, _zrf, _g, _gdot, \
_nx, _nz, _rff, _qff, _mem) \
{ \
.base = YAFL_EKF_BASE_INITIALIZER(_f, _jf, _h, _jh, _zrf, _nx, _nz, \
_rff, _qff, _mem), \
.g = _g, \
.gdot = _gdot \
}
/*---------------------------------------------------------------------------*/
YAFL_EKF_PREDICT_WRAPPER(_yafl_rob_ekf_predict_wrapper, yaflEKFRobustSt)
/*-----------------------------------------------------------------------------
Robust Bierman filter
-----------------------------------------------------------------------------*/
#define YAFL_EKF_ROBUST_BIERAMN_PREDICT _yafl_rob_ekf_predict_wrapper
YAFL_EKF_UPDATE_IMPL(yafl_ekf_robust_bierman_update, yaflEKFRobustSt)
/*-----------------------------------------------------------------------------
Robust Joseph filter
-----------------------------------------------------------------------------*/
#define YAFL_EKF_ROBUST_JOSEPH_PREDICT _yafl_rob_ekf_predict_wrapper
YAFL_EKF_UPDATE_IMPL(yafl_ekf_robust_joseph_update, yaflEKFRobustSt)
/*=============================================================================
Adaptive robust UD-factorized EKF definitions
=============================================================================*/
typedef struct {
yaflEKFRobustSt base;
yaflFloat chi2; /*Divergence test threshold (chi-squared criteria)*/
} yaflEKFAdaptiveRobustSt; /*Robust EKF*/
/*---------------------------------------------------------------------------*/
#define YAFL_EKF_ADAPTIVE_ROBUST_INITIALIZER(_f, _jf, _h, _jh, _zrf, _g, _gdot, \
_nx, _nz, _rff, _qff, _chi2, _mem) \
{ \
.base = YAFL_EKF_ROBUST_INITIALIZER(_f, _jf, _h, _jh, _zrf, _g, _gdot, \
_nx, _nz, _rff, _qff, _mem), \
.chi2 = _chi2 \
}
/*
A good value of chi2 for yaflEKFAdaptiveRobustSt is:
scipy.stats.chi2.ppf(0.997, 1) == 8.807468393511947
*/
/*---------------------------------------------------------------------------*/
YAFL_EKF_PREDICT_WRAPPER(_yafl_ada_rob_predict_wrapper, \
yaflEKFAdaptiveRobustSt)
/*-----------------------------------------------------------------------------
Adaptive Bierman filter
-----------------------------------------------------------------------------*/
#define YAFL_EKF_ADAPTIVE_ROBUST_BIERAMN_PREDICT _yafl_ada_rob_predict_wrapper
YAFL_EKF_UPDATE_IMPL(yafl_ekf_adaptive_robust_bierman_update, \
yaflEKFAdaptiveRobustSt)
/*-----------------------------------------------------------------------------
Adaptive Joseph filter
-----------------------------------------------------------------------------*/
#define YAFL_EKF_ADAPTIVE_ROBUST_JOSEPH_PREDICT \
_yafl_ada_rob_predict_wrapper
YAFL_EKF_UPDATE_IMPL(yafl_ekf_adaptive_robust_joseph_update, \
yaflEKFAdaptiveRobustSt)
/*=============================================================================
Basic UD-factorized UKF definitions
=============================================================================*/
typedef struct _yaflUKFBaseSt yaflUKFBaseSt; /* The UKF base type */
/*
Used to add delta vectors to initial point in sigma point generation.
Parameters:
yaflFloat * x0
yaflFloat * delta_x
yaflFloat factor
Does:
delta_x = x0 + factor * delta_x
*/
typedef yaflStatusEn (* yaflUKFSigmaAddP)(yaflUKFBaseSt *, yaflFloat *, \
yaflFloat *, yaflFloat);
/*Sigma point generator info base type*/
typedef struct _yaflUKFSigmaSt {
yaflInt np; /* The number of sigma points */
yaflUKFSigmaAddP addf; /* Sigma point addition function */
} yaflUKFSigmaSt;
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_SIGMA_BASE_INITIALIZER(_np, _addf, _mem) \
{ \
.np = (yaflInt)_np, \
.addf = (yaflUKFSigmaAddP)_addf, \
}
/*---------------------------------------------------------------------------*/
/* Computes sigma points weights */
typedef yaflStatusEn (* yafkUKFSigmaGenWeigthsP)(yaflUKFBaseSt *);
/* Generates sigma points */
typedef yaflStatusEn (* yaflUKFSigmaGenSigmasP)(yaflUKFBaseSt *);
typedef struct _yaflUKFSigmaMethodsSt {
yafkUKFSigmaGenWeigthsP wf; /* Weight function */
yaflUKFSigmaGenSigmasP spgf; /* Sigma point generator function */
} yaflUKFSigmaMethodsSt;
/*---------------------------------------------------------------------------*/
struct _yaflUKFBaseSt {
yaflKalmanBaseSt base;
/* A pointer to the sigma point generator structure */
yaflUKFSigmaSt * sp_info;
/* A sigma point generator method table pointer */
const yaflUKFSigmaMethodsSt * sp_meth;
yaflKalmanFuncP xmf; /* State mean function */
yaflKalmanResFuncP xrf; /* State residual function function */
yaflKalmanFuncP zmf; /* Measurement mean function function */
yaflFloat * zp; /* Predicted measurement vector */
/*Scratchpad memory*/
yaflFloat * Sx; /* State */
yaflFloat * Sz; /* Measurement */
yaflFloat * Pzx; /* Pzx cross covariance matrix */
yaflFloat * sigmas_x; /* State sigma points */
yaflFloat * sigmas_z; /* Measurement sigma points */
yaflFloat * wm; /* Weights for mean calculations */
yaflFloat * wc; /* Weights for covariance calculations */
};
/*---------------------------------------------------------------------------*/
/*
Warning: sigmas_x and _sigmas_z aren't defined in this mixin, see
sigma points generators mixins!!!
*/
#define YAFL_UKF_BASE_MEMORY_MIXIN(nx, nz) \
YAFL_KALMAN_BASE_MEMORY_MIXIN(nx, nz); \
yaflFloat zp[nz]; \
yaflFloat Sx[nx]; \
yaflFloat Sz[nz]; \
yaflFloat Pzx[nz * nx]
/*---------------------------------------------------------------------------*/
/*
Sigma point memory mixin.
WARNING:
1. _SIGMAS_X and _SIGMAS_Z must be the parts of some larger
memory pool which has minimum size of (nx + nz) * (nz + 1)
or np * (nx + nz) where np is number of sigma points
2. _SIGMAS_X must be at start of this pool
*/
#define YAFL_UKF_SP_MEMORY_MIXIN(np, nx, nz) \
yaflFloat wm[np]; \
yaflFloat wc[np]; \
union{ \
struct { \
yaflFloat x[(np) * nx]; \
yaflFloat z[(np) * nz]; \
} sigmas; \
yaflFloat r_update_buf[(nx + nz) * (nz + 1)]; \
} pool
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_BASE_INITIALIZER(_p, _pm, _f, _xmf, _xrf, _h, _zmf, _zrf, \
_nx, _nz, _rff, _mem) \
{ \
.base = YAFL_KALMAN_BASE_INITIALIZER(_f, _h, _zrf, _nx, _nz, _rff, _mem), \
\
.sp_info = _p, \
.sp_meth = _pm, \
\
.xmf = (yaflKalmanFuncP)_xmf, \
.xrf = (yaflKalmanResFuncP)_xrf, \
\
.zmf = (yaflKalmanFuncP)_zmf, \
\
.zp = _mem.zp, \
\
.Sx = _mem.Sx, \
.Sz = _mem.Sz, \
.Pzx = _mem.Pzx, \
\
.sigmas_x = _mem.pool.sigmas.x, \
.sigmas_z = _mem.pool.sigmas.z, \
\
.wm = _mem.wm, \
.wc = _mem.wc \
}
/*---------------------------------------------------------------------------*/
static inline yaflStatusEn yafl_ukf_post_init(yaflUKFBaseSt * self)
{
YAFL_CHECK(self, YAFL_ST_INV_ARG_1);
YAFL_CHECK(self->sp_meth, YAFL_ST_INV_ARG_1);
YAFL_CHECK(self->sp_meth->wf, YAFL_ST_INV_ARG_1);
return self->sp_meth->wf(self); /*Need to compute weights before start*/
}
static inline yaflStatusEn yafl_ukf_gen_sigmas(yaflUKFBaseSt * self)
{
YAFL_CHECK(self, YAFL_ST_INV_ARG_1);
YAFL_CHECK(self->sp_meth, YAFL_ST_INV_ARG_1);
YAFL_CHECK(self->sp_meth->spgf, YAFL_ST_INV_ARG_1);
self->sp_meth->spgf(self);
return self->sp_meth->wf(self);
}
yaflStatusEn yafl_ukf_base_predict(yaflUKFBaseSt * self);
yaflStatusEn yafl_ukf_base_update(yaflUKFBaseSt * self, yaflFloat * z, \
yaflKalmanScalarUpdateP scalar_update);
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_PREDICT_WRAPPER(func, self_type) \
YAFL_KALMAN_PREDICT_WRAPPER(yafl_ukf_base_predict, yaflUKFBaseSt, \
func, self_type)
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_UPDATE_IMPL(func, self_type) \
YAFL_KALMAN_UPDATE_IMPL(yafl_ukf_base_update, yaflUKFBaseSt, \
func, self_type)
/*=============================================================================
Bierman UKF
=============================================================================*/
YAFL_UKF_PREDICT_WRAPPER(yafl_ukf_bierman_predict, yaflUKFBaseSt)
YAFL_UKF_UPDATE_IMPL(yafl_ukf_bierman_update, yaflUKFBaseSt)
/*=============================================================================
Adaptive Bierman UKF
=============================================================================*/
typedef struct {
yaflUKFBaseSt base;
yaflFloat chi2;
} yaflUKFAdaptivedSt;
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_ADAPTIVE_INITIALIZER(_p, _pm, _f, _xmf, _xrf, _h, _zmf, \
_zrf, _nx, _nz, _rff, _chi2, _mem) \
{ \
.base = YAFL_UKF_BASE_INITIALIZER(_p, _pm, _f, _xmf, _xrf, _h, \
_zmf, _zrf, _nx, _nz, _rff, _mem) , \
.chi2 = _chi2 \
}
/*
A good value of chi2 for yaflUKFAdaptivedSt is:
scipy.stats.chi2.ppf(0.999, 1) == 10.827566170662733
*/
/*---------------------------------------------------------------------------*/
YAFL_UKF_PREDICT_WRAPPER(yafl_ukf_adaptive_bierman_predict, yaflUKFAdaptivedSt)
YAFL_UKF_UPDATE_IMPL(yafl_ukf_adaptive_bierman_update, yaflUKFAdaptivedSt)
/*=============================================================================
Robust Bierman UKF
=============================================================================*/
typedef yaflFloat (* yaflUKFRobFuncP)(yaflUKFBaseSt *, yaflFloat);
typedef struct {
yaflUKFBaseSt base;
yaflKalmanRobFuncP g; /* g = -d(ln(pdf(y))) / dy */
yaflKalmanRobFuncP gdot; /* gdot = G = d(g) / dy */
} yaflUKFRobustSt; /*Robust UKF*/
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_ROBUST_INITIALIZER(_p, _pm, _f, _xmf, _xrf, _h, _zmf, _zrf, \
_g, _gdot, _nx, _nz, _rff, _mem) \
{ \
.base = YAFL_UKF_BASE_INITIALIZER(_p, _pm, _f, _xmf, _xrf, _h, _zmf, \
_zrf, _nx, _nz, _rff, _mem) , \
.g = _g, \
.gdot = _gdot \
}
/*---------------------------------------------------------------------------*/
YAFL_UKF_PREDICT_WRAPPER(yafl_ukf_robust_bierman_predict, yaflUKFRobustSt)
YAFL_UKF_UPDATE_IMPL(yafl_ukf_robust_bierman_update, yaflUKFRobustSt)
/*=============================================================================
Adaptive robust Bierman UKF
=============================================================================*/
typedef struct {
yaflUKFRobustSt base;
yaflFloat chi2; /*Divergence test threshold (chi-squared criteria)*/
} yaflUKFAdaptiveRobustSt; /*Robust EKF*/
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_ADAPTIVE_ROBUST_INITIALIZER(_p, _pm, _f, _xmf, _xrf, _h, \
_zmf, _zrf, _g, _gdot, _nx, \
_nz, _rff, _chi2, _mem) \
{ \
.base = YAFL_UKF_ROBUST_INITIALIZER(_p, _pm, _f, _xmf, _xrf, _h, _zmf, _zrf, \
_g, _gdot, _nx, _nz, _rff, _mem), \
.chi2 = _chi2 \
}
/*
A good value of chi2 for yaflUKFAdaptiveRobustSt is:
scipy.stats.chi2.ppf(0.997, 1) == 8.807468393511947
*/
/*---------------------------------------------------------------------------*/
YAFL_UKF_PREDICT_WRAPPER(yafl_ukf_adaptive_robust_bierman_predict, \
yaflUKFAdaptiveRobustSt)
YAFL_UKF_UPDATE_IMPL(yafl_ukf_adaptive_robust_bierman_update, \
yaflUKFAdaptiveRobustSt)
/*=============================================================================
Full UKF, not sequential square root version of UKF
=============================================================================*/
typedef struct {
yaflUKFBaseSt base; /* Base type */
yaflFloat * Us; /* Upper triangular part of S */
yaflFloat * Ds; /* Diagonal part of S */
} yaflUKFSt;
/*---------------------------------------------------------------------------*/
/*
Warning: sigmas_x and _sigmas_z aren't defined in this mixin, see
sigma points generators mixins!!!
*/
#define YAFL_UKF_MEMORY_MIXIN(nx, nz) \
YAFL_UKF_BASE_MEMORY_MIXIN(nx, nz); \
yaflFloat Us[((nz - 1) * nz)/2]; \
yaflFloat Ds[nz]
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_INITIALIZER(_p, _pm, _f, _xmf, _xrf, _h, _zmf, \
_zrf, _nx, _nz, _rff, _mem) \
{ \
.base = YAFL_UKF_BASE_INITIALIZER(_p, _pm, _f, _xmf, _xrf, _h, _zmf, \
_zrf, _nx, _nz, _rff, _mem), \
.Us = _mem.Us, \
.Ds = _mem.Ds \
}
/*---------------------------------------------------------------------------*/
YAFL_UKF_PREDICT_WRAPPER(yafl_ukf_predict, yaflUKFSt)
yaflStatusEn yafl_ukf_update(yaflUKFBaseSt * self, yaflFloat * z);
/*=============================================================================
Full adaptive UKF, not sequential square root version of UKF
=============================================================================*/
typedef struct {
yaflUKFSt base; /* Base type */
yaflFloat chi2; /*Divergence test threshold (chi-squared criteria)*/
} yaflUKFFullAdapiveSt;
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_FULL_ADAPTIVE_INITIALIZER(_p, _pm, _f, _xmf, _xrf, _h, \
_zmf, _zrf, _nx, _nz, \
_rff, _chi2, _mem) \
{ \
.base = YAFL_UKF_INITIALIZER(_p, _pm, _f, _xmf, _xrf, _h, _zmf, _zrf, \
_nx, _nz, _rff, _mem), \
.chi2 = _chi2 \
}
/*---------------------------------------------------------------------------*/
static inline \
yaflStatusEn yafl_ukf_adaptive_predict(yaflUKFFullAdapiveSt * self)
{
return yafl_ukf_predict((yaflUKFSt *)self);
}
yaflStatusEn yafl_ukf_adaptive_update(yaflUKFBaseSt * self, yaflFloat * z);
/*=============================================================================
Van der Merwe sigma point generator
=============================================================================*/
typedef struct _yaflUKFMerweSt {
yaflUKFSigmaSt base;
yaflFloat alpha;
yaflFloat beta;
yaflFloat kappa;
} yaflUKFMerweSt;
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_MERWE_MEMORY_MIXIN(nx, nz) \
YAFL_UKF_SP_MEMORY_MIXIN(2 * nx + 1, nx, nz)
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_MERWE_INITIALIZER(_nx, _addf, _alpha, _beta, _kappa, _mem) \
{ \
.base = YAFL_UKF_SIGMA_BASE_INITIALIZER((2 * _nx + 1), _addf, _mem), \
.alpha = _alpha, \
.beta = _beta, \
.kappa = _kappa \
}
/*---------------------------------------------------------------------------*/
extern const yaflUKFSigmaMethodsSt yafl_ukf_merwe_spm;
/*=============================================================================
Julier sigma point generator
=============================================================================*/
typedef struct _yaflUKFJulierSt {
yaflUKFSigmaSt base;
yaflFloat kappa;
} yaflUKFJulierSt;
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_JULIER_MEMORY_MIXIN(nx, nz) \
YAFL_UKF_SP_MEMORY_MIXIN(2 * nx + 1, nx, nz)
/*---------------------------------------------------------------------------*/
#define YAFL_UKF_JULIER_INITIALIZER(_nx, _addf, _kappa, _mem) \
{ \
.base = YAFL_UKF_SIGMA_BASE_INITIALIZER((2 * _nx + 1), _addf, _mem), \
.kappa = _kappa \
}
/*---------------------------------------------------------------------------*/
extern const yaflUKFSigmaMethodsSt yafl_ukf_julier_spm;
#endif // YAFL_H