/
estimator_kalman.c
745 lines (612 loc) · 23.8 KB
/
estimator_kalman.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
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
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
/**
* Authored by Michael Hamer (http://www.mikehamer.info), June 2016
* Thank you to Mark Mueller (www.mwm.im) for advice during implementation,
* and for derivation of the original filter in the below-cited paper.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, in version 3.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
* ============================================================================
*
* The Kalman filter implemented in this file is based on the papers:
*
* "Fusing ultra-wideband range measurements with accelerometers and rate gyroscopes for quadrocopter state estimation"
* http://ieeexplore.ieee.org/xpl/articleDetails.jsp?arnumber=7139421
*
* and
*
* "Covariance Correction Step for Kalman Filtering with an Attitude"
* http://arc.aiaa.org/doi/abs/10.2514/1.G000848
*
* Academic citation would be appreciated.
*
* BIBTEX ENTRIES:
@INPROCEEDINGS{MuellerHamerUWB2015,
author = {Mueller, Mark W and Hamer, Michael and D’Andrea, Raffaello},
title = {Fusing ultra-wideband range measurements with accelerometers and rate gyroscopes for quadrocopter state estimation},
booktitle = {2015 IEEE International Conference on Robotics and Automation (ICRA)},
year = {2015},
month = {May},
pages = {1730-1736},
doi = {10.1109/ICRA.2015.7139421},
ISSN = {1050-4729}}
@ARTICLE{MuellerCovariance2016,
author={Mueller, Mark W and Hehn, Markus and D’Andrea, Raffaello},
title={Covariance Correction Step for Kalman Filtering with an Attitude},
journal={Journal of Guidance, Control, and Dynamics},
pages={1--7},
year={2016},
publisher={American Institute of Aeronautics and Astronautics}}
*
* ============================================================================
*
* MAJOR CHANGELOG:
* 2016.06.28, Mike Hamer: Initial version
* 2019.04.12, Kristoffer Richardsson: Refactored, separated kalman implementation from OS related functionality
*
*/
#include "kalman_core.h"
#include "estimator_kalman.h"
#include "kalman_supervisor.h"
#include "FreeRTOS.h"
#include "queue.h"
#include "task.h"
#include "semphr.h"
#include "sensors.h"
#include "static_mem.h"
#include "system.h"
#include "log.h"
#include "param.h"
#include "physicalConstants.h"
#include "statsCnt.h"
#define DEBUG_MODULE "ESTKALMAN"
#include "debug.h"
// #define KALMAN_USE_BARO_UPDATE
/**
* Additionally, the filter supports the incorporation of additional sensors into the state estimate
*
* This is done via the external functions:
* - bool estimatorKalmanEnqueueUWBPacket(uwbPacket_t *uwb)
* - bool estimatorKalmanEnqueuePosition(positionMeasurement_t *pos)
* - bool estimatorKalmanEnqueueDistance(distanceMeasurement_t *dist)
*
* As well as by the following internal functions and datatypes
*/
// Distance-to-point measurements
static xQueueHandle distDataQueue;
STATIC_MEM_QUEUE_ALLOC(distDataQueue, 10, sizeof(distanceMeasurement_t));
static inline bool stateEstimatorHasDistanceMeasurement(distanceMeasurement_t *dist) {
return (pdTRUE == xQueueReceive(distDataQueue, dist, 0));
}
// Direct measurements of Crazyflie position
static xQueueHandle posDataQueue;
STATIC_MEM_QUEUE_ALLOC(posDataQueue, 10, sizeof(positionMeasurement_t));
static inline bool stateEstimatorHasPositionMeasurement(positionMeasurement_t *pos) {
return (pdTRUE == xQueueReceive(posDataQueue, pos, 0));
}
// Direct measurements of Crazyflie pose
static xQueueHandle poseDataQueue;
STATIC_MEM_QUEUE_ALLOC(poseDataQueue, 10, sizeof(poseMeasurement_t));
static inline bool stateEstimatorHasPoseMeasurement(poseMeasurement_t *pose) {
return (pdTRUE == xQueueReceive(poseDataQueue, pose, 0));
}
// Measurements of a UWB Tx/Rx
static xQueueHandle tdoaDataQueue;
STATIC_MEM_QUEUE_ALLOC(tdoaDataQueue, 10, sizeof(tdoaMeasurement_t));
static inline bool stateEstimatorHasTDOAPacket(tdoaMeasurement_t *uwb) {
return (pdTRUE == xQueueReceive(tdoaDataQueue, uwb, 0));
}
// Measurements of flow (dnx, dny)
static xQueueHandle flowDataQueue;
STATIC_MEM_QUEUE_ALLOC(flowDataQueue, 10, sizeof(flowMeasurement_t));
static inline bool stateEstimatorHasFlowPacket(flowMeasurement_t *flow) {
return (pdTRUE == xQueueReceive(flowDataQueue, flow, 0));
}
// Measurements of TOF from laser sensor
static xQueueHandle tofDataQueue;
STATIC_MEM_QUEUE_ALLOC(tofDataQueue, 10, sizeof(tofMeasurement_t));
static inline bool stateEstimatorHasTOFPacket(tofMeasurement_t *tof) {
return (pdTRUE == xQueueReceive(tofDataQueue, tof, 0));
}
// Absolute height measurement along the room Z
static xQueueHandle heightDataQueue;
STATIC_MEM_QUEUE_ALLOC(heightDataQueue, 10, sizeof(heightMeasurement_t));
static inline bool stateEstimatorHasHeightPacket(heightMeasurement_t *height) {
return (pdTRUE == xQueueReceive(heightDataQueue, height, 0));
}
static xQueueHandle yawErrorDataQueue;
STATIC_MEM_QUEUE_ALLOC(yawErrorDataQueue, 10, sizeof(yawErrorMeasurement_t));
static inline bool stateEstimatorHasYawErrorPacket(yawErrorMeasurement_t *error)
{
return (pdTRUE == xQueueReceive(yawErrorDataQueue, error, 0));
}
static xQueueHandle sweepAnglesDataQueue;
STATIC_MEM_QUEUE_ALLOC(sweepAnglesDataQueue, 10, sizeof(sweepAngleMeasurement_t));
static inline bool stateEstimatorHasSweepAnglesPacket(sweepAngleMeasurement_t *angles)
{
return (pdTRUE == xQueueReceive(sweepAnglesDataQueue, angles, 0));
}
// Semaphore to signal that we got data from the stabilzer loop to process
static SemaphoreHandle_t runTaskSemaphore;
// Mutex to protect data that is shared between the task and
// functions called by the stabilizer loop
static SemaphoreHandle_t dataMutex;
static StaticSemaphore_t dataMutexBuffer;
/**
* Constants used in the estimator
*/
#define CRAZYFLIE_WEIGHT_grams (27.0f)
//thrust is thrust mapped for 65536 <==> 60 GRAMS!
#define CONTROL_TO_ACC (GRAVITY_MAGNITUDE*60.0f/CRAZYFLIE_WEIGHT_grams/65536.0f)
/**
* Tuning parameters
*/
#define PREDICT_RATE RATE_100_HZ // this is slower than the IMU update rate of 500Hz
#define BARO_RATE RATE_25_HZ
// the point at which the dynamics change from stationary to flying
#define IN_FLIGHT_THRUST_THRESHOLD (GRAVITY_MAGNITUDE*0.1f)
#define IN_FLIGHT_TIME_THRESHOLD (500)
// The bounds on the covariance, these shouldn't be hit, but sometimes are... why?
#define MAX_COVARIANCE (100)
#define MIN_COVARIANCE (1e-6f)
/**
* Quadrocopter State
*
* The internally-estimated state is:
* - X, Y, Z: the quad's position in the global frame
* - PX, PY, PZ: the quad's velocity in its body frame
* - D0, D1, D2: attitude error
*
* For more information, refer to the paper
*/
NO_DMA_CCM_SAFE_ZERO_INIT static kalmanCoreData_t coreData;
/**
* Internal variables. Note that static declaration results in default initialization (to 0)
*/
static bool isInit = false;
static Axis3f accAccumulator;
static float thrustAccumulator;
static Axis3f gyroAccumulator;
static float baroAslAccumulator;
static uint32_t accAccumulatorCount;
static uint32_t thrustAccumulatorCount;
static uint32_t gyroAccumulatorCount;
static uint32_t baroAccumulatorCount;
static bool quadIsFlying = false;
static uint32_t lastFlightCmd;
static uint32_t takeoffTime;
// Data used to enable the task and stabilizer loop to run with minimal locking
static state_t taskEstimatorState; // The estimator state produced by the task, copied to the stabilzer when needed.
static Axis3f gyroSnapshot; // A snpashot of the latest gyro data, used by the task
static Axis3f accSnapshot; // A snpashot of the latest acc data, used by the task
// Statistics
#define ONE_SECOND 1000
static STATS_CNT_RATE_DEFINE(updateCounter, ONE_SECOND);
static STATS_CNT_RATE_DEFINE(predictionCounter, ONE_SECOND);
static STATS_CNT_RATE_DEFINE(baroUpdateCounter, ONE_SECOND);
static STATS_CNT_RATE_DEFINE(finalizeCounter, ONE_SECOND);
static STATS_CNT_RATE_DEFINE(measurementAppendedCounter, ONE_SECOND);
static STATS_CNT_RATE_DEFINE(measurementNotAppendedCounter, ONE_SECOND);
#ifdef KALMAN_USE_BARO_UPDATE
static const bool useBaroUpdate = true;
#else
static const bool useBaroUpdate = false;
#endif
/**
* Supporting and utility functions
*/
static inline void mat_trans(const arm_matrix_instance_f32 * pSrc, arm_matrix_instance_f32 * pDst)
{ configASSERT(ARM_MATH_SUCCESS == arm_mat_trans_f32(pSrc, pDst)); }
static inline void mat_inv(const arm_matrix_instance_f32 * pSrc, arm_matrix_instance_f32 * pDst)
{ configASSERT(ARM_MATH_SUCCESS == arm_mat_inverse_f32(pSrc, pDst)); }
static inline void mat_mult(const arm_matrix_instance_f32 * pSrcA, const arm_matrix_instance_f32 * pSrcB, arm_matrix_instance_f32 * pDst)
{ configASSERT(ARM_MATH_SUCCESS == arm_mat_mult_f32(pSrcA, pSrcB, pDst)); }
static inline float arm_sqrt(float32_t in)
{ float pOut = 0; arm_status result = arm_sqrt_f32(in, &pOut); configASSERT(ARM_MATH_SUCCESS == result); return pOut; }
static void kalmanTask(void* parameters);
static bool predictStateForward(uint32_t osTick, float dt);
static bool updateQueuedMeasurments(const Axis3f *gyro, const uint32_t tick);
STATIC_MEM_TASK_ALLOC_STACK_NO_DMA_CCM_SAFE(kalmanTask, 3 * configMINIMAL_STACK_SIZE);
// --------------------------------------------------
// Called one time during system startup
void estimatorKalmanTaskInit() {
distDataQueue = STATIC_MEM_QUEUE_CREATE(distDataQueue);
posDataQueue = STATIC_MEM_QUEUE_CREATE(posDataQueue);
poseDataQueue = STATIC_MEM_QUEUE_CREATE(poseDataQueue);
tdoaDataQueue = STATIC_MEM_QUEUE_CREATE(tdoaDataQueue);
flowDataQueue = STATIC_MEM_QUEUE_CREATE(flowDataQueue);
tofDataQueue = STATIC_MEM_QUEUE_CREATE(tofDataQueue);
heightDataQueue = STATIC_MEM_QUEUE_CREATE(heightDataQueue);
yawErrorDataQueue = STATIC_MEM_QUEUE_CREATE(yawErrorDataQueue);
sweepAnglesDataQueue = STATIC_MEM_QUEUE_CREATE(sweepAnglesDataQueue);
vSemaphoreCreateBinary(runTaskSemaphore);
dataMutex = xSemaphoreCreateMutexStatic(&dataMutexBuffer);
STATIC_MEM_TASK_CREATE(kalmanTask, kalmanTask, KALMAN_TASK_NAME, NULL, KALMAN_TASK_PRI);
isInit = true;
}
bool estimatorKalmanTaskTest() {
return isInit;
}
static void kalmanTask(void* parameters) {
systemWaitStart();
uint32_t lastPrediction = xTaskGetTickCount();
uint32_t nextPrediction = xTaskGetTickCount();
uint32_t lastPNUpdate = xTaskGetTickCount();
uint32_t nextBaroUpdate = xTaskGetTickCount();
while (true) {
xSemaphoreTake(runTaskSemaphore, portMAX_DELAY);
// If the client triggers an estimator reset via parameter update
if (coreData.resetEstimation) {
estimatorKalmanInit();
coreData.resetEstimation = false;
}
// Tracks whether an update to the state has been made, and the state therefore requires finalization
bool doneUpdate = false;
uint32_t osTick = xTaskGetTickCount(); // would be nice if this had a precision higher than 1ms...
#ifdef KALMAN_DECOUPLE_XY
kalmanCoreDecoupleXY(&coreData);
#endif
// Run the system dynamics to predict the state forward.
if (osTick >= nextPrediction) { // update at the PREDICT_RATE
float dt = T2S(osTick - lastPrediction);
if (predictStateForward(osTick, dt)) {
lastPrediction = osTick;
doneUpdate = true;
STATS_CNT_RATE_EVENT(&predictionCounter);
}
nextPrediction = osTick + S2T(1.0f / PREDICT_RATE);
}
/**
* Add process noise every loop, rather than every prediction
*/
{
float dt = T2S(osTick - lastPNUpdate);
if (dt > 0.0f) {
kalmanCoreAddProcessNoise(&coreData, dt);
lastPNUpdate = osTick;
}
}
/**
* Update the state estimate with the barometer measurements
*/
// Accumulate the barometer measurements
if (useBaroUpdate) {
if (osTick > nextBaroUpdate // update at BARO_RATE
&& baroAccumulatorCount > 0)
{
xSemaphoreTake(dataMutex, portMAX_DELAY);
float baroAslAverage = baroAslAccumulator / baroAccumulatorCount;
baroAslAccumulator = 0;
baroAccumulatorCount = 0;
xSemaphoreGive(dataMutex);
kalmanCoreUpdateWithBaro(&coreData, baroAslAverage, quadIsFlying);
nextBaroUpdate = osTick + S2T(1.0f / BARO_RATE);
doneUpdate = true;
STATS_CNT_RATE_EVENT(&baroUpdateCounter);
}
}
{
Axis3f gyro;
xSemaphoreTake(dataMutex, portMAX_DELAY);
memcpy(&gyro, &gyroSnapshot, sizeof(gyro));
xSemaphoreGive(dataMutex);
doneUpdate = doneUpdate || updateQueuedMeasurments(&gyro, osTick);
}
/**
* If an update has been made, the state is finalized:
* - the attitude error is moved into the body attitude quaternion,
* - the body attitude is converted into a rotation matrix for the next prediction, and
* - correctness of the covariance matrix is ensured
*/
if (doneUpdate)
{
kalmanCoreFinalize(&coreData, osTick);
STATS_CNT_RATE_EVENT(&finalizeCounter);
if (! kalmanSupervisorIsStateWithinBounds(&coreData)) {
coreData.resetEstimation = true;
DEBUG_PRINT("State out of bounds, resetting\n");
}
}
/**
* Finally, the internal state is externalized.
* This is done every round, since the external state includes some sensor data
*/
xSemaphoreTake(dataMutex, portMAX_DELAY);
kalmanCoreExternalizeState(&coreData, &taskEstimatorState, &accSnapshot, osTick);
xSemaphoreGive(dataMutex);
STATS_CNT_RATE_EVENT(&updateCounter);
}
}
void estimatorKalman(state_t *state, sensorData_t *sensors, control_t *control, const uint32_t tick)
{
// This function is called from the stabilizer loop. It is important that this call returns
// as quickly as possible. The dataMutex must only be locked short periods by the task.
xSemaphoreTake(dataMutex, portMAX_DELAY);
// Average the last IMU measurements. We do this because the prediction loop is
// slower than the IMU loop, but the IMU information is required externally at
// a higher rate (for body rate control).
if (sensorsReadAcc(&sensors->acc)) {
accAccumulator.x += sensors->acc.x;
accAccumulator.y += sensors->acc.y;
accAccumulator.z += sensors->acc.z;
accAccumulatorCount++;
}
if (sensorsReadGyro(&sensors->gyro)) {
gyroAccumulator.x += sensors->gyro.x;
gyroAccumulator.y += sensors->gyro.y;
gyroAccumulator.z += sensors->gyro.z;
gyroAccumulatorCount++;
}
// Average the thrust command from the last time steps, generated externally by the controller
thrustAccumulator += control->thrust;
thrustAccumulatorCount++;
// Average barometer data
if (useBaroUpdate) {
if (sensorsReadBaro(&sensors->baro)) {
baroAslAccumulator += sensors->baro.asl;
baroAccumulatorCount++;
}
}
// Make a copy of sensor data to be used by the task
memcpy(&gyroSnapshot, &sensors->gyro, sizeof(gyroSnapshot));
memcpy(&accSnapshot, &sensors->acc, sizeof(accSnapshot));
// Copy the latest state, calculated by the task
memcpy(state, &taskEstimatorState, sizeof(state_t));
xSemaphoreGive(dataMutex);
xSemaphoreGive(runTaskSemaphore);
}
static bool predictStateForward(uint32_t osTick, float dt) {
if (gyroAccumulatorCount == 0
|| accAccumulatorCount == 0
|| thrustAccumulatorCount == 0)
{
return false;
}
xSemaphoreTake(dataMutex, portMAX_DELAY);
// gyro is in deg/sec but the estimator requires rad/sec
Axis3f gyroAverage;
gyroAverage.x = gyroAccumulator.x * DEG_TO_RAD / gyroAccumulatorCount;
gyroAverage.y = gyroAccumulator.y * DEG_TO_RAD / gyroAccumulatorCount;
gyroAverage.z = gyroAccumulator.z * DEG_TO_RAD / gyroAccumulatorCount;
// accelerometer is in Gs but the estimator requires ms^-2
Axis3f accAverage;
accAverage.x = accAccumulator.x * GRAVITY_MAGNITUDE / accAccumulatorCount;
accAverage.y = accAccumulator.y * GRAVITY_MAGNITUDE / accAccumulatorCount;
accAverage.z = accAccumulator.z * GRAVITY_MAGNITUDE / accAccumulatorCount;
// thrust is in grams, we need ms^-2
float thrustAverage = thrustAccumulator * CONTROL_TO_ACC / thrustAccumulatorCount;
accAccumulator = (Axis3f){.axis={0}};
accAccumulatorCount = 0;
gyroAccumulator = (Axis3f){.axis={0}};
gyroAccumulatorCount = 0;
thrustAccumulator = 0;
thrustAccumulatorCount = 0;
xSemaphoreGive(dataMutex);
// TODO: Find a better check for whether the quad is flying
// Assume that the flight begins when the thrust is large enough and for now we never stop "flying".
if (thrustAverage > IN_FLIGHT_THRUST_THRESHOLD) {
lastFlightCmd = osTick;
if (!quadIsFlying) {
takeoffTime = lastFlightCmd;
}
}
quadIsFlying = (osTick-lastFlightCmd) < IN_FLIGHT_TIME_THRESHOLD;
kalmanCorePredict(&coreData, thrustAverage, &accAverage, &gyroAverage, dt, quadIsFlying);
return true;
}
static bool updateQueuedMeasurments(const Axis3f *gyro, const uint32_t tick) {
bool doneUpdate = false;
/**
* Sensor measurements can come in sporadically and faster than the stabilizer loop frequency,
* we therefore consume all measurements since the last loop, rather than accumulating
*/
tofMeasurement_t tof;
while (stateEstimatorHasTOFPacket(&tof))
{
kalmanCoreUpdateWithTof(&coreData, &tof);
doneUpdate = true;
}
yawErrorMeasurement_t yawError;
while (stateEstimatorHasYawErrorPacket(&yawError))
{
kalmanCoreUpdateWithYawError(&coreData, &yawError);
doneUpdate = true;
}
heightMeasurement_t height;
while (stateEstimatorHasHeightPacket(&height))
{
kalmanCoreUpdateWithAbsoluteHeight(&coreData, &height);
doneUpdate = true;
}
distanceMeasurement_t dist;
while (stateEstimatorHasDistanceMeasurement(&dist))
{
kalmanCoreUpdateWithDistance(&coreData, &dist);
doneUpdate = true;
}
positionMeasurement_t pos;
while (stateEstimatorHasPositionMeasurement(&pos))
{
kalmanCoreUpdateWithPosition(&coreData, &pos);
doneUpdate = true;
}
poseMeasurement_t pose;
while (stateEstimatorHasPoseMeasurement(&pose))
{
kalmanCoreUpdateWithPose(&coreData, &pose);
doneUpdate = true;
}
tdoaMeasurement_t tdoa;
while (stateEstimatorHasTDOAPacket(&tdoa))
{
kalmanCoreUpdateWithTDOA(&coreData, &tdoa);
doneUpdate = true;
}
flowMeasurement_t flow;
while (stateEstimatorHasFlowPacket(&flow))
{
kalmanCoreUpdateWithFlow(&coreData, &flow, gyro);
doneUpdate = true;
}
sweepAngleMeasurement_t angles;
while (stateEstimatorHasSweepAnglesPacket(&angles))
{
kalmanCoreUpdateWithSweepAngles(&coreData, &angles, tick);
doneUpdate = true;
}
return doneUpdate;
}
// Called when this estimator is activated
void estimatorKalmanInit(void) {
xQueueReset(distDataQueue);
xQueueReset(posDataQueue);
xQueueReset(poseDataQueue);
xQueueReset(tdoaDataQueue);
xQueueReset(flowDataQueue);
xQueueReset(tofDataQueue);
xSemaphoreTake(dataMutex, portMAX_DELAY);
accAccumulator = (Axis3f){.axis={0}};
gyroAccumulator = (Axis3f){.axis={0}};
thrustAccumulator = 0;
baroAslAccumulator = 0;
accAccumulatorCount = 0;
gyroAccumulatorCount = 0;
thrustAccumulatorCount = 0;
baroAccumulatorCount = 0;
xSemaphoreGive(dataMutex);
kalmanCoreInit(&coreData);
}
static bool appendMeasurement(xQueueHandle queue, void *measurement)
{
portBASE_TYPE result;
bool isInInterrupt = (SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk) != 0;
if (isInInterrupt) {
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
result = xQueueSendFromISR(queue, measurement, &xHigherPriorityTaskWoken);
if(xHigherPriorityTaskWoken == pdTRUE)
{
portYIELD();
}
} else {
result = xQueueSend(queue, measurement, 0);
}
if (result == pdTRUE) {
STATS_CNT_RATE_EVENT(&measurementAppendedCounter);
return true;
} else {
STATS_CNT_RATE_EVENT(&measurementNotAppendedCounter);
return true;
}
}
bool estimatorKalmanEnqueueTDOA(const tdoaMeasurement_t *uwb)
{
ASSERT(isInit);
return appendMeasurement(tdoaDataQueue, (void *)uwb);
}
bool estimatorKalmanEnqueuePosition(const positionMeasurement_t *pos)
{
ASSERT(isInit);
return appendMeasurement(posDataQueue, (void *)pos);
}
bool estimatorKalmanEnqueuePose(const poseMeasurement_t *pose)
{
ASSERT(isInit);
return appendMeasurement(poseDataQueue, (void *)pose);
}
bool estimatorKalmanEnqueueDistance(const distanceMeasurement_t *dist)
{
ASSERT(isInit);
return appendMeasurement(distDataQueue, (void *)dist);
}
bool estimatorKalmanEnqueueFlow(const flowMeasurement_t *flow)
{
// A flow measurement (dnx, dny) [accumulated pixels]
ASSERT(isInit);
return appendMeasurement(flowDataQueue, (void *)flow);
}
bool estimatorKalmanEnqueueTOF(const tofMeasurement_t *tof)
{
// A distance (distance) [m] to the ground along the z_B axis.
ASSERT(isInit);
return appendMeasurement(tofDataQueue, (void *)tof);
}
bool estimatorKalmanEnqueueAbsoluteHeight(const heightMeasurement_t *height)
{
// A distance (height) [m] to the ground along the z axis.
ASSERT(isInit);
return appendMeasurement(heightDataQueue, (void *)height);
}
bool estimatorKalmanEnqueueYawError(const yawErrorMeasurement_t* error)
{
ASSERT(isInit);
return appendMeasurement(yawErrorDataQueue, (void *)error);
}
bool estimatorKalmanEnqueueSweepAngles(const sweepAngleMeasurement_t *angles)
{
ASSERT(isInit);
return appendMeasurement(sweepAnglesDataQueue, (void *)angles);
}
bool estimatorKalmanTest(void)
{
return isInit;
}
void estimatorKalmanGetEstimatedPos(point_t* pos) {
pos->x = coreData.S[KC_STATE_X];
pos->y = coreData.S[KC_STATE_Y];
pos->z = coreData.S[KC_STATE_Z];
}
void estimatorKalmanGetEstimatedRot(float * rotationMatrix) {
memcpy(rotationMatrix, coreData.R, 9*sizeof(float));
}
// Temporary development groups
LOG_GROUP_START(kalman_states)
LOG_ADD(LOG_FLOAT, ox, &coreData.S[KC_STATE_X])
LOG_ADD(LOG_FLOAT, oy, &coreData.S[KC_STATE_Y])
LOG_ADD(LOG_FLOAT, vx, &coreData.S[KC_STATE_PX])
LOG_ADD(LOG_FLOAT, vy, &coreData.S[KC_STATE_PY])
LOG_GROUP_STOP(kalman_states)
// Stock log groups
LOG_GROUP_START(kalman)
LOG_ADD(LOG_UINT8, inFlight, &quadIsFlying)
LOG_ADD(LOG_FLOAT, stateX, &coreData.S[KC_STATE_X])
LOG_ADD(LOG_FLOAT, stateY, &coreData.S[KC_STATE_Y])
LOG_ADD(LOG_FLOAT, stateZ, &coreData.S[KC_STATE_Z])
LOG_ADD(LOG_FLOAT, statePX, &coreData.S[KC_STATE_PX])
LOG_ADD(LOG_FLOAT, statePY, &coreData.S[KC_STATE_PY])
LOG_ADD(LOG_FLOAT, statePZ, &coreData.S[KC_STATE_PZ])
LOG_ADD(LOG_FLOAT, stateD0, &coreData.S[KC_STATE_D0])
LOG_ADD(LOG_FLOAT, stateD1, &coreData.S[KC_STATE_D1])
LOG_ADD(LOG_FLOAT, stateD2, &coreData.S[KC_STATE_D2])
LOG_ADD(LOG_FLOAT, varX, &coreData.P[KC_STATE_X][KC_STATE_X])
LOG_ADD(LOG_FLOAT, varY, &coreData.P[KC_STATE_Y][KC_STATE_Y])
LOG_ADD(LOG_FLOAT, varZ, &coreData.P[KC_STATE_Z][KC_STATE_Z])
LOG_ADD(LOG_FLOAT, varPX, &coreData.P[KC_STATE_PX][KC_STATE_PX])
LOG_ADD(LOG_FLOAT, varPY, &coreData.P[KC_STATE_PY][KC_STATE_PY])
LOG_ADD(LOG_FLOAT, varPZ, &coreData.P[KC_STATE_PZ][KC_STATE_PZ])
LOG_ADD(LOG_FLOAT, varD0, &coreData.P[KC_STATE_D0][KC_STATE_D0])
LOG_ADD(LOG_FLOAT, varD1, &coreData.P[KC_STATE_D1][KC_STATE_D1])
LOG_ADD(LOG_FLOAT, varD2, &coreData.P[KC_STATE_D2][KC_STATE_D2])
LOG_ADD(LOG_FLOAT, q0, &coreData.q[0])
LOG_ADD(LOG_FLOAT, q1, &coreData.q[1])
LOG_ADD(LOG_FLOAT, q2, &coreData.q[2])
LOG_ADD(LOG_FLOAT, q3, &coreData.q[3])
STATS_CNT_RATE_LOG_ADD(rtUpdate, &updateCounter)
STATS_CNT_RATE_LOG_ADD(rtPred, &predictionCounter)
STATS_CNT_RATE_LOG_ADD(rtBaro, &baroUpdateCounter)
STATS_CNT_RATE_LOG_ADD(rtFinal, &finalizeCounter)
STATS_CNT_RATE_LOG_ADD(rtApnd, &measurementAppendedCounter)
STATS_CNT_RATE_LOG_ADD(rtRej, &measurementNotAppendedCounter)
LOG_GROUP_STOP(kalman)
PARAM_GROUP_START(kalman)
PARAM_ADD(PARAM_UINT8, resetEstimation, &coreData.resetEstimation)
PARAM_ADD(PARAM_UINT8, quadIsFlying, &quadIsFlying)
PARAM_GROUP_STOP(kalman)