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 509
/
ekf_helper.cpp
1788 lines (1476 loc) · 60.3 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 <bapstroman@gmail.com>
*
*/
#include "ekf.h"
#include <ecl.h>
#include <mathlib/mathlib.h>
#include <cstdlib>
void Ekf::resetVelocity()
{
if (_control_status.flags.gps && isTimedOut(_last_gps_fail_us, (uint64_t)_min_gps_health_time_us)) {
// this reset is only called if we have new gps data at the fusion time horizon
resetVelocityToGps();
} else if (_control_status.flags.opt_flow) {
resetHorizontalVelocityToOpticalFlow();
} else if (_control_status.flags.ev_vel) {
resetVelocityToVision();
} else {
resetHorizontalVelocityToZero();
}
}
void Ekf::resetVelocityToGps() {
ECL_INFO_TIMESTAMPED("reset velocity to GPS");
resetVelocityTo(_gps_sample_delayed.vel);
P.uncorrelateCovarianceSetVariance<3>(4, sq(_gps_sample_delayed.sacc));
}
void Ekf::resetHorizontalVelocityToOpticalFlow() {
ECL_INFO_TIMESTAMPED("reset velocity to flow");
// constrain height above ground to be above minimum possible
const 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
const float range = heightAboveGndEst / _range_sensor.getCosTilt();
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 * _flow_compensated_XY_rad(1) / _flow_sample_delayed.dt;
vel_optflow_body(1) = range * _flow_compensated_XY_rad(0) / _flow_sample_delayed.dt;
vel_optflow_body(2) = 0.0f;
// rotate from body to earth frame
const Vector3f vel_optflow_earth = _R_to_earth * vel_optflow_body;
resetHorizontalVelocityTo(Vector2f(vel_optflow_earth));
} else {
resetHorizontalVelocityTo(Vector2f{0.f, 0.f});
}
// reset the horizontal velocity variance using the optical flow noise variance
P.uncorrelateCovarianceSetVariance<2>(4, sq(range) * calcOptFlowMeasVar());
}
void Ekf::resetVelocityToVision() {
ECL_INFO_TIMESTAMPED("reset to vision velocity");
Vector3f _ev_vel = _ev_sample_delayed.vel;
if(_params.fusion_mode & MASK_ROTATE_EV){
_ev_vel = _R_ev_to_ekf *_ev_sample_delayed.vel;
}
resetVelocityTo(getVisionVelocityInEkfFrame());
P.uncorrelateCovarianceSetVariance<3>(4, getVisionVelocityVarianceInEkfFrame());
}
void Ekf::resetHorizontalVelocityToZero() {
ECL_INFO_TIMESTAMPED("reset velocity to zero");
// Used when falling back to non-aiding mode of operation
resetHorizontalVelocityTo(Vector2f{0.f, 0.f});
P.uncorrelateCovarianceSetVariance<2>(4, 25.0f);
}
void Ekf::resetVelocityTo(const Vector3f &new_vel) {
resetHorizontalVelocityTo(Vector2f(new_vel));
resetVerticalVelocityTo(new_vel(2));
}
void Ekf::resetHorizontalVelocityTo(const Vector2f &new_horz_vel) {
const Vector2f delta_horz_vel = new_horz_vel - Vector2f(_state.vel);
_state.vel.xy() = new_horz_vel;
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
_output_buffer[index].vel.xy() += delta_horz_vel;
}
_output_new.vel.xy() += delta_horz_vel;
_state_reset_status.velNE_change = delta_horz_vel;
_state_reset_status.velNE_counter++;
}
void Ekf::resetVerticalVelocityTo(float new_vert_vel) {
const float delta_vert_vel = new_vert_vel - _state.vel(2);
_state.vel(2) = new_vert_vel;
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
_output_buffer[index].vel(2) += delta_vert_vel;
_output_vert_buffer[index].vert_vel += delta_vert_vel;
}
_output_new.vel(2) += delta_vert_vel;
_output_vert_new.vert_vel += delta_vert_vel;
_state_reset_status.velD_change = delta_vert_vel;
_state_reset_status.velD_counter++;
}
void Ekf::resetHorizontalPosition()
{
// 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
resetHorizontalPositionToGps();
} else if (_control_status.flags.ev_pos) {
// this reset is only called if we have new ev data at the fusion time horizon
resetHorizontalPositionToVision();
} else if (_control_status.flags.opt_flow) {
ECL_INFO_TIMESTAMPED("reset position to last known position");
if (!_control_status.flags.in_air) {
// we are likely starting OF for the first time so reset the horizontal position
resetHorizontalPositionTo(Vector2f(0.f, 0.f));
} else {
resetHorizontalPositionTo(_last_known_posNE);
}
// estimate is relative to initial position in this mode, so we start with zero error.
P.uncorrelateCovarianceSetVariance<2>(7, 0.0f);
} else {
ECL_INFO_TIMESTAMPED("reset position to last known position");
// Used when falling back to non-aiding mode of operation
resetHorizontalPositionTo(_last_known_posNE);
P.uncorrelateCovarianceSetVariance<2>(7, sq(_params.pos_noaid_noise));
}
}
void Ekf::resetHorizontalPositionToGps() {
ECL_INFO_TIMESTAMPED("reset position to GPS");
resetHorizontalPositionTo(_gps_sample_delayed.pos);
P.uncorrelateCovarianceSetVariance<2>(7, sq(_gps_sample_delayed.hacc));
}
void Ekf::resetHorizontalPositionToVision() {
ECL_INFO_TIMESTAMPED("reset position to ev position");
Vector3f _ev_pos = _ev_sample_delayed.pos;
if(_params.fusion_mode & MASK_ROTATE_EV){
_ev_pos = _R_ev_to_ekf *_ev_sample_delayed.pos;
}
resetHorizontalPositionTo(Vector2f(_ev_pos));
P.uncorrelateCovarianceSetVariance<2>(7, _ev_sample_delayed.posVar.slice<2, 1>(0, 0));
}
void Ekf::resetHorizontalPositionTo(const Vector2f &new_horz_pos) {
const Vector2f delta_horz_pos = new_horz_pos - Vector2f(_state.pos);
_state.pos.xy() = new_horz_pos;
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
_output_buffer[index].pos.xy() += delta_horz_pos;
}
_output_new.pos.xy() += delta_horz_pos;
_state_reset_status.posNE_change = delta_horz_pos;
_state_reset_status.posNE_counter++;
}
// 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
const float old_vert_pos = _state.pos(2);
bool vert_pos_reset = false;
// reset the vertical position
if (_control_status.flags.rng_hgt) {
const float new_pos_down = _hgt_sensor_offset - _range_sensor.getDistBottom();
// update the state and associated variance
_state.pos(2) = new_pos_down;
// the state variance is the same as the observation
P.uncorrelateCovarianceSetVariance<1>(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 if (_control_status.flags.baro_hgt) {
// initialize vertical position with newest baro measurement
const baroSample &baro_newest = _baro_buffer.get_newest();
if (!_baro_hgt_faulty) {
_state.pos(2) = -baro_newest.hgt + _baro_hgt_offset;
// the state variance is the same as the observation
P.uncorrelateCovarianceSetVariance<1>(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 (!_gps_hgt_intermittent) {
_state.pos(2) = _hgt_sensor_offset - gps_newest.hgt + _gps_alt_ref;
// the state variance is the same as the observation
P.uncorrelateCovarianceSetVariance<1>(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
const int32_t dt_newest = ev_newest.time_us - _imu_sample_delayed.time_us;
const 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.pos(2);
} else {
_state.pos(2) = _ev_sample_delayed.pos(2);
}
}
// reset the vertical velocity state
if (_control_status.flags.gps && !_gps_hgt_intermittent) {
// If we are using GPS, then use it to reset the vertical velocity
resetVerticalVelocityTo(gps_newest.vel(2));
// the state variance is the same as the observation
P.uncorrelateCovarianceSetVariance<1>(6, sq(1.5f * gps_newest.sacc));
} else {
// we don't know what the vertical velocity is, so set it to zero
resetVerticalVelocityTo(0.0f);
// Set the variance to a value large enough to allow the state to converge quickly
// that does not destabilise the filter
P.uncorrelateCovarianceSetVariance<1>(6, 10.0f);
}
// 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++;
}
// 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;
}
// 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].vert_vel_integ += _state_reset_status.posD_change;
}
}
// add the reset amount to the output observer vertical position state
if (vert_pos_reset) {
_output_vert_new.vert_vel_integ = _state.pos(2);
}
}
// align output filter states to match EKF states at the fusion time horizon
void Ekf::alignOutputFilter()
{
const outputSample output_delayed = _output_buffer.get_oldest();
// calculate the quaternion rotation delta from the EKF to output observer states at the EKF fusion time horizon
Quatf q_delta = _state.quat_nominal * output_delayed.quat_nominal.inversed();
q_delta.normalize();
// calculate the velocity and position deltas between the output and EKF at the EKF fusion time horizon
const Vector3f vel_delta = _state.vel - output_delayed.vel;
const Vector3f pos_delta = _state.pos - output_delayed.pos;
// loop through the output filter state history and add the deltas
for (uint8_t i = 0; i < _output_buffer.get_length(); i++) {
_output_buffer[i].quat_nominal = q_delta * _output_buffer[i].quat_nominal;
_output_buffer[i].quat_nominal.normalize();
_output_buffer[i].vel += vel_delta;
_output_buffer[i].pos += pos_delta;
}
_output_new = _output_buffer.get_newest();
}
// 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()
{
const float gpsSpeed = sqrtf(sq(_gps_sample_delayed.vel(0)) + sq(_gps_sample_delayed.vel(1)));
// Need at least 5 m/s of GPS horizontal speed and
// ratio of velocity error to velocity < 0.15 for a reliable alignment
const bool gps_yaw_alignment_possible = (gpsSpeed > 5.0f) && (_gps_sample_delayed.sacc < (0.15f * gpsSpeed));
if (!gps_yaw_alignment_possible) {
// attempt a normal alignment using the magnetometer
return resetMagHeading(_mag_lpf.getState());
}
// check for excessive horizontal GPS velocity innovations
const bool badVelInnov = (_gps_vel_test_ratio(0) > 1.0f) && _control_status.flags.gps;
// calculate GPS course over ground angle
const float gpsCOG = atan2f(_gps_sample_delayed.vel(1), _gps_sample_delayed.vel(0));
// calculate course yaw angle
const float ekfCOG = atan2f(_state.vel(1), _state.vel(0));
// Check the EKF and GPS course over ground for consistency
const float courseYawError = wrap_pi(gpsCOG - ekfCOG);
// If the angles disagree and horizontal GPS velocity innovations are large or no previous yaw alignment, we declare the magnetic yaw as bad
const bool badYawErr = fabsf(courseYawError) > 0.5f;
const 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_TIMESTAMPED("bad yaw, using GPS course");
// declare the magnetometer as failed if a bad yaw has occurred more than once
if (_control_status.flags.mag_aligned_in_flight && (_num_bad_flight_yaw_events >= 2) && !_control_status.flags.mag_fault) {
ECL_WARN_TIMESTAMPED("stopping mag use");
_control_status.flags.mag_fault = true;
}
// calculate new yaw estimate
float yaw_new;
if (!_control_status.flags.mag_aligned_in_flight) {
// This is our first flight alignment 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
const Eulerf euler321(_state.quat_nominal);
yaw_new = euler321(2) + courseYawError;
_control_status.flags.mag_aligned_in_flight = 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
yaw_new = 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
yaw_new = atan2f(_gps_sample_delayed.vel(1), _gps_sample_delayed.vel(0));
}
// use the combined EKF and GPS speed variance to calculate a rough estimate of the yaw error after alignment
const float SpdErrorVariance = sq(_gps_sample_delayed.sacc) + P(4,4) + P(5,5);
const float sineYawError = math::constrain(sqrtf(SpdErrorVariance) / gpsSpeed, 0.0f, 1.0f);
const float yaw_variance_new = sq(asinf(sineYawError));
// Apply updated yaw and yaw variance to states and covariances
resetQuatStateYaw(yaw_new, yaw_variance_new, true);
// Use the last magnetometer measurements to reset the field states
_state.mag_B.zero();
_R_to_earth = Dcmf(_state.quat_nominal);
_state.mag_I = _R_to_earth * _mag_sample_delayed.mag;
resetMagCov();
// record the start time for the magnetic field alignment
_flt_mag_align_start_time = _imu_sample_delayed.time_us;
// If heading was bad, then we also need to reset the velocity and position states
_velpos_reset_request = badMagYaw;
return true;
} else {
// align mag states only
// calculate initial earth magnetic field states
_state.mag_I = _R_to_earth * _mag_sample_delayed.mag;
resetMagCov();
// record the start time for the magnetic field alignment
_flt_mag_align_start_time = _imu_sample_delayed.time_us;
return true;
}
}
// Reset heading and magnetic field states
bool Ekf::resetMagHeading(const Vector3f &mag_init, bool increase_yaw_var, bool update_buffer)
{
// 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) {
stopMagFusion();
return false;
}
// calculate the observed yaw angle and yaw variance
float yaw_new;
float yaw_new_variance = 0.0f;
if (_control_status.flags.ev_yaw) {
// convert the observed quaternion to a rotation matrix
const Dcmf R_to_earth_ev(_ev_sample_delayed.quat); // transformation matrix from body to world frame
// calculate the yaw angle for a 312 sequence
yaw_new = atan2f(R_to_earth_ev(1, 0), R_to_earth_ev(0, 0));
if (increase_yaw_var) {
yaw_new_variance = fmaxf(_ev_sample_delayed.angVar, sq(1.0e-2f));
}
} else if (_params.mag_fusion_type <= MAG_FUSE_TYPE_3D) {
// rotate the magnetometer measurements into earth frame using a zero yaw angle
Dcmf R_to_earth;
if (fabsf(_R_to_earth(2, 0)) < fabsf(_R_to_earth(2, 1))) {
// rolled more than pitched so use 321 rotation order
Eulerf euler321(_state.quat_nominal);
euler321(2) = 0.0f;
R_to_earth = Dcmf(euler321);
} else {
// pitched more than rolled so use 312 rotation order
const Vector3f rotVec312(0.0f, // yaw
asinf(_R_to_earth(2, 1)), // roll
atan2f(-_R_to_earth(2, 0), _R_to_earth(2, 2))); // pitch
R_to_earth = taitBryan312ToRotMat(rotVec312);
}
// the angle of the projection onto the horizontal gives the yaw angle
const Vector3f mag_earth_pred = R_to_earth * mag_init;
yaw_new = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + getMagDeclination();
if (increase_yaw_var) {
yaw_new_variance = sq(fmaxf(_params.mag_heading_noise, 1.0e-2f));
}
} else if (_params.mag_fusion_type == MAG_FUSE_TYPE_INDOOR && _is_yaw_fusion_inhibited) {
// we are operating temporarily without knowing the earth frame yaw angle
return true;
} else {
// there is no yaw observation
return false;
}
// update quaternion states and corresponding covarainces
resetQuatStateYaw(yaw_new, yaw_new_variance, update_buffer);
// set the earth magnetic field states using the updated rotation
_state.mag_I = _R_to_earth * mag_init;
resetMagCov();
// record the time for the magnetic field alignment event
_flt_mag_align_start_time = _imu_sample_delayed.time_us;
return true;
}
// Return the magnetic declination in radians to be used by the alignment and fusion processing
float Ekf::getMagDeclination()
{
// set source of magnetic declination for internal use
if (_control_status.flags.mag_aligned_in_flight) {
// Use value consistent with earth field state
return 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) {
return _mag_declination_gps;
} else {
return math::radians(_params.mag_declination_deg);
}
} else {
// always use the parameter value
return math::radians(_params.mag_declination_deg);
}
}
void Ekf::constrainStates()
{
_state.quat_nominal = matrix::constrain(_state.quat_nominal, -1.0f, 1.0f);
_state.vel = matrix::constrain(_state.vel, -1000.0f, 1000.0f);
_state.pos = matrix::constrain(_state.pos, -1.e6f, 1.e6f);
const float delta_ang_bias_limit = math::radians(20.f) * _dt_ekf_avg;
_state.delta_ang_bias = matrix::constrain(_state.delta_ang_bias, -delta_ang_bias_limit, delta_ang_bias_limit);
const float delta_vel_bias_limit = _params.acc_bias_lim * _dt_ekf_avg;
_state.delta_vel_bias = matrix::constrain(_state.delta_vel_bias, -delta_vel_bias_limit, delta_vel_bias_limit);
_state.mag_I = matrix::constrain(_state.mag_I, -1.0f, 1.0f);
_state.mag_B = matrix::constrain(_state.mag_B, -0.5f, 0.5f);
_state.wind_vel = matrix::constrain(_state.wind_vel, -100.0f, 100.0f);
}
float Ekf::compensateBaroForDynamicPressure(const float baro_alt_uncompensated)
{
// calculate static pressure error = Pmeas - Ptruth
// model position error sensitivity as a body fixed ellipse with a different scale in the positive and
// negative X and Y directions. Used to correct baro data for positional errors
const matrix::Dcmf R_to_body(_output_new.quat_nominal.inversed());
// Calculate airspeed in body frame
const Vector3f velocity_earth = _output_new.vel - _vel_imu_rel_body_ned;
const Vector3f wind_velocity_earth(_state.wind_vel(0), _state.wind_vel(1), 0.0f);
const Vector3f airspeed_earth = velocity_earth - wind_velocity_earth;
const Vector3f airspeed_body = R_to_body * airspeed_earth;
const Vector3f K_pstatic_coef(airspeed_body(0) >= 0.0f ? _params.static_pressure_coef_xp : _params.static_pressure_coef_xn,
airspeed_body(1) >= 0.0f ? _params.static_pressure_coef_yp : _params.static_pressure_coef_yn,
_params.static_pressure_coef_z);
const Vector3f airspeed_squared = matrix::min(airspeed_body.emult(airspeed_body), sq(_params.max_correction_airspeed));
const float pstatic_err = 0.5f * _air_density * (airspeed_squared.dot(K_pstatic_coef));
// correct baro measurement using pressure error estimate and assuming sea level gravity
return baro_alt_uncompensated + pstatic_err / (_air_density * CONSTANTS_ONE_G);
}
// calculate the earth rotation vector
Vector3f Ekf::calcEarthRateNED(float lat_rad) const
{
return Vector3f(CONSTANTS_EARTH_SPIN_RATE * cosf(lat_rad),
0.0f,
-CONSTANTS_EARTH_SPIN_RATE * sinf(lat_rad));
}
void Ekf::getGpsVelPosInnov(float hvel[2], float &vvel, float hpos[2], float &vpos) const
{
hvel[0] = _gps_vel_innov(0);
hvel[1] = _gps_vel_innov(1);
vvel = _gps_vel_innov(2);
hpos[0] = _gps_pos_innov(0);
hpos[1] = _gps_pos_innov(1);
vpos = _gps_pos_innov(2);
}
void Ekf::getGpsVelPosInnovVar(float hvel[2], float &vvel, float hpos[2], float &vpos) const
{
hvel[0] = _gps_vel_innov_var(0);
hvel[1] = _gps_vel_innov_var(1);
vvel = _gps_vel_innov_var(2);
hpos[0] = _gps_pos_innov_var(0);
hpos[1] = _gps_pos_innov_var(1);
vpos = _gps_pos_innov_var(2);
}
void Ekf::getGpsVelPosInnovRatio(float &hvel, float &vvel, float &hpos, float &vpos) const
{
hvel = _gps_vel_test_ratio(0);
vvel = _gps_vel_test_ratio(1);
hpos = _gps_pos_test_ratio(0);
vpos = _gps_pos_test_ratio(1);
}
void Ekf::getEvVelPosInnov(float hvel[2], float &vvel, float hpos[2], float &vpos) const
{
hvel[0] = _ev_vel_innov(0);
hvel[1] = _ev_vel_innov(1);
vvel = _ev_vel_innov(2);
hpos[0] = _ev_pos_innov(0);
hpos[1] = _ev_pos_innov(1);
vpos = _ev_pos_innov(2);
}
void Ekf::getEvVelPosInnovVar(float hvel[2], float &vvel, float hpos[2], float &vpos) const
{
hvel[0] = _ev_vel_innov_var(0);
hvel[1] = _ev_vel_innov_var(1);
vvel = _ev_vel_innov_var(2);
hpos[0] = _ev_pos_innov_var(0);
hpos[1] = _ev_pos_innov_var(1);
vpos = _ev_pos_innov_var(2);
}
void Ekf::getEvVelPosInnovRatio(float &hvel, float &vvel, float &hpos, float &vpos) const
{
hvel = _ev_vel_test_ratio(0);
vvel = _ev_vel_test_ratio(1);
hpos = _ev_pos_test_ratio(0);
vpos = _ev_pos_test_ratio(1);
}
void Ekf::getBaroHgtInnov(float &baro_hgt_innov) const
{
baro_hgt_innov = _baro_hgt_innov(2);
}
void Ekf::getBaroHgtInnovVar(float &baro_hgt_innov_var) const
{
baro_hgt_innov_var = _baro_hgt_innov_var(2);
}
void Ekf::getBaroHgtInnovRatio(float &baro_hgt_innov_ratio) const
{
baro_hgt_innov_ratio = _baro_hgt_test_ratio(1);
}
void Ekf::getRngHgtInnov(float &rng_hgt_innov) const
{
rng_hgt_innov = _rng_hgt_innov(2);
}
void Ekf::getRngHgtInnovVar(float &rng_hgt_innov_var) const
{
rng_hgt_innov_var = _rng_hgt_innov_var(2);
}
void Ekf::getRngHgtInnovRatio(float &rng_hgt_innov_ratio) const
{
rng_hgt_innov_ratio = _rng_hgt_test_ratio(1);
}
void Ekf::getAuxVelInnov(float aux_vel_innov[2]) const
{
aux_vel_innov[0] = _aux_vel_innov(0);
aux_vel_innov[1] = _aux_vel_innov(1);
}
void Ekf::getAuxVelInnovVar(float aux_vel_innov_var[2]) const
{
aux_vel_innov_var[0] = _aux_vel_innov_var(0);
aux_vel_innov_var[1] = _aux_vel_innov_var(1);
}
void Ekf::getAuxVelInnovRatio(float &aux_vel_innov_ratio) const
{
aux_vel_innov_ratio = _aux_vel_test_ratio(0);
}
void Ekf::getFlowInnov(float flow_innov[2]) const
{
_flow_innov.copyTo(flow_innov);
}
void Ekf::getFlowInnovVar(float flow_innov_var[2]) const
{
_flow_innov_var.copyTo(flow_innov_var);
}
void Ekf::getFlowInnovRatio(float &flow_innov_ratio) const
{
flow_innov_ratio = _optflow_test_ratio;
}
void Ekf::getHeadingInnov(float &heading_innov) const
{
heading_innov = _heading_innov;
}
void Ekf::getHeadingInnovVar(float &heading_innov_var) const
{
heading_innov_var = _heading_innov_var;
}
void Ekf::getHeadingInnovRatio(float &heading_innov_ratio) const
{
heading_innov_ratio = _yaw_test_ratio;
}
void Ekf::getMagInnov(float mag_innov[3]) const
{
_mag_innov.copyTo(mag_innov);
}
void Ekf::getMagInnovVar(float mag_innov_var[3]) const
{
_mag_innov_var.copyTo(mag_innov_var);
}
void Ekf::getMagInnovRatio(float &mag_innov_ratio) const
{
mag_innov_ratio = _mag_test_ratio.max();
}
void Ekf::getDragInnov(float drag_innov[2]) const
{
_drag_innov.copyTo(drag_innov);
}
void Ekf::getDragInnovVar(float drag_innov_var[2]) const
{
_drag_innov_var.copyTo(drag_innov_var);
}
void Ekf::getDragInnovRatio(float drag_innov_ratio[2]) const
{
_drag_test_ratio.copyTo(drag_innov_ratio);
}
void Ekf::getAirspeedInnov(float &airspeed_innov) const
{
airspeed_innov = _airspeed_innov;
}
void Ekf::getAirspeedInnovVar(float &airspeed_innov_var) const
{
airspeed_innov_var = _airspeed_innov_var;
}
void Ekf::getAirspeedInnovRatio(float &airspeed_innov_ratio) const
{
airspeed_innov_ratio = _tas_test_ratio;
}
void Ekf::getBetaInnov(float &beta_innov) const
{
beta_innov = _beta_innov;
}
void Ekf::getBetaInnovVar(float &beta_innov_var) const
{
beta_innov_var = _beta_innov_var;
}
void Ekf::getBetaInnovRatio(float &beta_innov_ratio) const
{
beta_innov_ratio = _beta_test_ratio;
}
void Ekf::getHaglInnov(float &hagl_innov) const
{
hagl_innov = _hagl_innov;
}
void Ekf::getHaglInnovVar(float &hagl_innov_var) const
{
hagl_innov_var = _hagl_innov_var;
}
void Ekf::getHaglInnovRatio(float &hagl_innov_ratio) const
{
hagl_innov_ratio = _hagl_test_ratio;
}
// 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
matrix::Vector<float, 24> Ekf::getStateAtFusionHorizonAsVector() const
{
matrix::Vector<float, 24> state;
state.slice<4, 1>(0, 0) = _state.quat_nominal;
state.slice<3, 1>(4, 0) = _state.vel;
state.slice<3, 1>(7, 0) = _state.pos;
state.slice<3, 1>(10, 0) = _state.delta_ang_bias;
state.slice<3, 1>(13, 0) = _state.delta_vel_bias;
state.slice<3, 1>(16, 0) = _state.mag_I;
state.slice<3, 1>(19, 0) = _state.mag_B;
state.slice<2, 1>(22, 0) = _state.wind_vel;
return state;
}
Vector3f Ekf::getAccelBias() const
{
return _state.delta_vel_bias / _dt_ekf_avg;
}
Vector3f Ekf::getGyroBias() const
{
return _state.delta_ang_bias / _dt_ekf_avg;
}
// 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)
{
memcpy(origin_time, &_last_gps_origin_time_us, sizeof(uint64_t));
memcpy(origin_pos, &_pos_ref, sizeof(map_projection_reference_s));
memcpy(origin_alt, &_gps_alt_ref, sizeof(float));
return _NED_origin_initialised;
}
// return a vector containing the output predictor angular, velocity and position tracking
// error magnitudes (rad), (m/s), (m)
Vector3f Ekf::getOutputTrackingError() const
{
return _output_tracking_error;
}
/*
Returns following IMU vibration metrics in the following array locations
0 : Gyro delta angle coning metric = filtered length of (delta_angle x prev_delta_angle)
1 : Gyro high frequency vibe = filtered length of (delta_angle - prev_delta_angle)
2 : Accel high frequency vibe = filtered length of (delta_velocity - prev_delta_velocity)
*/
Vector3f Ekf::getImuVibrationMetrics() const
{
return _vibe_metrics;
}
/*
First argument returns GPS drift metrics in the following array locations
0 : Horizontal position drift rate (m/s)
1 : Vertical position drift rate (m/s)
2 : Filtered horizontal velocity (m/s)
Second argument returns true when IMU movement is blocking the drift calculation
Function returns true if the metrics have been updated and not returned previously by this function
*/
bool Ekf::get_gps_drift_metrics(float drift[3], bool *blocked)
{
memcpy(drift, _gps_drift_metrics, 3 * sizeof(float));
*blocked = !_control_status.flags.vehicle_at_rest;
if (_gps_drift_updated) {
_gps_drift_updated = false;
return true;
}
return false;
}
// get the 1-sigma horizontal and vertical position uncertainty of the ekf WGS-84 position
void Ekf::get_ekf_gpos_accuracy(float *ekf_eph, float *ekf_epv)
{
// report absolute accuracy taking into account the uncertainty in location of the origin
// If not aiding, return 0 for horizontal position estimate as no estimate is available
// TODO - allow for baro drift in vertical position error
float hpos_err = sqrtf(P(7,7) + P(8,8) + sq(_gps_origin_eph));
// If we are dead-reckoning, use the innovations as a conservative alternate measure of the horizontal position error
// The reason is that complete rejection of measurements is often caused by heading misalignment or inertial sensing errors
// and using state variances for accuracy reporting is overly optimistic in these situations
if (_is_dead_reckoning && (_control_status.flags.gps)) {
hpos_err = math::max(hpos_err, sqrtf(sq(_gps_pos_innov(0)) + sq(_gps_pos_innov(1))));
}
else if (_is_dead_reckoning && (_control_status.flags.ev_pos)) {
hpos_err = math::max(hpos_err, sqrtf(sq(_ev_pos_innov(0)) + sq(_ev_pos_innov(1))));
}
*ekf_eph = hpos_err;
*ekf_epv = sqrtf(P(9,9) + sq(_gps_origin_epv));
}
// get the 1-sigma horizontal and vertical position uncertainty of the ekf local position
void Ekf::get_ekf_lpos_accuracy(float *ekf_eph, float *ekf_epv)
{
// TODO - allow for baro drift in vertical position error
float hpos_err = sqrtf(P(7,7) + P(8,8));
// If we are dead-reckoning, use the innovations as a conservative alternate measure of the horizontal position error
// The reason is that complete rejection of measurements is often caused by heading misalignment or inertial sensing errors
// and using state variances for accuracy reporting is overly optimistic in these situations
if (_is_dead_reckoning && _control_status.flags.gps) {
hpos_err = math::max(hpos_err, sqrtf(sq(_gps_pos_innov(0)) + sq(_gps_pos_innov(1))));
}
*ekf_eph = hpos_err;
*ekf_epv = sqrtf(P(9,9));
}
// get the 1-sigma horizontal and vertical velocity uncertainty
void Ekf::get_ekf_vel_accuracy(float *ekf_evh, float *ekf_evv)
{
float hvel_err = sqrtf(P(4,4) + P(5,5));
// If we are dead-reckoning, use the innovations as a conservative alternate measure of the horizontal velocity error
// The reason is that complete rejection of measurements is often caused by heading misalignment or inertial sensing errors
// and using state variances for accuracy reporting is overly optimistic in these situations
if (_is_dead_reckoning) {
float vel_err_conservative = 0.0f;
if (_control_status.flags.opt_flow) {
float gndclearance = math::max(_params.rng_gnd_clearance, 0.1f);
vel_err_conservative = math::max((_terrain_vpos - _state.pos(2)), gndclearance) * _flow_innov.norm();
}
if (_control_status.flags.gps) {
vel_err_conservative = math::max(vel_err_conservative, sqrtf(sq(_gps_pos_innov(0)) + sq(_gps_pos_innov(1))));
}
else if (_control_status.flags.ev_pos) {
vel_err_conservative = math::max(vel_err_conservative, sqrtf(sq(_ev_pos_innov(0)) + sq(_ev_pos_innov(1))));
}
if (_control_status.flags.ev_vel) {
vel_err_conservative = math::max(vel_err_conservative, sqrtf(sq(_ev_vel_innov(0)) + sq(_ev_vel_innov(1))));
}
hvel_err = math::max(hvel_err, vel_err_conservative);
}
*ekf_evh = hvel_err;
*ekf_evv = sqrtf(P(6,6));
}
/*
Returns the following vehicle control limits required by the estimator to keep within sensor limitations.
vxy_max : Maximum ground relative horizontal speed (meters/sec). NaN when limiting is not needed.
vz_max : Maximum ground relative vertical speed (meters/sec). NaN when limiting is not needed.
hagl_min : Minimum height above ground (meters). NaN when limiting is not needed.
hagl_max : Maximum height above ground (meters). NaN when limiting is not needed.
*/
void Ekf::get_ekf_ctrl_limits(float *vxy_max, float *vz_max, float *hagl_min, float *hagl_max)
{
// Calculate range finder limits
const float rangefinder_hagl_min = _range_sensor.getValidMinVal();
// Allow use of 75% of rangefinder maximum range to allow for angular motion
const float rangefinder_hagl_max = 0.75f * _range_sensor.getValidMaxVal();
// Calculate optical flow limits
// Allow ground relative velocity to use 50% of available flow sensor range to allow for angular motion
const float flow_vxy_max = fmaxf(0.5f * _flow_max_rate * (_terrain_vpos - _state.pos(2)), 0.0f);
const float flow_hagl_min = _flow_min_distance;
const float flow_hagl_max = _flow_max_distance;
// TODO : calculate visual odometry limits
const bool relying_on_rangefinder = _control_status.flags.rng_hgt && !_params.range_aid;
const bool relying_on_optical_flow = isOnlyActiveSourceOfHorizontalAiding(_control_status.flags.opt_flow);
// Do not require limiting by default
*vxy_max = NAN;