This repository has been archived by the owner on May 1, 2024. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 510
/
Copy pathekf_helper.cpp
1746 lines (1426 loc) · 61 KB
/
ekf_helper.cpp
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
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/****************************************************************************
*
* Copyright (c) 2015 Estimation and Control Library (ECL). All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name ECL nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file ekf_helper.cpp
* Definition of ekf helper functions.
*
* @author Roman Bast <[email protected]>
*
*/
#include "ekf.h"
#include <ecl.h>
#include <mathlib/mathlib.h>
#include <cstdlib>
// Reset the velocity states. If we have a recent and valid
// gps measurement then use for velocity initialisation
bool Ekf::resetVelocity()
{
// used to calculate the velocity change due to the reset
Vector3f vel_before_reset = _state.vel;
// reset EKF states
if (_control_status.flags.gps) {
// this reset is only called if we have new gps data at the fusion time horizon
_state.vel = _gps_sample_delayed.vel;
// use GPS accuracy to reset variances
setDiag(P, 4, 6, sq(_gps_sample_delayed.sacc));
} else if (_control_status.flags.opt_flow) {
// constrain height above ground to be above minimum possible
float heightAboveGndEst = fmaxf((_terrain_vpos - _state.pos(2)), _params.rng_gnd_clearance);
// calculate absolute distance from focal point to centre of frame assuming a flat earth
float range = heightAboveGndEst / _R_rng_to_earth_2_2;
if ((range - _params.rng_gnd_clearance) > 0.3f && _flow_sample_delayed.dt > 0.05f) {
// we should have reliable OF measurements so
// calculate X and Y body relative velocities from OF measurements
Vector3f vel_optflow_body;
vel_optflow_body(0) = - range * _flowRadXYcomp(1) / _flow_sample_delayed.dt;
vel_optflow_body(1) = range * _flowRadXYcomp(0) / _flow_sample_delayed.dt;
vel_optflow_body(2) = 0.0f;
// rotate from body to earth frame
Vector3f vel_optflow_earth;
vel_optflow_earth = _R_to_earth * vel_optflow_body;
// take x and Y components
_state.vel(0) = vel_optflow_earth(0);
_state.vel(1) = vel_optflow_earth(1);
} else {
_state.vel(0) = 0.0f;
_state.vel(1) = 0.0f;
}
// reset the velocity covariance terms
zeroRows(P, 4, 5);
zeroCols(P, 4, 5);
// reset the horizontal velocity variance using the optical flow noise variance
P[5][5] = P[4][4] = sq(range) * calcOptFlowMeasVar();
} else if (_control_status.flags.ev_pos) {
_state.vel.setZero();
zeroOffDiag(P, 4, 6);
} else {
// Used when falling back to non-aiding mode of operation
_state.vel(0) = 0.0f;
_state.vel(1) = 0.0f;
setDiag(P, 4, 5, 25.0f);
}
// calculate the change in velocity and apply to the output predictor state history
const Vector3f velocity_change = _state.vel - vel_before_reset;
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
_output_buffer[index].vel += velocity_change;
}
// apply the change in velocity to our newest velocity estimate
// which was already taken out from the output buffer
_output_new.vel += velocity_change;
// capture the reset event
_state_reset_status.velNE_change(0) = velocity_change(0);
_state_reset_status.velNE_change(1) = velocity_change(1);
_state_reset_status.velD_change = velocity_change(2);
_state_reset_status.velNE_counter++;
_state_reset_status.velD_counter++;
return true;
}
// Reset position states. If we have a recent and valid
// gps measurement then use for position initialisation
bool Ekf::resetPosition()
{
// used to calculate the position change due to the reset
Vector2f posNE_before_reset;
posNE_before_reset(0) = _state.pos(0);
posNE_before_reset(1) = _state.pos(1);
// let the next odometry update know that the previous value of states cannot be used to calculate the change in position
_hpos_prev_available = false;
if (_control_status.flags.gps) {
// this reset is only called if we have new gps data at the fusion time horizon
_state.pos(0) = _gps_sample_delayed.pos(0);
_state.pos(1) = _gps_sample_delayed.pos(1);
// use GPS accuracy to reset variances
setDiag(P, 7, 8, sq(_gps_sample_delayed.hacc));
} else if (_control_status.flags.ev_pos) {
// this reset is only called if we have new ev data at the fusion time horizon
_state.pos(0) = _ev_sample_delayed.posNED(0);
_state.pos(1) = _ev_sample_delayed.posNED(1);
// use EV accuracy to reset variances
setDiag(P, 7, 8, sq(_ev_sample_delayed.posErr));
} else if (_control_status.flags.opt_flow) {
if (!_control_status.flags.in_air) {
// we are likely starting OF for the first time so reset the horizontal position
_state.pos(0) = 0.0f;
_state.pos(1) = 0.0f;
} else {
// set to the last known position
_state.pos(0) = _last_known_posNE(0);
_state.pos(1) = _last_known_posNE(1);
}
// estimate is relative to initial positon in this mode, so we start with zero error.
zeroCols(P,7,8);
zeroRows(P,7,8);
} else {
// Used when falling back to non-aiding mode of operation
_state.pos(0) = _last_known_posNE(0);
_state.pos(1) = _last_known_posNE(1);
setDiag(P, 7, 8, sq(_params.pos_noaid_noise));
}
// calculate the change in position and apply to the output predictor state history
const Vector2f posNE_change{_state.pos(0) - posNE_before_reset(0), _state.pos(1) - posNE_before_reset(1)};
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
_output_buffer[index].pos(0) += posNE_change(0);
_output_buffer[index].pos(1) += posNE_change(1);
}
// apply the change in position to our newest position estimate
// which was already taken out from the output buffer
_output_new.pos(0) += posNE_change(0);
_output_new.pos(1) += posNE_change(1);
// capture the reset event
_state_reset_status.posNE_change = posNE_change;
_state_reset_status.posNE_counter++;
return true;
}
// Reset height state using the last height measurement
void Ekf::resetHeight()
{
// Get the most recent GPS data
const gpsSample &gps_newest = _gps_buffer.get_newest();
// store the current vertical position and velocity for reference so we can calculate and publish the reset amount
float old_vert_pos = _state.pos(2);
bool vert_pos_reset = false;
float old_vert_vel = _state.vel(2);
bool vert_vel_reset = false;
// reset the vertical position
if (_control_status.flags.rng_hgt) {
rangeSample range_newest = _range_buffer.get_newest();
if (_time_last_imu - range_newest.time_us < 2 * RNG_MAX_INTERVAL) {
// correct the range data for position offset relative to the IMU
Vector3f pos_offset_body = _params.rng_pos_body - _params.imu_pos_body;
Vector3f pos_offset_earth = _R_to_earth * pos_offset_body;
range_newest.rng += pos_offset_earth(2) / _R_rng_to_earth_2_2;
// calculate the new vertical position using range sensor
float new_pos_down = _hgt_sensor_offset - range_newest.rng * _R_rng_to_earth_2_2;
// update the state and assoicated variance
_state.pos(2) = new_pos_down;
// reset the associated covariance values
zeroRows(P, 9, 9);
zeroCols(P, 9, 9);
// the state variance is the same as the observation
P[9][9] = sq(_params.range_noise);
vert_pos_reset = true;
// reset the baro offset which is subtracted from the baro reading if we need to use it as a backup
const baroSample &baro_newest = _baro_buffer.get_newest();
_baro_hgt_offset = baro_newest.hgt + _state.pos(2);
} else {
// TODO: reset to last known range based estimate
}
} else if (_control_status.flags.baro_hgt) {
// initialize vertical position with newest baro measurement
const baroSample &baro_newest = _baro_buffer.get_newest();
if (_time_last_imu - baro_newest.time_us < 2 * BARO_MAX_INTERVAL) {
_state.pos(2) = _hgt_sensor_offset - baro_newest.hgt + _baro_hgt_offset;
// reset the associated covariance values
zeroRows(P, 9, 9);
zeroCols(P, 9, 9);
// the state variance is the same as the observation
P[9][9] = sq(_params.baro_noise);
vert_pos_reset = true;
} else {
// TODO: reset to last known baro based estimate
}
} else if (_control_status.flags.gps_hgt) {
// initialize vertical position and velocity with newest gps measurement
if (_time_last_imu - gps_newest.time_us < 2 * GPS_MAX_INTERVAL) {
_state.pos(2) = _hgt_sensor_offset - gps_newest.hgt + _gps_alt_ref;
// reset the associated covarince values
zeroRows(P, 9, 9);
zeroCols(P, 9, 9);
// the state variance is the same as the observation
P[9][9] = sq(gps_newest.hacc);
vert_pos_reset = true;
// reset the baro offset which is subtracted from the baro reading if we need to use it as a backup
const baroSample &baro_newest = _baro_buffer.get_newest();
_baro_hgt_offset = baro_newest.hgt + _state.pos(2);
} else {
// TODO: reset to last known gps based estimate
}
} else if (_control_status.flags.ev_hgt) {
// initialize vertical position with newest measurement
const extVisionSample &ev_newest = _ext_vision_buffer.get_newest();
// use the most recent data if it's time offset from the fusion time horizon is smaller
int32_t dt_newest = ev_newest.time_us - _imu_sample_delayed.time_us;
int32_t dt_delayed = _ev_sample_delayed.time_us - _imu_sample_delayed.time_us;
vert_pos_reset = true;
if (std::abs(dt_newest) < std::abs(dt_delayed)) {
_state.pos(2) = ev_newest.posNED(2);
} else {
_state.pos(2) = _ev_sample_delayed.posNED(2);
}
}
// reset the vertical velocity covariance values
zeroRows(P, 6, 6);
zeroCols(P, 6, 6);
// reset the vertical velocity state
if (_control_status.flags.gps && (_time_last_imu - gps_newest.time_us < 2 * GPS_MAX_INTERVAL)) {
// If we are using GPS, then use it to reset the vertical velocity
_state.vel(2) = gps_newest.vel(2);
// the state variance is the same as the observation
P[6][6] = sq(1.5f * gps_newest.sacc);
} else {
// we don't know what the vertical velocity is, so set it to zero
_state.vel(2) = 0.0f;
// Set the variance to a value large enough to allow the state to converge quickly
// that does not destabilise the filter
P[6][6] = 10.0f;
}
vert_vel_reset = true;
// store the reset amount and time to be published
if (vert_pos_reset) {
_state_reset_status.posD_change = _state.pos(2) - old_vert_pos;
_state_reset_status.posD_counter++;
}
if (vert_vel_reset) {
_state_reset_status.velD_change = _state.vel(2) - old_vert_vel;
_state_reset_status.velD_counter++;
}
// apply the change in height / height rate to our newest height / height rate estimate
// which have already been taken out from the output buffer
if (vert_pos_reset) {
_output_new.pos(2) += _state_reset_status.posD_change;
}
if (vert_vel_reset) {
_output_new.vel(2) += _state_reset_status.velD_change;
}
// add the reset amount to the output observer buffered data
for (uint8_t i = 0; i < _output_buffer.get_length(); i++) {
if (vert_pos_reset) {
_output_buffer[i].pos(2) += _state_reset_status.posD_change;
_output_vert_buffer[i].vel_d_integ += _state_reset_status.posD_change;
}
if (vert_vel_reset) {
_output_buffer[i].vel(2) += _state_reset_status.velD_change;
_output_vert_buffer[i].vel_d += _state_reset_status.velD_change;
}
}
// add the reset amount to the output observer vertical position state
if (vert_pos_reset) {
_output_vert_delayed.vel_d_integ = _state.pos(2);
_output_vert_new.vel_d_integ = _state.pos(2);
}
if (vert_vel_reset) {
_output_vert_delayed.vel_d = _state.vel(2);
_output_vert_new.vel_d = _state.vel(2);
}
}
// align output filter states to match EKF states at the fusion time horizon
void Ekf::alignOutputFilter()
{
// calculate the quaternion delta between the output and EKF quaternions at the EKF fusion time horizon
Quatf q_delta = _state.quat_nominal.inversed() * _output_sample_delayed.quat_nominal;
q_delta.normalize();
// calculate the velocity and posiiton deltas between the output and EKF at the EKF fusion time horizon
const Vector3f vel_delta = _state.vel - _output_sample_delayed.vel;
const Vector3f pos_delta = _state.pos - _output_sample_delayed.pos;
// loop through the output filter state history and add the deltas
// Note q1 *= q2 is equivalent to q1 = q2 * q1
for (uint8_t i = 0; i < _output_buffer.get_length(); i++) {
_output_buffer[i].quat_nominal *= q_delta;
_output_buffer[i].quat_nominal.normalize();
_output_buffer[i].vel += vel_delta;
_output_buffer[i].pos += pos_delta;
}
}
// Do a forced re-alignment of the yaw angle to align with the horizontal velocity vector from the GPS.
// It is used to align the yaw angle after launch or takeoff for fixed wing vehicle only.
bool Ekf::realignYawGPS()
{
// Need at least 5 m/s of GPS horizontal speed and ratio of velocity error to velocity < 0.15 for a reliable alignment
float gpsSpeed = sqrtf(sq(_gps_sample_delayed.vel(0)) + sq(_gps_sample_delayed.vel(1)));
if ((gpsSpeed > 5.0f) && (_gps_sample_delayed.sacc < (0.15f * gpsSpeed))) {
// check for excessive GPS velocity innovations
bool badVelInnov = ((_vel_pos_test_ratio[0] > 1.0f) || (_vel_pos_test_ratio[1] > 1.0f)) && _control_status.flags.gps;
// calculate GPS course over ground angle
float gpsCOG = atan2f(_gps_sample_delayed.vel(1), _gps_sample_delayed.vel(0));
// calculate course yaw angle
float ekfGOG = atan2f(_state.vel(1), _state.vel(0));
// Check the EKF and GPS course over ground for consistency
float courseYawError = gpsCOG - ekfGOG;
// If the angles disagree and horizontal GPS velocity innovations are large or no previous yaw alignment, we declare the magnetic yaw as bad
bool badYawErr = fabsf(courseYawError) > 0.5f;
bool badMagYaw = (badYawErr && badVelInnov);
if (badMagYaw) {
_num_bad_flight_yaw_events ++;
}
// correct yaw angle using GPS ground course if compass yaw bad or yaw is previously not aligned
if (badMagYaw || !_control_status.flags.yaw_align) {
ECL_WARN("EKF bad yaw corrected using GPS course");
// declare the magnetomer as failed if a bad yaw has occurred more than once
if (_control_status.flags.mag_align_complete && (_num_bad_flight_yaw_events >= 2) && !_control_status.flags.mag_fault) {
ECL_WARN("EKF stopping magnetometer use");
_control_status.flags.mag_fault = true;
}
// save a copy of the quaternion state for later use in calculating the amount of reset change
Quatf quat_before_reset = _state.quat_nominal;
// update transformation matrix from body to world frame using the current state estimate
_R_to_earth = quat_to_invrotmat(_state.quat_nominal);
// get quaternion from existing filter states and calculate roll, pitch and yaw angles
Eulerf euler321(_state.quat_nominal);
// apply yaw correction
if (!_control_status.flags.mag_align_complete) {
// This is our first flight aligment so we can assume that the recent change in velocity has occurred due to a
// forward direction takeoff or launch and therefore the inertial and GPS ground course discrepancy is due to yaw error
euler321(2) += courseYawError;
_control_status.flags.mag_align_complete = true;
} else if (_control_status.flags.wind) {
// we have previously aligned yaw in-flight and have wind estimates so set the yaw such that the vehicle nose is
// aligned with the wind relative GPS velocity vector
euler321(2) = atan2f((_gps_sample_delayed.vel(1) - _state.wind_vel(1)),
(_gps_sample_delayed.vel(0) - _state.wind_vel(0)));
} else {
// we don't have wind estimates, so align yaw to the GPS velocity vector
euler321(2) = atan2f(_gps_sample_delayed.vel(1), _gps_sample_delayed.vel(0));
}
// calculate new filter quaternion states using corected yaw angle
_state.quat_nominal = Quatf(euler321);
uncorrelateQuatStates();
// If heading was bad, then we also need to reset the velocity and position states
_velpos_reset_request = badMagYaw;
// update transformation matrix from body to world frame using the current state estimate
_R_to_earth = quat_to_invrotmat(_state.quat_nominal);
// Use the last magnetometer measurements to reset the field states
_state.mag_B.zero();
_state.mag_I = _R_to_earth * _mag_sample_delayed.mag;
// use the combined EKF and GPS speed variance to calculate a rough estimate of the yaw error after alignment
float SpdErrorVariance = sq(_gps_sample_delayed.sacc) + P[4][4] + P[5][5];
float sineYawError = math::constrain(sqrtf(SpdErrorVariance) / gpsSpeed, 0.0f, 1.0f);
// adjust the quaternion covariances estimated yaw error
increaseQuatYawErrVariance(sq(asinf(sineYawError)));
// reset the corresponding rows and columns in the covariance matrix and set the variances on the magnetic field states to the measurement variance
zeroRows(P, 16, 21);
zeroCols(P, 16, 21);
if (_control_status.flags.mag_3D) {
for (uint8_t index = 16; index <= 21; index ++) {
P[index][index] = sq(_params.mag_noise);
}
// Fuse the declination angle to prevent rapid rotation of earth field vector estimates
fuseDeclination(0.02f);
// save covariance data for re-use when auto-switching between heading and 3-axis fusion
save_mag_cov_data();
}
// record the start time for the magnetic field alignment
_flt_mag_align_start_time = _imu_sample_delayed.time_us;
// calculate the amount that the quaternion has changed by
_state_reset_status.quat_change = quat_before_reset.inversed() * _state.quat_nominal;
// add the reset amount to the output observer buffered data
// Note q1 *= q2 is equivalent to q1 = q2 * q1
for (uint8_t i = 0; i < _output_buffer.get_length(); i++) {
_output_buffer[i].quat_nominal *= _state_reset_status.quat_change;
}
// apply the change in attitude quaternion to our newest quaternion estimate
// which was already taken out from the output buffer
_output_new.quat_nominal = _state_reset_status.quat_change * _output_new.quat_nominal;
// capture the reset event
_state_reset_status.quat_counter++;
return true;
} else {
// align mag states only
// calculate initial earth magnetic field states
_state.mag_I = _R_to_earth * _mag_sample_delayed.mag;
// reset the corresponding rows and columns in the covariance matrix and set the variances on the magnetic field states to the measurement variance
zeroRows(P, 16, 21);
zeroCols(P, 16, 21);
if (_control_status.flags.mag_3D) {
for (uint8_t index = 16; index <= 21; index ++) {
P[index][index] = sq(_params.mag_noise);
}
// Fuse the declination angle to prevent rapid rotation of earth field vector estimates
fuseDeclination(0.02f);
// save covariance data for re-use when auto-switching between heading and 3-axis fusion
save_mag_cov_data();
}
// record the start time for the magnetic field alignment
_flt_mag_align_start_time = _imu_sample_delayed.time_us;
return true;
}
} else {
// attempt a normal alignment using the magnetometer
return resetMagHeading(_mag_sample_delayed.mag);
}
}
// Reset heading and magnetic field states
bool Ekf::resetMagHeading(Vector3f &mag_init)
{
// prevent a reset being performed more than once on the same frame
if (_imu_sample_delayed.time_us == _flt_mag_align_start_time) {
return true;
}
if (_params.mag_fusion_type >= MAG_FUSE_TYPE_NONE) {
// do not use the magnetomer and deactivate magnetic field states
// save covariance data for re-use if currently doing 3-axis fusion
if (_control_status.flags.mag_3D) {
save_mag_cov_data();
_control_status.flags.mag_3D = false;
}
zeroRows(P, 16, 21);
zeroCols(P, 16, 21);
_control_status.flags.mag_hdg = false;
return false;
}
// save a copy of the quaternion state for later use in calculating the amount of reset change
Quatf quat_before_reset = _state.quat_nominal;
Quatf quat_after_reset = _state.quat_nominal;
// update transformation matrix from body to world frame using the current estimate
_R_to_earth = quat_to_invrotmat(_state.quat_nominal);
// calculate the initial quaternion
// determine if a 321 or 312 Euler sequence is best
if (fabsf(_R_to_earth(2, 0)) < fabsf(_R_to_earth(2, 1))) {
// use a 321 sequence
// rotate the magnetometer measurement into earth frame
Eulerf euler321(_state.quat_nominal);
// Set the yaw angle to zero and calculate the rotation matrix from body to earth frame
euler321(2) = 0.0f;
Dcmf R_to_earth(euler321);
// calculate the observed yaw angle
if (_control_status.flags.ev_yaw) {
// convert the observed quaternion to a rotation matrix
Dcmf R_to_earth_ev(_ev_sample_delayed.quat); // transformation matrix from body to world frame
// calculate the yaw angle for a 312 sequence
euler321(2) = atan2f(R_to_earth_ev(1, 0), R_to_earth_ev(0, 0));
} else if (_params.mag_fusion_type <= MAG_FUSE_TYPE_AUTOFW) {
// rotate the magnetometer measurements into earth frame using a zero yaw angle
Vector3f mag_earth_pred = R_to_earth * mag_init;
// the angle of the projection onto the horizontal gives the yaw angle
euler321(2) = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + _mag_declination;
} else if (_params.mag_fusion_type == MAG_FUSE_TYPE_INDOOR && _mag_use_inhibit) {
// we are operating without knowing the earth frame yaw angle
return true;
} else {
// there is no yaw observation
return false;
}
// calculate initial quaternion states for the ekf
// we don't change the output attitude to avoid jumps
quat_after_reset = Quatf(euler321);
} else {
// use a 312 sequence
// Calculate the 312 sequence euler angles that rotate from earth to body frame
// See http://www.atacolorado.com/eulersequences.doc
Vector3f euler312;
euler312(0) = atan2f(-_R_to_earth(0, 1), _R_to_earth(1, 1)); // first rotation (yaw)
euler312(1) = asinf(_R_to_earth(2, 1)); // second rotation (roll)
euler312(2) = atan2f(-_R_to_earth(2, 0), _R_to_earth(2, 2)); // third rotation (pitch)
// Set the first rotation (yaw) to zero and calculate the rotation matrix from body to earth frame
euler312(0) = 0.0f;
// Calculate the body to earth frame rotation matrix from the euler angles using a 312 rotation sequence
float c2 = cosf(euler312(2));
float s2 = sinf(euler312(2));
float s1 = sinf(euler312(1));
float c1 = cosf(euler312(1));
float s0 = sinf(euler312(0));
float c0 = cosf(euler312(0));
Dcmf R_to_earth;
R_to_earth(0, 0) = c0 * c2 - s0 * s1 * s2;
R_to_earth(1, 1) = c0 * c1;
R_to_earth(2, 2) = c2 * c1;
R_to_earth(0, 1) = -c1 * s0;
R_to_earth(0, 2) = s2 * c0 + c2 * s1 * s0;
R_to_earth(1, 0) = c2 * s0 + s2 * s1 * c0;
R_to_earth(1, 2) = s0 * s2 - s1 * c0 * c2;
R_to_earth(2, 0) = -s2 * c1;
R_to_earth(2, 1) = s1;
// calculate the observed yaw angle
if (_control_status.flags.ev_yaw) {
// convert the observed quaternion to a rotation matrix
Dcmf R_to_earth_ev(_ev_sample_delayed.quat); // transformation matrix from body to world frame
// calculate the yaw angle for a 312 sequence
euler312(0) = atan2f(-R_to_earth_ev(0, 1), R_to_earth_ev(1, 1));
} else if (_params.mag_fusion_type <= MAG_FUSE_TYPE_AUTOFW) {
// rotate the magnetometer measurements into earth frame using a zero yaw angle
Vector3f mag_earth_pred = R_to_earth * mag_init;
// the angle of the projection onto the horizontal gives the yaw angle
euler312(0) = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + _mag_declination;
} else if (_params.mag_fusion_type == MAG_FUSE_TYPE_INDOOR && _mag_use_inhibit) {
// we are operating without knowing the earth frame yaw angle
return true;
} else {
// there is no yaw observation
return false;
}
// re-calculate the rotation matrix using the updated yaw angle
s0 = sinf(euler312(0));
c0 = cosf(euler312(0));
R_to_earth(0, 0) = c0 * c2 - s0 * s1 * s2;
R_to_earth(1, 1) = c0 * c1;
R_to_earth(2, 2) = c2 * c1;
R_to_earth(0, 1) = -c1 * s0;
R_to_earth(0, 2) = s2 * c0 + c2 * s1 * s0;
R_to_earth(1, 0) = c2 * s0 + s2 * s1 * c0;
R_to_earth(1, 2) = s0 * s2 - s1 * c0 * c2;
R_to_earth(2, 0) = -s2 * c1;
R_to_earth(2, 1) = s1;
// calculate initial quaternion states for the ekf
// we don't change the output attitude to avoid jumps
quat_after_reset = Quatf(R_to_earth);
}
// set the earth magnetic field states using the updated rotation
Dcmf _R_to_earth_after = quat_to_invrotmat(quat_after_reset);
_state.mag_I = _R_to_earth_after * mag_init;
// reset the corresponding rows and columns in the covariance matrix and set the variances on the magnetic field states to the measurement variance
zeroRows(P, 16, 21);
zeroCols(P, 16, 21);
if (_control_status.flags.mag_3D) {
for (uint8_t index = 16; index <= 21; index ++) {
P[index][index] = sq(_params.mag_noise);
}
// Fuse the declination angle to prevent rapid rotation of earth field vector estimates
fuseDeclination(0.02f);
// save covariance data for re-use when auto-switching between heading and 3-axis fusion
save_mag_cov_data();
}
// record the time for the magnetic field alignment event
_flt_mag_align_start_time = _imu_sample_delayed.time_us;
// calculate the amount that the quaternion has changed by
Quatf q_error = quat_before_reset.inversed() * quat_after_reset;
q_error.normalize();
// convert the quaternion delta to a delta angle
Vector3f delta_ang_error;
float scalar;
if (q_error(0) >= 0.0f) {
scalar = -2.0f;
} else {
scalar = 2.0f;
}
delta_ang_error(0) = scalar * q_error(1);
delta_ang_error(1) = scalar * q_error(2);
delta_ang_error(2) = scalar * q_error(3);
// update quaternion states
_state.quat_nominal = quat_after_reset;
uncorrelateQuatStates();
// record the state change
_state_reset_status.quat_change = q_error;
// update transformation matrix from body to world frame using the current estimate
_R_to_earth = quat_to_invrotmat(_state.quat_nominal);
// reset the rotation from the EV to EKF frame of reference if it is being used
if ((_params.fusion_mode & MASK_ROTATE_EV) && (_params.fusion_mode & MASK_USE_EVPOS) && !_control_status.flags.ev_yaw) {
resetExtVisRotMat();
}
// update the yaw angle variance using the variance of the measurement
if (_control_status.flags.ev_yaw) {
// using error estimate from external vision data
increaseQuatYawErrVariance(sq(fmaxf(_ev_sample_delayed.angErr, 1.0e-2f)));
} else if (_params.mag_fusion_type <= MAG_FUSE_TYPE_AUTOFW) {
// using magnetic heading tuning parameter
increaseQuatYawErrVariance(sq(fmaxf(_params.mag_heading_noise, 1.0e-2f)));
}
// add the reset amount to the output observer buffered data
for (uint8_t i = 0; i < _output_buffer.get_length(); i++) {
// Note q1 *= q2 is equivalent to q1 = q2 * q1
_output_buffer[i].quat_nominal *= _state_reset_status.quat_change;
}
// apply the change in attitude quaternion to our newest quaternion estimate
// which was already taken out from the output buffer
_output_new.quat_nominal = _state_reset_status.quat_change * _output_new.quat_nominal;
// capture the reset event
_state_reset_status.quat_counter++;
return true;
}
// Calculate the magnetic declination to be used by the alignment and fusion processing
void Ekf::calcMagDeclination()
{
// set source of magnetic declination for internal use
if (_control_status.flags.mag_align_complete) {
// Use value consistent with earth field state
_mag_declination = atan2f(_state.mag_I(1), _state.mag_I(0));
} else if (_params.mag_declination_source & MASK_USE_GEO_DECL) {
// use parameter value until GPS is available, then use value returned by geo library
if (_NED_origin_initialised) {
_mag_declination = _mag_declination_gps;
_mag_declination_to_save_deg = math::degrees(_mag_declination);
} else {
_mag_declination = math::radians(_params.mag_declination_deg);
_mag_declination_to_save_deg = _params.mag_declination_deg;
}
} else {
// always use the parameter value
_mag_declination = math::radians(_params.mag_declination_deg);
_mag_declination_to_save_deg = _params.mag_declination_deg;
}
}
// This function forces the covariance matrix to be symmetric
void Ekf::makeSymmetrical(float (&cov_mat)[_k_num_states][_k_num_states], uint8_t first, uint8_t last)
{
for (unsigned row = first; row <= last; row++) {
for (unsigned column = 0; column < row; column++) {
float tmp = (cov_mat[row][column] + cov_mat[column][row]) / 2;
cov_mat[row][column] = tmp;
cov_mat[column][row] = tmp;
}
}
}
void Ekf::constrainStates()
{
for (int i = 0; i < 4; i++) {
_state.quat_nominal(i) = math::constrain(_state.quat_nominal(i), -1.0f, 1.0f);
}
for (int i = 0; i < 3; i++) {
_state.vel(i) = math::constrain(_state.vel(i), -1000.0f, 1000.0f);
}
for (int i = 0; i < 3; i++) {
_state.pos(i) = math::constrain(_state.pos(i), -1.e6f, 1.e6f);
}
for (int i = 0; i < 3; i++) {
_state.gyro_bias(i) = math::constrain(_state.gyro_bias(i), -math::radians(20.f) * _dt_ekf_avg, math::radians(20.f) * _dt_ekf_avg);
}
for (int i = 0; i < 3; i++) {
_state.accel_bias(i) = math::constrain(_state.accel_bias(i), -_params.acc_bias_lim * _dt_ekf_avg, _params.acc_bias_lim * _dt_ekf_avg);
}
for (int i = 0; i < 3; i++) {
_state.mag_I(i) = math::constrain(_state.mag_I(i), -1.0f, 1.0f);
}
for (int i = 0; i < 3; i++) {
_state.mag_B(i) = math::constrain(_state.mag_B(i), -0.5f, 0.5f);
}
for (int i = 0; i < 2; i++) {
_state.wind_vel(i) = math::constrain(_state.wind_vel(i), -100.0f, 100.0f);
}
}
// calculate the earth rotation vector
void Ekf::calcEarthRateNED(Vector3f &omega, float lat_rad) const
{
omega(0) = CONSTANTS_EARTH_SPIN_RATE * cosf(lat_rad);
omega(1) = 0.0f;
omega(2) = -CONSTANTS_EARTH_SPIN_RATE * sinf(lat_rad);
}
// gets the innovations of velocity and position measurements
// 0-2 vel, 3-5 pos
void Ekf::get_vel_pos_innov(float vel_pos_innov[6])
{
memcpy(vel_pos_innov, _vel_pos_innov, sizeof(float) * 6);
}
// gets the innovations of the earth magnetic field measurements
void Ekf::get_aux_vel_innov(float aux_vel_innov[2])
{
memcpy(aux_vel_innov, _aux_vel_innov, sizeof(float) * 2);
}
// writes the innovations of the earth magnetic field measurements
void Ekf::get_mag_innov(float mag_innov[3])
{
memcpy(mag_innov, _mag_innov, 3 * sizeof(float));
}
// gets the innovations of the airspeed measnurement
void Ekf::get_airspeed_innov(float *airspeed_innov)
{
memcpy(airspeed_innov, &_airspeed_innov, sizeof(float));
}
// gets the innovations of the synthetic sideslip measurements
void Ekf::get_beta_innov(float *beta_innov)
{
memcpy(beta_innov, &_beta_innov, sizeof(float));
}
// gets the innovations of the heading measurement
void Ekf::get_heading_innov(float *heading_innov)
{
memcpy(heading_innov, &_heading_innov, sizeof(float));
}
// gets the innovation variances of velocity and position measurements
// 0-2 vel, 3-5 pos
void Ekf::get_vel_pos_innov_var(float vel_pos_innov_var[6])
{
memcpy(vel_pos_innov_var, _vel_pos_innov_var, sizeof(float) * 6);
}
// gets the innovation variances of the earth magnetic field measurements
void Ekf::get_mag_innov_var(float mag_innov_var[3])
{
memcpy(mag_innov_var, _mag_innov_var, sizeof(float) * 3);
}
// gest the innovation variance of the airspeed measurement
void Ekf::get_airspeed_innov_var(float *airspeed_innov_var)
{
memcpy(airspeed_innov_var, &_airspeed_innov_var, sizeof(float));
}
// gets the innovation variance of the synthetic sideslip measurement
void Ekf::get_beta_innov_var(float *beta_innov_var)
{
memcpy(beta_innov_var, &_beta_innov_var, sizeof(float));
}
// gets the innovation variance of the heading measurement
void Ekf::get_heading_innov_var(float *heading_innov_var)
{
memcpy(heading_innov_var, &_heading_innov_var, sizeof(float));
}
// get GPS check status
void Ekf::get_gps_check_status(uint16_t *val)
{
*val = _gps_check_fail_status.value;
}
// get the state vector at the delayed time horizon
void Ekf::get_state_delayed(float *state)
{
for (int i = 0; i < 4; i++) {
state[i] = _state.quat_nominal(i);
}
for (int i = 0; i < 3; i++) {
state[i + 4] = _state.vel(i);
}
for (int i = 0; i < 3; i++) {
state[i + 7] = _state.pos(i);
}
for (int i = 0; i < 3; i++) {
state[i + 10] = _state.gyro_bias(i);
}
for (int i = 0; i < 3; i++) {
state[i + 13] = _state.accel_bias(i);
}
for (int i = 0; i < 3; i++) {
state[i + 16] = _state.mag_I(i);
}
for (int i = 0; i < 3; i++) {
state[i + 19] = _state.mag_B(i);
}
for (int i = 0; i < 2; i++) {
state[i + 22] = _state.wind_vel(i);
}
}
// get the accelerometer bias
void Ekf::get_accel_bias(float bias[3])
{
float temp[3];
temp[0] = _state.accel_bias(0) / _dt_ekf_avg;
temp[1] = _state.accel_bias(1) / _dt_ekf_avg;
temp[2] = _state.accel_bias(2) / _dt_ekf_avg;
memcpy(bias, temp, 3 * sizeof(float));
}
// get the gyroscope bias in rad/s
void Ekf::get_gyro_bias(float bias[3])
{
float temp[3];
temp[0] = _state.gyro_bias(0) / _dt_ekf_avg;
temp[1] = _state.gyro_bias(1) / _dt_ekf_avg;
temp[2] = _state.gyro_bias(2) / _dt_ekf_avg;
memcpy(bias, temp, 3 * sizeof(float));
}
// get the diagonal elements of the covariance matrix
void Ekf::get_covariances(float *covariances)
{
for (unsigned i = 0; i < _k_num_states; i++) {
covariances[i] = P[i][i];
}
}
// get the position and height of the ekf origin in WGS-84 coordinates and time the origin was set
// return true if the origin is valid
bool Ekf::get_ekf_origin(uint64_t *origin_time, map_projection_reference_s *origin_pos, float *origin_alt)