-
Notifications
You must be signed in to change notification settings - Fork 17.5k
/
AP_AHRS_DCM.cpp
1336 lines (1159 loc) · 45.1 KB
/
AP_AHRS_DCM.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
/*
* APM_AHRS_DCM.cpp
*
* AHRS system using DCM matrices
*
* Based on DCM code by Doug Weibel, Jordi Munoz and Jose Julio. DIYDrones.com
*
* Adapted for the general ArduPilot AHRS interface by Andrew Tridgell
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, either version 3 of the License, or
(at your option) any later version.
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/>.
*/
#include "AP_AHRS_config.h"
#if AP_AHRS_DCM_ENABLED
#include "AP_AHRS.h"
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
extern const AP_HAL::HAL& hal;
// this is the speed in m/s above which we first get a yaw lock with
// the GPS
#define GPS_SPEED_MIN 3
// the limit (in degrees/second) beyond which we stop integrating
// omega_I. At larger spin rates the DCM PI controller can get 'dizzy'
// which results in false gyro drift. See
// http://gentlenav.googlecode.com/files/fastRotations.pdf
#define SPIN_RATE_LIMIT 20
// reset the current gyro drift estimate
// should be called if gyro offsets are recalculated
void
AP_AHRS_DCM::reset_gyro_drift(void)
{
_omega_I.zero();
_omega_I_sum.zero();
_omega_I_sum_time = 0;
}
// run a full DCM update round
void
AP_AHRS_DCM::update()
{
AP_InertialSensor &_ins = AP::ins();
// ask the IMU how much time this sensor reading represents
const float delta_t = _ins.get_delta_time();
// if the update call took more than 0.2 seconds then discard it,
// otherwise we may move too far. This happens when arming motors
// in ArduCopter
if (delta_t > 0.2f) {
memset((void *)&_ra_sum[0], 0, sizeof(_ra_sum));
_ra_deltat = 0;
return;
}
// Integrate the DCM matrix using gyro inputs
matrix_update();
// Normalize the DCM matrix
normalize();
// Perform drift correction
drift_correction(delta_t);
// paranoid check for bad values in the DCM matrix
check_matrix();
// calculate the euler angles and DCM matrix which will be used
// for high level navigation control. Apply trim such that a
// positive trim value results in a positive vehicle rotation
// about that axis (ie a negative offset)
_body_dcm_matrix = _dcm_matrix * AP::ahrs().get_rotation_vehicle_body_to_autopilot_body();
_body_dcm_matrix.to_euler(&roll, &pitch, &yaw);
// pre-calculate some trig for CPU purposes:
_cos_yaw = cosf(yaw);
_sin_yaw = sinf(yaw);
backup_attitude();
// remember the last origin for fallback support
IGNORE_RETURN(AP::ahrs().get_origin(last_origin));
#if HAL_LOGGING_ENABLED
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - last_log_ms >= 100) {
// log DCM at 10Hz
last_log_ms = now_ms;
// @LoggerMessage: DCM
// @Description: DCM Estimator Data
// @Field: TimeUS: Time since system startup
// @Field: Roll: estimated roll
// @Field: Pitch: estimated pitch
// @Field: Yaw: estimated yaw
// @Field: ErrRP: lowest estimated gyro drift error
// @Field: ErrYaw: difference between measured yaw and DCM yaw estimate
// @Field: VWN: wind velocity, to-the-North component
// @Field: VWE: wind velocity, to-the-East component
// @Field: VWD: wind velocity, Up-to-Down component
AP::logger().WriteStreaming(
"DCM",
"TimeUS," "Roll," "Pitch," "Yaw," "ErrRP," "ErrYaw," "VWN," "VWE," "VWD",
"s" "d" "d" "d" "d" "h" "n" "n" "n",
"F" "0" "0" "0" "0" "0" "0" "0" "0",
"Q" "f" "f" "f" "f" "f" "f" "f" "f",
AP_HAL::micros64(),
degrees(roll),
degrees(pitch),
wrap_360(degrees(yaw)),
get_error_rp(),
get_error_yaw(),
_wind.x,
_wind.y,
_wind.z
);
}
#endif // HAL_LOGGING_ENABLED
}
void AP_AHRS_DCM::get_results(AP_AHRS_Backend::Estimates &results)
{
results.roll_rad = roll;
results.pitch_rad = pitch;
results.yaw_rad = yaw;
results.dcm_matrix = _body_dcm_matrix;
results.gyro_estimate = _omega;
results.gyro_drift = _omega_I;
results.accel_ef = _accel_ef;
results.location_valid = get_location(results.location);
}
/*
backup attitude to persistent_data for use in watchdog reset
*/
void AP_AHRS_DCM::backup_attitude(void)
{
AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
pd.roll_rad = roll;
pd.pitch_rad = pitch;
pd.yaw_rad = yaw;
}
// update the DCM matrix using only the gyros
void AP_AHRS_DCM::matrix_update(void)
{
// use only the primary gyro so our bias estimate is valid, allowing us to return the right filtered gyro
// for rate controllers
const auto &_ins = AP::ins();
Vector3f delta_angle;
float dangle_dt;
if (_ins.get_delta_angle(delta_angle, dangle_dt) && dangle_dt > 0) {
_omega = delta_angle / dangle_dt;
_omega += _omega_I;
_dcm_matrix.rotate((_omega + _omega_P + _omega_yaw_P) * dangle_dt);
}
// now update _omega from the filtered value from the primary IMU. We need to use
// the primary IMU as the notch filters will only be running on one IMU
// note that we do not include the P terms in _omega. This is
// because the spin_rate is calculated from _omega.length(),
// and including the P terms would give positive feedback into
// the _P_gain() calculation, which can lead to a very large P
// value
_omega = _ins.get_gyro() + _omega_I;
}
/*
* reset the DCM matrix and omega. Used on ground start, and on
* extreme errors in the matrix
*/
void
AP_AHRS_DCM::reset(bool recover_eulers)
{
// reset the integration terms
_omega_I.zero();
_omega_P.zero();
_omega_yaw_P.zero();
_omega.zero();
// if the caller wants us to try to recover to the current
// attitude then calculate the dcm matrix from the current
// roll/pitch/yaw values
if (hal.util->was_watchdog_reset() && AP_HAL::millis() < 10000) {
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
roll = pd.roll_rad;
pitch = pd.pitch_rad;
yaw = pd.yaw_rad;
_dcm_matrix.from_euler(roll, pitch, yaw);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Restored watchdog attitude %.0f %.0f %.0f",
degrees(roll), degrees(pitch), degrees(yaw));
} else if (recover_eulers && !isnan(roll) && !isnan(pitch) && !isnan(yaw)) {
_dcm_matrix.from_euler(roll, pitch, yaw);
} else {
// Use the measured accel due to gravity to calculate an initial
// roll and pitch estimate
AP_InertialSensor &_ins = AP::ins();
// Get body frame accel vector
Vector3f initAccVec = _ins.get_accel();
uint8_t counter = 0;
// the first vector may be invalid as the filter starts up
while ((initAccVec.length() < 9.0f || initAccVec.length() > 11) && counter++ < 20) {
_ins.wait_for_sample();
_ins.update();
initAccVec = _ins.get_accel();
}
// normalise the acceleration vector
if (initAccVec.length() > 5.0f) {
// calculate initial pitch angle
pitch = atan2f(initAccVec.x, norm(initAccVec.y, initAccVec.z));
// calculate initial roll angle
roll = atan2f(-initAccVec.y, -initAccVec.z);
} else {
// If we can't use the accel vector, then align flat
roll = 0.0f;
pitch = 0.0f;
}
_dcm_matrix.from_euler(roll, pitch, 0);
}
// pre-calculate some trig for CPU purposes:
_cos_yaw = cosf(yaw);
_sin_yaw = sinf(yaw);
_last_startup_ms = AP_HAL::millis();
}
/*
* check the DCM matrix for pathological values
*/
void
AP_AHRS_DCM::check_matrix(void)
{
if (_dcm_matrix.is_nan()) {
//Serial.printf("ERROR: DCM matrix NAN\n");
AP_AHRS_DCM::reset(true);
return;
}
// some DCM matrix values can lead to an out of range error in
// the pitch calculation via asin(). These NaN values can
// feed back into the rest of the DCM matrix via the
// error_course value.
if (!(_dcm_matrix.c.x < 1.0f &&
_dcm_matrix.c.x > -1.0f)) {
// We have an invalid matrix. Force a normalisation.
normalize();
if (_dcm_matrix.is_nan() ||
fabsf(_dcm_matrix.c.x) > 10.0) {
// See Issue #20284: regarding the selection of 10.0 for DCM reset
// This won't be lowered without evidence of an issue or mathematical proof & testing of a lower bound
// normalisation didn't fix the problem! We're
// in real trouble. All we can do is reset
//Serial.printf("ERROR: DCM matrix error. _dcm_matrix.c.x=%f\n",
// _dcm_matrix.c.x);
AP_AHRS_DCM::reset(true);
}
}
}
// renormalise one vector component of the DCM matrix
// this will return false if renormalization fails
bool
AP_AHRS_DCM::renorm(Vector3f const &a, Vector3f &result)
{
// numerical errors will slowly build up over time in DCM,
// causing inaccuracies. We can keep ahead of those errors
// using the renormalization technique from the DCM IMU paper
// (see equations 18 to 21).
// For APM we don't bother with the taylor expansion
// optimisation from the paper as on our 2560 CPU the cost of
// the sqrt() is 44 microseconds, and the small time saving of
// the taylor expansion is not worth the potential of
// additional error buildup.
// Note that we can get significant renormalisation values
// when we have a larger delta_t due to a glitch elsewhere in
// APM, such as a I2c timeout or a set of EEPROM writes. While
// we would like to avoid these if possible, if it does happen
// we don't want to compound the error by making DCM less
// accurate.
const float renorm_val = 1.0f / a.length();
// keep the average for reporting
_renorm_val_sum += renorm_val;
_renorm_val_count++;
if (!(renorm_val < 2.0f && renorm_val > 0.5f)) {
// this is larger than it should get - log it as a warning
if (!(renorm_val < 1.0e6f && renorm_val > 1.0e-6f)) {
// we are getting values which are way out of
// range, we will reset the matrix and hope we
// can recover our attitude using drift
// correction before we hit the ground!
//Serial.printf("ERROR: DCM renormalisation error. renorm_val=%f\n",
// renorm_val);
return false;
}
}
result = a * renorm_val;
return true;
}
/*************************************************
* Direction Cosine Matrix IMU: Theory
* William Premerlani and Paul Bizard
*
* Numerical errors will gradually reduce the orthogonality conditions expressed by equation 5
* to approximations rather than identities. In effect, the axes in the two frames of reference no
* longer describe a rigid body. Fortunately, numerical error accumulates very slowly, so it is a
* simple matter to stay ahead of it.
* We call the process of enforcing the orthogonality conditions: renormalization.
*/
void
AP_AHRS_DCM::normalize(void)
{
const float error = _dcm_matrix.a * _dcm_matrix.b; // eq.18
const Vector3f t0 = _dcm_matrix.a - (_dcm_matrix.b * (0.5f * error)); // eq.19
const Vector3f t1 = _dcm_matrix.b - (_dcm_matrix.a * (0.5f * error)); // eq.19
const Vector3f t2 = t0 % t1; // c= a x b // eq.20
if (!renorm(t0, _dcm_matrix.a) ||
!renorm(t1, _dcm_matrix.b) ||
!renorm(t2, _dcm_matrix.c)) {
// Our solution is blowing up and we will force back
// to last euler angles
_last_failure_ms = AP_HAL::millis();
AP_AHRS_DCM::reset(true);
}
}
// produce a yaw error value. The returned value is proportional
// to sin() of the current heading error in earth frame
float
AP_AHRS_DCM::yaw_error_compass(Compass &compass)
{
const Vector3f &mag = compass.get_field();
// get the mag vector in the earth frame
Vector2f rb = _dcm_matrix.mulXY(mag);
if (rb.length() < FLT_EPSILON) {
return 0.0f;
}
rb.normalize();
if (rb.is_inf()) {
// not a valid vector
return 0.0f;
}
// update vector holding earths magnetic field (if required)
if( !is_equal(_last_declination, compass.get_declination()) ) {
_last_declination = compass.get_declination();
_mag_earth.x = cosf(_last_declination);
_mag_earth.y = sinf(_last_declination);
}
// calculate the error term in earth frame
// calculate the Z component of the cross product of rb and _mag_earth
return rb % _mag_earth;
}
// the _P_gain raises the gain of the PI controller
// when we are spinning fast. See the fastRotations
// paper from Bill.
float
AP_AHRS_DCM::_P_gain(float spin_rate)
{
if (spin_rate < ToRad(50)) {
return 1.0f;
}
if (spin_rate > ToRad(500)) {
return 10.0f;
}
return spin_rate/ToRad(50);
}
// _yaw_gain reduces the gain of the PI controller applied to heading errors
// when observability from change of velocity is good (eg changing speed or turning)
// This reduces unwanted roll and pitch coupling due to compass errors for planes.
// High levels of noise on _accel_ef will cause the gain to drop and could lead to
// increased heading drift during straight and level flight, however some gain is
// always available. TODO check the necessity of adding adjustable acc threshold
// and/or filtering accelerations before getting magnitude
float
AP_AHRS_DCM::_yaw_gain(void) const
{
const float VdotEFmag = _accel_ef.xy().length();
if (VdotEFmag <= 4.0f) {
return 0.2f*(4.5f - VdotEFmag);
}
return 0.1f;
}
// return true if we have and should use GPS
bool AP_AHRS_DCM::have_gps(void) const
{
if (_gps_use == GPSUse::Disable || AP::gps().status() <= AP_GPS::NO_FIX) {
return false;
}
return true;
}
/*
when we are getting the initial attitude we want faster gains so
that if the board starts upside down we quickly approach the right
attitude.
We don't want to keep those high gains for too long though as high P
gains cause slow gyro offset learning. So we keep the high gains for
a maximum of 20 seconds
*/
bool AP_AHRS_DCM::use_fast_gains(void) const
{
return !hal.util->get_soft_armed() && (AP_HAL::millis() - _last_startup_ms) < 20000U;
}
// return true if we should use the compass for yaw correction
bool AP_AHRS_DCM::use_compass(void)
{
const Compass &compass = AP::compass();
if (!compass.use_for_yaw()) {
// no compass available
return false;
}
if (!AP::ahrs().get_fly_forward() || !have_gps()) {
// we don't have any alternative to the compass
return true;
}
if (AP::gps().ground_speed() < GPS_SPEED_MIN) {
// we are not going fast enough to use the GPS
return true;
}
// if the current yaw differs from the GPS yaw by more than 45
// degrees and the estimated wind speed is less than 80% of the
// ground speed, then switch to GPS navigation. This will help
// prevent flyaways with very bad compass offsets
const float error = fabsf(wrap_180(degrees(yaw) - AP::gps().ground_course()));
if (error > 45 && _wind.length() < AP::gps().ground_speed()*0.8f) {
if (AP_HAL::millis() - _last_consistent_heading > 2000) {
// start using the GPS for heading if the compass has been
// inconsistent with the GPS for 2 seconds
return false;
}
} else {
_last_consistent_heading = AP_HAL::millis();
}
// use the compass
return true;
}
// return the quaternion defining the rotation from NED to XYZ (body) axes
bool AP_AHRS_DCM::get_quaternion(Quaternion &quat) const
{
quat.from_rotation_matrix(_dcm_matrix);
return true;
}
// yaw drift correction using the compass or GPS
// this function produces the _omega_yaw_P vector, and also
// contributes to the _omega_I.z long term yaw drift estimate
void
AP_AHRS_DCM::drift_correction_yaw(void)
{
bool new_value = false;
float yaw_error;
float yaw_deltat;
const AP_GPS &_gps = AP::gps();
Compass &compass = AP::compass();
#if COMPASS_CAL_ENABLED
if (compass.is_calibrating()) {
// don't do any yaw correction while calibrating
return;
}
#endif
if (AP_AHRS_DCM::use_compass()) {
/*
we are using compass for yaw
*/
if (compass.last_update_usec() != _compass_last_update) {
yaw_deltat = (compass.last_update_usec() - _compass_last_update) * 1.0e-6f;
_compass_last_update = compass.last_update_usec();
// we force an additional compass read()
// here. This has the effect of throwing away
// the first compass value, which can be bad
if (!have_initial_yaw && compass.read()) {
const float heading = compass.calculate_heading(_dcm_matrix);
_dcm_matrix.from_euler(roll, pitch, heading);
_omega_yaw_P.zero();
have_initial_yaw = true;
}
new_value = true;
yaw_error = yaw_error_compass(compass);
// also update the _gps_last_update, so if we later
// disable the compass due to significant yaw error we
// don't suddenly change yaw with a reset
_gps_last_update = _gps.last_fix_time_ms();
}
} else if (AP::ahrs().get_fly_forward() && have_gps()) {
/*
we are using GPS for yaw
*/
if (_gps.last_fix_time_ms() != _gps_last_update &&
_gps.ground_speed() >= GPS_SPEED_MIN) {
yaw_deltat = (_gps.last_fix_time_ms() - _gps_last_update) * 1.0e-3f;
_gps_last_update = _gps.last_fix_time_ms();
new_value = true;
const float gps_course_rad = ToRad(_gps.ground_course());
const float yaw_error_rad = wrap_PI(gps_course_rad - yaw);
yaw_error = sinf(yaw_error_rad);
/* reset yaw to match GPS heading under any of the
following 3 conditions:
1) if we have reached GPS_SPEED_MIN and have never had
yaw information before
2) if the last time we got yaw information from the GPS
is more than 20 seconds ago, which means we may have
suffered from considerable gyro drift
3) if we are over 3*GPS_SPEED_MIN (which means 9m/s)
and our yaw error is over 60 degrees, which means very
poor yaw. This can happen on bungee launch when the
operator pulls back the plane rapidly enough then on
release the GPS heading changes very rapidly
*/
if (!have_initial_yaw ||
yaw_deltat > 20 ||
(_gps.ground_speed() >= 3*GPS_SPEED_MIN && fabsf(yaw_error_rad) >= 1.047f)) {
// reset DCM matrix based on current yaw
_dcm_matrix.from_euler(roll, pitch, gps_course_rad);
_omega_yaw_P.zero();
have_initial_yaw = true;
yaw_error = 0;
}
}
}
if (!new_value) {
// we don't have any new yaw information
// slowly decay _omega_yaw_P to cope with loss
// of our yaw source
_omega_yaw_P *= 0.97f;
return;
}
// convert the error vector to body frame
const float error_z = _dcm_matrix.c.z * yaw_error;
// the spin rate changes the P gain, and disables the
// integration at higher rates
const float spin_rate = _omega.length();
// sanity check _kp_yaw
if (_kp_yaw < AP_AHRS_YAW_P_MIN) {
_kp_yaw.set(AP_AHRS_YAW_P_MIN);
}
// update the proportional control to drag the
// yaw back to the right value. We use a gain
// that depends on the spin rate. See the fastRotations.pdf
// paper from Bill Premerlani
// We also adjust the gain depending on the rate of change of horizontal velocity which
// is proportional to how observable the heading is from the accelerations and GPS velocity
// The acceleration derived heading will be more reliable in turns than compass or GPS
_omega_yaw_P.z = error_z * _P_gain(spin_rate) * _kp_yaw * _yaw_gain();
if (use_fast_gains()) {
_omega_yaw_P.z *= 8;
}
// don't update the drift term if we lost the yaw reference
// for more than 2 seconds
if (yaw_deltat < 2.0f && spin_rate < ToRad(SPIN_RATE_LIMIT)) {
// also add to the I term
_omega_I_sum.z += error_z * _ki_yaw * yaw_deltat;
}
_error_yaw = 0.8f * _error_yaw + 0.2f * fabsf(yaw_error);
}
/**
return an accel vector delayed by AHRS_ACCEL_DELAY samples for a
specific accelerometer instance
*/
Vector3f AP_AHRS_DCM::ra_delayed(uint8_t instance, const Vector3f &ra)
{
// get the old element, and then fill it with the new element
const Vector3f ret = _ra_delay_buffer[instance];
_ra_delay_buffer[instance] = ra;
if (ret.is_zero()) {
// use the current vector if the previous vector is exactly
// zero. This prevents an error on initialisation
return ra;
}
return ret;
}
/* returns true if attitude should be corrected from GPS-derived
* velocity-deltas. We turn this off for Copter and other similar
* vehicles while the vehicle is disarmed to avoid the HUD bobbing
* around while the vehicle is disarmed.
*/
bool AP_AHRS_DCM::should_correct_centrifugal() const
{
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduSub) || APM_BUILD_TYPE(APM_BUILD_Blimp)
return hal.util->get_soft_armed();
#endif
return true;
}
// perform drift correction. This function aims to update _omega_P and
// _omega_I with our best estimate of the short term and long term
// gyro error. The _omega_P value is what pulls our attitude solution
// back towards the reference vector quickly. The _omega_I term is an
// attempt to learn the long term drift rate of the gyros.
//
// This drift correction implementation is based on a paper
// by Bill Premerlani from here:
// http://gentlenav.googlecode.com/files/RollPitchDriftCompensation.pdf
void
AP_AHRS_DCM::drift_correction(float deltat)
{
Vector3f velocity;
uint32_t last_correction_time;
// perform yaw drift correction if we have a new yaw reference
// vector
drift_correction_yaw();
const AP_InertialSensor &_ins = AP::ins();
// rotate accelerometer values into the earth frame
for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
if (_ins.use_accel(i)) {
/*
by using get_delta_velocity() instead of get_accel() the
accel value is sampled over the right time delta for
each sensor, which prevents an aliasing effect
*/
Vector3f delta_velocity;
float delta_velocity_dt;
_ins.get_delta_velocity(i, delta_velocity, delta_velocity_dt);
if (delta_velocity_dt > 0) {
Vector3f accel_ef = _dcm_matrix * (delta_velocity / delta_velocity_dt);
// integrate the accel vector in the earth frame between GPS readings
_ra_sum[i] += accel_ef * deltat;
}
}
}
// set _accel_ef_blended based on filtered accel
_accel_ef = _dcm_matrix * _ins.get_accel();
// keep a sum of the deltat values, so we know how much time
// we have integrated over
_ra_deltat += deltat;
const AP_GPS &_gps = AP::gps();
const bool fly_forward = AP::ahrs().get_fly_forward();
if (!have_gps() ||
_gps.status() < AP_GPS::GPS_OK_FIX_3D ||
_gps.num_sats() < _gps_minsats) {
// no GPS, or not a good lock. From experience we need at
// least 6 satellites to get a really reliable velocity number
// from the GPS.
//
// As a fallback we use the fixed wing acceleration correction
// if we have an airspeed estimate (which we only have if
// _fly_forward is set), otherwise no correction
if (_ra_deltat < 0.2f) {
// not enough time has accumulated
return;
}
float airspeed = _last_airspeed;
#if AP_AIRSPEED_ENABLED
if (airspeed_sensor_enabled()) {
airspeed = AP::airspeed()->get_airspeed();
}
#endif
// use airspeed to estimate our ground velocity in
// earth frame by subtracting the wind
velocity = _dcm_matrix.colx() * airspeed;
// add in wind estimate
velocity += _wind;
last_correction_time = AP_HAL::millis();
_have_gps_lock = false;
} else {
if (_gps.last_fix_time_ms() == _ra_sum_start) {
// we don't have a new GPS fix - nothing more to do
return;
}
velocity = _gps.velocity();
last_correction_time = _gps.last_fix_time_ms();
if (_have_gps_lock == false) {
// if we didn't have GPS lock in the last drift
// correction interval then set the velocities equal
_last_velocity = velocity;
}
_have_gps_lock = true;
// keep last airspeed estimate for dead-reckoning purposes
Vector3f airspeed = velocity - _wind;
// rotate vector to body frame
airspeed = _body_dcm_matrix.mul_transpose(airspeed);
// take positive component in X direction. This mimics a pitot
// tube
_last_airspeed = MAX(airspeed.x, 0);
}
if (have_gps()) {
// use GPS for positioning with any fix, even a 2D fix
_last_lat = _gps.location().lat;
_last_lng = _gps.location().lng;
_last_pos_ms = AP_HAL::millis();
_position_offset_north = 0;
_position_offset_east = 0;
// once we have a single GPS lock, we can update using
// dead-reckoning from then on
_have_position = true;
} else {
// update dead-reckoning position estimate
_position_offset_north += velocity.x * _ra_deltat;
_position_offset_east += velocity.y * _ra_deltat;
}
// see if this is our first time through - in which case we
// just setup the start times and return
if (_ra_sum_start == 0) {
_ra_sum_start = last_correction_time;
_last_velocity = velocity;
return;
}
// equation 9: get the corrected acceleration vector in earth frame. Units
// are m/s/s
Vector3f GA_e(0.0f, 0.0f, -1.0f);
if (_ra_deltat <= 0) {
// waiting for more data
return;
}
bool using_gps_corrections = false;
float ra_scale = 1.0f/(_ra_deltat*GRAVITY_MSS);
if (should_correct_centrifugal() && (_have_gps_lock || fly_forward)) {
const float v_scale = gps_gain.get() * ra_scale;
const Vector3f vdelta = (velocity - _last_velocity) * v_scale;
GA_e += vdelta;
GA_e.normalize();
if (GA_e.is_inf()) {
// wait for some non-zero acceleration information
_last_failure_ms = AP_HAL::millis();
return;
}
using_gps_corrections = true;
}
// calculate the error term in earth frame.
// we do this for each available accelerometer then pick the
// accelerometer that leads to the smallest error term. This takes
// advantage of the different sample rates on different
// accelerometers to dramatically reduce the impact of aliasing
// due to harmonics of vibrations that match closely the sampling
// rate of our accelerometers. On the Pixhawk we have the LSM303D
// running at 800Hz and the MPU6000 running at 1kHz, by combining
// the two the effects of aliasing are greatly reduced.
Vector3f error[INS_MAX_INSTANCES];
float error_dirn[INS_MAX_INSTANCES];
Vector3f GA_b[INS_MAX_INSTANCES];
int8_t besti = -1;
float best_error = 0;
for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
if (!_ins.get_accel_health(i)) {
// only use healthy sensors
continue;
}
_ra_sum[i] *= ra_scale;
// get the delayed ra_sum to match the GPS lag
if (using_gps_corrections) {
GA_b[i] = ra_delayed(i, _ra_sum[i]);
} else {
GA_b[i] = _ra_sum[i];
}
if (GA_b[i].is_zero()) {
// wait for some non-zero acceleration information
continue;
}
GA_b[i].normalize();
if (GA_b[i].is_inf()) {
// wait for some non-zero acceleration information
continue;
}
error[i] = GA_b[i] % GA_e;
// Take dot product to catch case vectors are opposite sign and parallel
error_dirn[i] = GA_b[i] * GA_e;
const float error_length = error[i].length();
if (besti == -1 || error_length < best_error) {
besti = i;
best_error = error_length;
}
// Catch case where orientation is 180 degrees out
if (error_dirn[besti] < 0.0f) {
best_error = 1.0f;
}
}
if (besti == -1) {
// no healthy accelerometers!
_last_failure_ms = AP_HAL::millis();
return;
}
_active_accel_instance = besti;
#define YAW_INDEPENDENT_DRIFT_CORRECTION 0
#if YAW_INDEPENDENT_DRIFT_CORRECTION
// step 2 calculate earth_error_Z
const float earth_error_Z = error.z;
// equation 10
const float tilt = GA_e.xy().length();
// equation 11
const float theta = atan2f(GA_b[besti].y, GA_b[besti].x);
// equation 12
const Vector3f GA_e2 = Vector3f(cosf(theta)*tilt, sinf(theta)*tilt, GA_e.z);
// step 6
error = GA_b[besti] % GA_e2;
error.z = earth_error_Z;
#endif // YAW_INDEPENDENT_DRIFT_CORRECTION
// to reduce the impact of two competing yaw controllers, we
// reduce the impact of the gps/accelerometers on yaw when we are
// flat, but still allow for yaw correction using the
// accelerometers at high roll angles as long as we have a GPS
if (AP_AHRS_DCM::use_compass()) {
if (have_gps() && is_equal(gps_gain.get(), 1.0f)) {
error[besti].z *= sinf(fabsf(roll));
} else {
error[besti].z = 0;
}
}
// if ins is unhealthy then stop attitude drift correction and
// hope the gyros are OK for a while. Just slowly reduce _omega_P
// to prevent previous bad accels from throwing us off
if (!_ins.healthy()) {
error[besti].zero();
} else {
// convert the error term to body frame
error[besti] = _dcm_matrix.mul_transpose(error[besti]);
}
if (error[besti].is_nan() || error[besti].is_inf()) {
// don't allow bad values
check_matrix();
_last_failure_ms = AP_HAL::millis();
return;
}
_error_rp = 0.8f * _error_rp + 0.2f * best_error;
// base the P gain on the spin rate
const float spin_rate = _omega.length();
// sanity check _kp value
if (_kp < AP_AHRS_RP_P_MIN) {
_kp.set(AP_AHRS_RP_P_MIN);
}
// we now want to calculate _omega_P and _omega_I. The
// _omega_P value is what drags us quickly to the
// accelerometer reading.
_omega_P = error[besti] * _P_gain(spin_rate) * _kp;
if (use_fast_gains()) {
_omega_P *= 8;
}
if (fly_forward && _gps.status() >= AP_GPS::GPS_OK_FIX_2D &&
_gps.ground_speed() < GPS_SPEED_MIN &&
_ins.get_accel().x >= 7 &&
pitch > radians(-30) && pitch < radians(30)) {
// assume we are in a launch acceleration, and reduce the
// rp gain by 50% to reduce the impact of GPS lag on
// takeoff attitude when using a catapult
_omega_P *= 0.5f;
}
// accumulate some integrator error
if (spin_rate < ToRad(SPIN_RATE_LIMIT)) {
_omega_I_sum += error[besti] * _ki * _ra_deltat;
_omega_I_sum_time += _ra_deltat;
}
if (_omega_I_sum_time >= 5) {
// limit the rate of change of omega_I to the hardware
// reported maximum gyro drift rate. This ensures that
// short term errors don't cause a buildup of omega_I
// beyond the physical limits of the device
const float change_limit = AP::ins().get_gyro_drift_rate() * _omega_I_sum_time;
_omega_I_sum.x = constrain_float(_omega_I_sum.x, -change_limit, change_limit);
_omega_I_sum.y = constrain_float(_omega_I_sum.y, -change_limit, change_limit);
_omega_I_sum.z = constrain_float(_omega_I_sum.z, -change_limit, change_limit);
_omega_I += _omega_I_sum;
_omega_I_sum.zero();
_omega_I_sum_time = 0;
}
// zero our accumulator ready for the next GPS step
memset((void *)&_ra_sum[0], 0, sizeof(_ra_sum));
_ra_deltat = 0;
_ra_sum_start = last_correction_time;
// remember the velocity for next time
_last_velocity = velocity;
}
// update our wind speed estimate
void AP_AHRS_DCM::estimate_wind(void)
{
if (!AP::ahrs().get_wind_estimation_enabled()) {
return;
}
const Vector3f &velocity = _last_velocity;
// this is based on the wind speed estimation code from MatrixPilot by
// Bill Premerlani. Adaption for ArduPilot by Jon Challinger
// See http://gentlenav.googlecode.com/files/WindEstimation.pdf
const Vector3f fuselageDirection = _dcm_matrix.colx();
const Vector3f fuselageDirectionDiff = fuselageDirection - _last_fuse;
const uint32_t now = AP_HAL::millis();
// scrap our data and start over if we're taking too long to get a direction change
if (now - _last_wind_time > 10000) {
_last_wind_time = now;