CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_AHRS/AP_AHRS_DCM.cpp
Views: 1798
1
/*
2
* APM_AHRS_DCM.cpp
3
*
4
* AHRS system using DCM matrices
5
*
6
* Based on DCM code by Doug Weibel, Jordi Munoz and Jose Julio. DIYDrones.com
7
*
8
* Adapted for the general ArduPilot AHRS interface by Andrew Tridgell
9
10
This program is free software: you can redistribute it and/or modify
11
it under the terms of the GNU General Public License as published by
12
the Free Software Foundation, either version 3 of the License, or
13
(at your option) any later version.
14
15
This program is distributed in the hope that it will be useful,
16
but WITHOUT ANY WARRANTY; without even the implied warranty of
17
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
18
GNU General Public License for more details.
19
20
You should have received a copy of the GNU General Public License
21
along with this program. If not, see <http://www.gnu.org/licenses/>.
22
*/
23
24
#include "AP_AHRS_config.h"
25
26
#if AP_AHRS_DCM_ENABLED
27
28
#include "AP_AHRS.h"
29
#include <AP_HAL/AP_HAL.h>
30
#include <GCS_MAVLink/GCS.h>
31
#include <AP_GPS/AP_GPS.h>
32
#include <AP_Baro/AP_Baro.h>
33
#include <AP_Compass/AP_Compass.h>
34
#include <AP_Logger/AP_Logger.h>
35
#include <AP_Vehicle/AP_Vehicle_Type.h>
36
37
extern const AP_HAL::HAL& hal;
38
39
// this is the speed in m/s above which we first get a yaw lock with
40
// the GPS
41
#define GPS_SPEED_MIN 3
42
43
// the limit (in degrees/second) beyond which we stop integrating
44
// omega_I. At larger spin rates the DCM PI controller can get 'dizzy'
45
// which results in false gyro drift. See
46
// http://gentlenav.googlecode.com/files/fastRotations.pdf
47
#define SPIN_RATE_LIMIT 20
48
49
// reset the current gyro drift estimate
50
// should be called if gyro offsets are recalculated
51
void
52
AP_AHRS_DCM::reset_gyro_drift(void)
53
{
54
_omega_I.zero();
55
_omega_I_sum.zero();
56
_omega_I_sum_time = 0;
57
}
58
59
// run a full DCM update round
60
void
61
AP_AHRS_DCM::update()
62
{
63
AP_InertialSensor &_ins = AP::ins();
64
65
// ask the IMU how much time this sensor reading represents
66
const float delta_t = _ins.get_delta_time();
67
68
// if the update call took more than 0.2 seconds then discard it,
69
// otherwise we may move too far. This happens when arming motors
70
// in ArduCopter
71
if (delta_t > 0.2f) {
72
memset((void *)&_ra_sum[0], 0, sizeof(_ra_sum));
73
_ra_deltat = 0;
74
return;
75
}
76
77
// Integrate the DCM matrix using gyro inputs
78
matrix_update();
79
80
// Normalize the DCM matrix
81
normalize();
82
83
// Perform drift correction
84
drift_correction(delta_t);
85
86
// paranoid check for bad values in the DCM matrix
87
check_matrix();
88
89
// calculate the euler angles and DCM matrix which will be used
90
// for high level navigation control. Apply trim such that a
91
// positive trim value results in a positive vehicle rotation
92
// about that axis (ie a negative offset)
93
_body_dcm_matrix = _dcm_matrix * AP::ahrs().get_rotation_vehicle_body_to_autopilot_body();
94
_body_dcm_matrix.to_euler(&roll, &pitch, &yaw);
95
96
// pre-calculate some trig for CPU purposes:
97
_cos_yaw = cosf(yaw);
98
_sin_yaw = sinf(yaw);
99
100
backup_attitude();
101
102
// remember the last origin for fallback support
103
IGNORE_RETURN(AP::ahrs().get_origin(last_origin));
104
105
#if HAL_LOGGING_ENABLED
106
const uint32_t now_ms = AP_HAL::millis();
107
if (now_ms - last_log_ms >= 100) {
108
// log DCM at 10Hz
109
last_log_ms = now_ms;
110
111
// @LoggerMessage: DCM
112
// @Description: DCM Estimator Data
113
// @Field: TimeUS: Time since system startup
114
// @Field: Roll: estimated roll
115
// @Field: Pitch: estimated pitch
116
// @Field: Yaw: estimated yaw
117
// @Field: ErrRP: lowest estimated gyro drift error
118
// @Field: ErrYaw: difference between measured yaw and DCM yaw estimate
119
// @Field: VWN: wind velocity, to-the-North component
120
// @Field: VWE: wind velocity, to-the-East component
121
// @Field: VWD: wind velocity, Up-to-Down component
122
AP::logger().WriteStreaming(
123
"DCM",
124
"TimeUS," "Roll," "Pitch," "Yaw," "ErrRP," "ErrYaw," "VWN," "VWE," "VWD",
125
"s" "d" "d" "d" "d" "h" "n" "n" "n",
126
"F" "0" "0" "0" "0" "0" "0" "0" "0",
127
"Q" "f" "f" "f" "f" "f" "f" "f" "f",
128
AP_HAL::micros64(),
129
degrees(roll),
130
degrees(pitch),
131
wrap_360(degrees(yaw)),
132
get_error_rp(),
133
get_error_yaw(),
134
_wind.x,
135
_wind.y,
136
_wind.z
137
);
138
}
139
#endif // HAL_LOGGING_ENABLED
140
}
141
142
void AP_AHRS_DCM::get_results(AP_AHRS_Backend::Estimates &results)
143
{
144
results.roll_rad = roll;
145
results.pitch_rad = pitch;
146
results.yaw_rad = yaw;
147
148
results.dcm_matrix = _body_dcm_matrix;
149
results.gyro_estimate = _omega;
150
results.gyro_drift = _omega_I;
151
results.accel_ef = _accel_ef;
152
153
results.location_valid = get_location(results.location);
154
}
155
156
/*
157
backup attitude to persistent_data for use in watchdog reset
158
*/
159
void AP_AHRS_DCM::backup_attitude(void)
160
{
161
AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
162
pd.roll_rad = roll;
163
pd.pitch_rad = pitch;
164
pd.yaw_rad = yaw;
165
}
166
167
// update the DCM matrix using only the gyros
168
void AP_AHRS_DCM::matrix_update(void)
169
{
170
// use only the primary gyro so our bias estimate is valid, allowing us to return the right filtered gyro
171
// for rate controllers
172
const auto &_ins = AP::ins();
173
Vector3f delta_angle;
174
float dangle_dt;
175
if (_ins.get_delta_angle(delta_angle, dangle_dt) && dangle_dt > 0) {
176
_omega = delta_angle / dangle_dt;
177
_omega += _omega_I;
178
_dcm_matrix.rotate((_omega + _omega_P + _omega_yaw_P) * dangle_dt);
179
}
180
181
// now update _omega from the filtered value from the primary IMU. We need to use
182
// the primary IMU as the notch filters will only be running on one IMU
183
184
// note that we do not include the P terms in _omega. This is
185
// because the spin_rate is calculated from _omega.length(),
186
// and including the P terms would give positive feedback into
187
// the _P_gain() calculation, which can lead to a very large P
188
// value
189
_omega = _ins.get_gyro() + _omega_I;
190
}
191
192
193
/*
194
* reset the DCM matrix and omega. Used on ground start, and on
195
* extreme errors in the matrix
196
*/
197
void
198
AP_AHRS_DCM::reset(bool recover_eulers)
199
{
200
// reset the integration terms
201
_omega_I.zero();
202
_omega_P.zero();
203
_omega_yaw_P.zero();
204
_omega.zero();
205
206
// if the caller wants us to try to recover to the current
207
// attitude then calculate the dcm matrix from the current
208
// roll/pitch/yaw values
209
if (hal.util->was_watchdog_reset() && AP_HAL::millis() < 10000) {
210
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
211
roll = pd.roll_rad;
212
pitch = pd.pitch_rad;
213
yaw = pd.yaw_rad;
214
_dcm_matrix.from_euler(roll, pitch, yaw);
215
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Restored watchdog attitude %.0f %.0f %.0f",
216
degrees(roll), degrees(pitch), degrees(yaw));
217
} else if (recover_eulers && !isnan(roll) && !isnan(pitch) && !isnan(yaw)) {
218
_dcm_matrix.from_euler(roll, pitch, yaw);
219
} else {
220
221
// Use the measured accel due to gravity to calculate an initial
222
// roll and pitch estimate
223
224
AP_InertialSensor &_ins = AP::ins();
225
226
// Get body frame accel vector
227
Vector3f initAccVec = _ins.get_accel();
228
uint8_t counter = 0;
229
230
// the first vector may be invalid as the filter starts up
231
while ((initAccVec.length() < 9.0f || initAccVec.length() > 11) && counter++ < 20) {
232
_ins.wait_for_sample();
233
_ins.update();
234
initAccVec = _ins.get_accel();
235
}
236
237
// normalise the acceleration vector
238
if (initAccVec.length() > 5.0f) {
239
// calculate initial pitch angle
240
pitch = atan2f(initAccVec.x, norm(initAccVec.y, initAccVec.z));
241
// calculate initial roll angle
242
roll = atan2f(-initAccVec.y, -initAccVec.z);
243
} else {
244
// If we can't use the accel vector, then align flat
245
roll = 0.0f;
246
pitch = 0.0f;
247
}
248
_dcm_matrix.from_euler(roll, pitch, 0);
249
250
}
251
252
// pre-calculate some trig for CPU purposes:
253
_cos_yaw = cosf(yaw);
254
_sin_yaw = sinf(yaw);
255
256
_last_startup_ms = AP_HAL::millis();
257
}
258
259
/*
260
* check the DCM matrix for pathological values
261
*/
262
void
263
AP_AHRS_DCM::check_matrix(void)
264
{
265
if (_dcm_matrix.is_nan()) {
266
//Serial.printf("ERROR: DCM matrix NAN\n");
267
AP_AHRS_DCM::reset(true);
268
return;
269
}
270
// some DCM matrix values can lead to an out of range error in
271
// the pitch calculation via asin(). These NaN values can
272
// feed back into the rest of the DCM matrix via the
273
// error_course value.
274
if (!(_dcm_matrix.c.x < 1.0f &&
275
_dcm_matrix.c.x > -1.0f)) {
276
// We have an invalid matrix. Force a normalisation.
277
normalize();
278
279
if (_dcm_matrix.is_nan() ||
280
fabsf(_dcm_matrix.c.x) > 10.0) {
281
// See Issue #20284: regarding the selection of 10.0 for DCM reset
282
// This won't be lowered without evidence of an issue or mathematical proof & testing of a lower bound
283
284
// normalisation didn't fix the problem! We're
285
// in real trouble. All we can do is reset
286
//Serial.printf("ERROR: DCM matrix error. _dcm_matrix.c.x=%f\n",
287
// _dcm_matrix.c.x);
288
AP_AHRS_DCM::reset(true);
289
}
290
}
291
}
292
293
// renormalise one vector component of the DCM matrix
294
// this will return false if renormalization fails
295
bool
296
AP_AHRS_DCM::renorm(Vector3f const &a, Vector3f &result)
297
{
298
// numerical errors will slowly build up over time in DCM,
299
// causing inaccuracies. We can keep ahead of those errors
300
// using the renormalization technique from the DCM IMU paper
301
// (see equations 18 to 21).
302
303
// For APM we don't bother with the taylor expansion
304
// optimisation from the paper as on our 2560 CPU the cost of
305
// the sqrt() is 44 microseconds, and the small time saving of
306
// the taylor expansion is not worth the potential of
307
// additional error buildup.
308
309
// Note that we can get significant renormalisation values
310
// when we have a larger delta_t due to a glitch elsewhere in
311
// APM, such as a I2c timeout or a set of EEPROM writes. While
312
// we would like to avoid these if possible, if it does happen
313
// we don't want to compound the error by making DCM less
314
// accurate.
315
316
const float renorm_val = 1.0f / a.length();
317
318
// keep the average for reporting
319
_renorm_val_sum += renorm_val;
320
_renorm_val_count++;
321
322
if (!(renorm_val < 2.0f && renorm_val > 0.5f)) {
323
// this is larger than it should get - log it as a warning
324
if (!(renorm_val < 1.0e6f && renorm_val > 1.0e-6f)) {
325
// we are getting values which are way out of
326
// range, we will reset the matrix and hope we
327
// can recover our attitude using drift
328
// correction before we hit the ground!
329
//Serial.printf("ERROR: DCM renormalisation error. renorm_val=%f\n",
330
// renorm_val);
331
return false;
332
}
333
}
334
335
result = a * renorm_val;
336
return true;
337
}
338
339
/*************************************************
340
* Direction Cosine Matrix IMU: Theory
341
* William Premerlani and Paul Bizard
342
*
343
* Numerical errors will gradually reduce the orthogonality conditions expressed by equation 5
344
* to approximations rather than identities. In effect, the axes in the two frames of reference no
345
* longer describe a rigid body. Fortunately, numerical error accumulates very slowly, so it is a
346
* simple matter to stay ahead of it.
347
* We call the process of enforcing the orthogonality conditions: renormalization.
348
*/
349
void
350
AP_AHRS_DCM::normalize(void)
351
{
352
const float error = _dcm_matrix.a * _dcm_matrix.b; // eq.18
353
354
const Vector3f t0 = _dcm_matrix.a - (_dcm_matrix.b * (0.5f * error)); // eq.19
355
const Vector3f t1 = _dcm_matrix.b - (_dcm_matrix.a * (0.5f * error)); // eq.19
356
const Vector3f t2 = t0 % t1; // c= a x b // eq.20
357
358
if (!renorm(t0, _dcm_matrix.a) ||
359
!renorm(t1, _dcm_matrix.b) ||
360
!renorm(t2, _dcm_matrix.c)) {
361
// Our solution is blowing up and we will force back
362
// to last euler angles
363
_last_failure_ms = AP_HAL::millis();
364
AP_AHRS_DCM::reset(true);
365
}
366
}
367
368
369
// produce a yaw error value. The returned value is proportional
370
// to sin() of the current heading error in earth frame
371
float
372
AP_AHRS_DCM::yaw_error_compass(Compass &compass)
373
{
374
const Vector3f &mag = compass.get_field();
375
// get the mag vector in the earth frame
376
Vector2f rb = _dcm_matrix.mulXY(mag);
377
378
if (rb.length() < FLT_EPSILON) {
379
return 0.0f;
380
}
381
382
rb.normalize();
383
if (rb.is_inf()) {
384
// not a valid vector
385
return 0.0f;
386
}
387
388
// update vector holding earths magnetic field (if required)
389
if( !is_equal(_last_declination, compass.get_declination()) ) {
390
_last_declination = compass.get_declination();
391
_mag_earth.x = cosf(_last_declination);
392
_mag_earth.y = sinf(_last_declination);
393
}
394
395
// calculate the error term in earth frame
396
// calculate the Z component of the cross product of rb and _mag_earth
397
return rb % _mag_earth;
398
}
399
400
// the _P_gain raises the gain of the PI controller
401
// when we are spinning fast. See the fastRotations
402
// paper from Bill.
403
float
404
AP_AHRS_DCM::_P_gain(float spin_rate)
405
{
406
if (spin_rate < ToRad(50)) {
407
return 1.0f;
408
}
409
if (spin_rate > ToRad(500)) {
410
return 10.0f;
411
}
412
return spin_rate/ToRad(50);
413
}
414
415
// _yaw_gain reduces the gain of the PI controller applied to heading errors
416
// when observability from change of velocity is good (eg changing speed or turning)
417
// This reduces unwanted roll and pitch coupling due to compass errors for planes.
418
// High levels of noise on _accel_ef will cause the gain to drop and could lead to
419
// increased heading drift during straight and level flight, however some gain is
420
// always available. TODO check the necessity of adding adjustable acc threshold
421
// and/or filtering accelerations before getting magnitude
422
float
423
AP_AHRS_DCM::_yaw_gain(void) const
424
{
425
const float VdotEFmag = _accel_ef.xy().length();
426
427
if (VdotEFmag <= 4.0f) {
428
return 0.2f*(4.5f - VdotEFmag);
429
}
430
return 0.1f;
431
}
432
433
434
// return true if we have and should use GPS
435
bool AP_AHRS_DCM::have_gps(void) const
436
{
437
if (_gps_use == GPSUse::Disable || AP::gps().status() <= AP_GPS::NO_FIX) {
438
return false;
439
}
440
return true;
441
}
442
443
/*
444
when we are getting the initial attitude we want faster gains so
445
that if the board starts upside down we quickly approach the right
446
attitude.
447
We don't want to keep those high gains for too long though as high P
448
gains cause slow gyro offset learning. So we keep the high gains for
449
a maximum of 20 seconds
450
*/
451
bool AP_AHRS_DCM::use_fast_gains(void) const
452
{
453
return !hal.util->get_soft_armed() && (AP_HAL::millis() - _last_startup_ms) < 20000U;
454
}
455
456
457
// return true if we should use the compass for yaw correction
458
bool AP_AHRS_DCM::use_compass(void)
459
{
460
const Compass &compass = AP::compass();
461
462
if (!compass.use_for_yaw()) {
463
// no compass available
464
return false;
465
}
466
if (!AP::ahrs().get_fly_forward() || !have_gps()) {
467
// we don't have any alternative to the compass
468
return true;
469
}
470
if (AP::gps().ground_speed() < GPS_SPEED_MIN) {
471
// we are not going fast enough to use the GPS
472
return true;
473
}
474
475
// if the current yaw differs from the GPS yaw by more than 45
476
// degrees and the estimated wind speed is less than 80% of the
477
// ground speed, then switch to GPS navigation. This will help
478
// prevent flyaways with very bad compass offsets
479
const float error = fabsf(wrap_180(degrees(yaw) - AP::gps().ground_course()));
480
if (error > 45 && _wind.length() < AP::gps().ground_speed()*0.8f) {
481
if (AP_HAL::millis() - _last_consistent_heading > 2000) {
482
// start using the GPS for heading if the compass has been
483
// inconsistent with the GPS for 2 seconds
484
return false;
485
}
486
} else {
487
_last_consistent_heading = AP_HAL::millis();
488
}
489
490
// use the compass
491
return true;
492
}
493
494
// return the quaternion defining the rotation from NED to XYZ (body) axes
495
bool AP_AHRS_DCM::get_quaternion(Quaternion &quat) const
496
{
497
quat.from_rotation_matrix(_dcm_matrix);
498
return true;
499
}
500
501
// yaw drift correction using the compass or GPS
502
// this function produces the _omega_yaw_P vector, and also
503
// contributes to the _omega_I.z long term yaw drift estimate
504
void
505
AP_AHRS_DCM::drift_correction_yaw(void)
506
{
507
bool new_value = false;
508
float yaw_error;
509
float yaw_deltat;
510
511
const AP_GPS &_gps = AP::gps();
512
513
Compass &compass = AP::compass();
514
515
#if COMPASS_CAL_ENABLED
516
if (compass.is_calibrating()) {
517
// don't do any yaw correction while calibrating
518
return;
519
}
520
#endif
521
522
if (AP_AHRS_DCM::use_compass()) {
523
/*
524
we are using compass for yaw
525
*/
526
if (compass.last_update_usec() != _compass_last_update) {
527
yaw_deltat = (compass.last_update_usec() - _compass_last_update) * 1.0e-6f;
528
_compass_last_update = compass.last_update_usec();
529
// we force an additional compass read()
530
// here. This has the effect of throwing away
531
// the first compass value, which can be bad
532
if (!have_initial_yaw && compass.read()) {
533
const float heading = compass.calculate_heading(_dcm_matrix);
534
_dcm_matrix.from_euler(roll, pitch, heading);
535
_omega_yaw_P.zero();
536
have_initial_yaw = true;
537
}
538
new_value = true;
539
yaw_error = yaw_error_compass(compass);
540
541
// also update the _gps_last_update, so if we later
542
// disable the compass due to significant yaw error we
543
// don't suddenly change yaw with a reset
544
_gps_last_update = _gps.last_fix_time_ms();
545
}
546
} else if (AP::ahrs().get_fly_forward() && have_gps()) {
547
/*
548
we are using GPS for yaw
549
*/
550
if (_gps.last_fix_time_ms() != _gps_last_update &&
551
_gps.ground_speed() >= GPS_SPEED_MIN) {
552
yaw_deltat = (_gps.last_fix_time_ms() - _gps_last_update) * 1.0e-3f;
553
_gps_last_update = _gps.last_fix_time_ms();
554
new_value = true;
555
const float gps_course_rad = ToRad(_gps.ground_course());
556
const float yaw_error_rad = wrap_PI(gps_course_rad - yaw);
557
yaw_error = sinf(yaw_error_rad);
558
559
/* reset yaw to match GPS heading under any of the
560
following 3 conditions:
561
562
1) if we have reached GPS_SPEED_MIN and have never had
563
yaw information before
564
565
2) if the last time we got yaw information from the GPS
566
is more than 20 seconds ago, which means we may have
567
suffered from considerable gyro drift
568
569
3) if we are over 3*GPS_SPEED_MIN (which means 9m/s)
570
and our yaw error is over 60 degrees, which means very
571
poor yaw. This can happen on bungee launch when the
572
operator pulls back the plane rapidly enough then on
573
release the GPS heading changes very rapidly
574
*/
575
if (!have_initial_yaw ||
576
yaw_deltat > 20 ||
577
(_gps.ground_speed() >= 3*GPS_SPEED_MIN && fabsf(yaw_error_rad) >= 1.047f)) {
578
// reset DCM matrix based on current yaw
579
_dcm_matrix.from_euler(roll, pitch, gps_course_rad);
580
_omega_yaw_P.zero();
581
have_initial_yaw = true;
582
yaw_error = 0;
583
}
584
}
585
}
586
587
if (!new_value) {
588
// we don't have any new yaw information
589
// slowly decay _omega_yaw_P to cope with loss
590
// of our yaw source
591
_omega_yaw_P *= 0.97f;
592
return;
593
}
594
595
// convert the error vector to body frame
596
const float error_z = _dcm_matrix.c.z * yaw_error;
597
598
// the spin rate changes the P gain, and disables the
599
// integration at higher rates
600
const float spin_rate = _omega.length();
601
602
// sanity check _kp_yaw
603
if (_kp_yaw < AP_AHRS_YAW_P_MIN) {
604
_kp_yaw.set(AP_AHRS_YAW_P_MIN);
605
}
606
607
// update the proportional control to drag the
608
// yaw back to the right value. We use a gain
609
// that depends on the spin rate. See the fastRotations.pdf
610
// paper from Bill Premerlani
611
// We also adjust the gain depending on the rate of change of horizontal velocity which
612
// is proportional to how observable the heading is from the accelerations and GPS velocity
613
// The acceleration derived heading will be more reliable in turns than compass or GPS
614
615
_omega_yaw_P.z = error_z * _P_gain(spin_rate) * _kp_yaw * _yaw_gain();
616
if (use_fast_gains()) {
617
_omega_yaw_P.z *= 8;
618
}
619
620
// don't update the drift term if we lost the yaw reference
621
// for more than 2 seconds
622
if (yaw_deltat < 2.0f && spin_rate < ToRad(SPIN_RATE_LIMIT)) {
623
// also add to the I term
624
_omega_I_sum.z += error_z * _ki_yaw * yaw_deltat;
625
}
626
627
_error_yaw = 0.8f * _error_yaw + 0.2f * fabsf(yaw_error);
628
}
629
630
631
/**
632
return an accel vector delayed by AHRS_ACCEL_DELAY samples for a
633
specific accelerometer instance
634
*/
635
Vector3f AP_AHRS_DCM::ra_delayed(uint8_t instance, const Vector3f &ra)
636
{
637
// get the old element, and then fill it with the new element
638
const Vector3f ret = _ra_delay_buffer[instance];
639
_ra_delay_buffer[instance] = ra;
640
if (ret.is_zero()) {
641
// use the current vector if the previous vector is exactly
642
// zero. This prevents an error on initialisation
643
return ra;
644
}
645
return ret;
646
}
647
648
/* returns true if attitude should be corrected from GPS-derived
649
* velocity-deltas. We turn this off for Copter and other similar
650
* vehicles while the vehicle is disarmed to avoid the HUD bobbing
651
* around while the vehicle is disarmed.
652
*/
653
bool AP_AHRS_DCM::should_correct_centrifugal() const
654
{
655
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduSub) || APM_BUILD_TYPE(APM_BUILD_Blimp)
656
return hal.util->get_soft_armed();
657
#endif
658
659
return true;
660
}
661
662
// perform drift correction. This function aims to update _omega_P and
663
// _omega_I with our best estimate of the short term and long term
664
// gyro error. The _omega_P value is what pulls our attitude solution
665
// back towards the reference vector quickly. The _omega_I term is an
666
// attempt to learn the long term drift rate of the gyros.
667
//
668
// This drift correction implementation is based on a paper
669
// by Bill Premerlani from here:
670
// http://gentlenav.googlecode.com/files/RollPitchDriftCompensation.pdf
671
void
672
AP_AHRS_DCM::drift_correction(float deltat)
673
{
674
Vector3f velocity;
675
uint32_t last_correction_time;
676
677
// perform yaw drift correction if we have a new yaw reference
678
// vector
679
drift_correction_yaw();
680
681
const AP_InertialSensor &_ins = AP::ins();
682
683
// rotate accelerometer values into the earth frame
684
for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
685
if (_ins.use_accel(i)) {
686
/*
687
by using get_delta_velocity() instead of get_accel() the
688
accel value is sampled over the right time delta for
689
each sensor, which prevents an aliasing effect
690
*/
691
Vector3f delta_velocity;
692
float delta_velocity_dt;
693
_ins.get_delta_velocity(i, delta_velocity, delta_velocity_dt);
694
if (delta_velocity_dt > 0) {
695
Vector3f accel_ef = _dcm_matrix * (delta_velocity / delta_velocity_dt);
696
// integrate the accel vector in the earth frame between GPS readings
697
_ra_sum[i] += accel_ef * deltat;
698
}
699
}
700
}
701
702
// set _accel_ef_blended based on filtered accel
703
_accel_ef = _dcm_matrix * _ins.get_accel();
704
705
// keep a sum of the deltat values, so we know how much time
706
// we have integrated over
707
_ra_deltat += deltat;
708
709
const AP_GPS &_gps = AP::gps();
710
const bool fly_forward = AP::ahrs().get_fly_forward();
711
712
if (!have_gps() ||
713
_gps.status() < AP_GPS::GPS_OK_FIX_3D ||
714
_gps.num_sats() < _gps_minsats) {
715
// no GPS, or not a good lock. From experience we need at
716
// least 6 satellites to get a really reliable velocity number
717
// from the GPS.
718
//
719
// As a fallback we use the fixed wing acceleration correction
720
// if we have an airspeed estimate (which we only have if
721
// _fly_forward is set), otherwise no correction
722
if (_ra_deltat < 0.2f) {
723
// not enough time has accumulated
724
return;
725
}
726
727
float airspeed_TAS = _last_airspeed_TAS;
728
#if AP_AIRSPEED_ENABLED
729
if (airspeed_sensor_enabled()) {
730
airspeed_TAS = AP::airspeed()->get_airspeed() * get_EAS2TAS();
731
}
732
#endif
733
734
// use airspeed to estimate our ground velocity in
735
// earth frame by subtracting the wind
736
velocity = _dcm_matrix.colx() * airspeed_TAS;
737
738
// add in wind estimate
739
velocity += _wind;
740
741
last_correction_time = AP_HAL::millis();
742
_have_gps_lock = false;
743
} else {
744
if (_gps.last_fix_time_ms() == _ra_sum_start) {
745
// we don't have a new GPS fix - nothing more to do
746
return;
747
}
748
velocity = _gps.velocity();
749
last_correction_time = _gps.last_fix_time_ms();
750
if (_have_gps_lock == false) {
751
// if we didn't have GPS lock in the last drift
752
// correction interval then set the velocities equal
753
_last_velocity = velocity;
754
}
755
_have_gps_lock = true;
756
757
// keep last airspeed estimate for dead-reckoning purposes
758
Vector3f airspeed = velocity - _wind;
759
760
// rotate vector to body frame
761
airspeed = _body_dcm_matrix.mul_transpose(airspeed);
762
763
// take positive component in X direction. This mimics a pitot
764
// tube
765
_last_airspeed_TAS = MAX(airspeed.x, 0);
766
}
767
768
if (have_gps()) {
769
// use GPS for positioning with any fix, even a 2D fix
770
_last_lat = _gps.location().lat;
771
_last_lng = _gps.location().lng;
772
_last_pos_ms = AP_HAL::millis();
773
_position_offset_north = 0;
774
_position_offset_east = 0;
775
776
// once we have a single GPS lock, we can update using
777
// dead-reckoning from then on
778
_have_position = true;
779
} else {
780
// update dead-reckoning position estimate
781
_position_offset_north += velocity.x * _ra_deltat;
782
_position_offset_east += velocity.y * _ra_deltat;
783
}
784
785
// see if this is our first time through - in which case we
786
// just setup the start times and return
787
if (_ra_sum_start == 0) {
788
_ra_sum_start = last_correction_time;
789
_last_velocity = velocity;
790
return;
791
}
792
793
// equation 9: get the corrected acceleration vector in earth frame. Units
794
// are m/s/s
795
Vector3f GA_e(0.0f, 0.0f, -1.0f);
796
797
if (_ra_deltat <= 0) {
798
// waiting for more data
799
return;
800
}
801
802
bool using_gps_corrections = false;
803
float ra_scale = 1.0f/(_ra_deltat*GRAVITY_MSS);
804
805
if (should_correct_centrifugal() && (_have_gps_lock || fly_forward)) {
806
const float v_scale = gps_gain.get() * ra_scale;
807
const Vector3f vdelta = (velocity - _last_velocity) * v_scale;
808
GA_e += vdelta;
809
GA_e.normalize();
810
if (GA_e.is_inf()) {
811
// wait for some non-zero acceleration information
812
_last_failure_ms = AP_HAL::millis();
813
return;
814
}
815
using_gps_corrections = true;
816
}
817
818
// calculate the error term in earth frame.
819
// we do this for each available accelerometer then pick the
820
// accelerometer that leads to the smallest error term. This takes
821
// advantage of the different sample rates on different
822
// accelerometers to dramatically reduce the impact of aliasing
823
// due to harmonics of vibrations that match closely the sampling
824
// rate of our accelerometers. On the Pixhawk we have the LSM303D
825
// running at 800Hz and the MPU6000 running at 1kHz, by combining
826
// the two the effects of aliasing are greatly reduced.
827
Vector3f error[INS_MAX_INSTANCES];
828
float error_dirn[INS_MAX_INSTANCES];
829
Vector3f GA_b[INS_MAX_INSTANCES];
830
int8_t besti = -1;
831
float best_error = 0;
832
for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
833
if (!_ins.get_accel_health(i)) {
834
// only use healthy sensors
835
continue;
836
}
837
_ra_sum[i] *= ra_scale;
838
839
// get the delayed ra_sum to match the GPS lag
840
if (using_gps_corrections) {
841
GA_b[i] = ra_delayed(i, _ra_sum[i]);
842
} else {
843
GA_b[i] = _ra_sum[i];
844
}
845
if (GA_b[i].is_zero()) {
846
// wait for some non-zero acceleration information
847
continue;
848
}
849
GA_b[i].normalize();
850
if (GA_b[i].is_inf()) {
851
// wait for some non-zero acceleration information
852
continue;
853
}
854
error[i] = GA_b[i] % GA_e;
855
// Take dot product to catch case vectors are opposite sign and parallel
856
error_dirn[i] = GA_b[i] * GA_e;
857
const float error_length = error[i].length();
858
if (besti == -1 || error_length < best_error) {
859
besti = i;
860
best_error = error_length;
861
}
862
// Catch case where orientation is 180 degrees out
863
if (error_dirn[besti] < 0.0f) {
864
best_error = 1.0f;
865
}
866
867
}
868
869
if (besti == -1) {
870
// no healthy accelerometers!
871
_last_failure_ms = AP_HAL::millis();
872
return;
873
}
874
875
_active_accel_instance = besti;
876
877
#define YAW_INDEPENDENT_DRIFT_CORRECTION 0
878
#if YAW_INDEPENDENT_DRIFT_CORRECTION
879
// step 2 calculate earth_error_Z
880
const float earth_error_Z = error.z;
881
882
// equation 10
883
const float tilt = GA_e.xy().length();
884
885
// equation 11
886
const float theta = atan2f(GA_b[besti].y, GA_b[besti].x);
887
888
// equation 12
889
const Vector3f GA_e2 = Vector3f(cosf(theta)*tilt, sinf(theta)*tilt, GA_e.z);
890
891
// step 6
892
error = GA_b[besti] % GA_e2;
893
error.z = earth_error_Z;
894
#endif // YAW_INDEPENDENT_DRIFT_CORRECTION
895
896
// to reduce the impact of two competing yaw controllers, we
897
// reduce the impact of the gps/accelerometers on yaw when we are
898
// flat, but still allow for yaw correction using the
899
// accelerometers at high roll angles as long as we have a GPS
900
if (AP_AHRS_DCM::use_compass()) {
901
if (have_gps() && is_equal(gps_gain.get(), 1.0f)) {
902
error[besti].z *= sinf(fabsf(roll));
903
} else {
904
error[besti].z = 0;
905
}
906
}
907
908
// if ins is unhealthy then stop attitude drift correction and
909
// hope the gyros are OK for a while. Just slowly reduce _omega_P
910
// to prevent previous bad accels from throwing us off
911
if (!_ins.healthy()) {
912
error[besti].zero();
913
} else {
914
// convert the error term to body frame
915
error[besti] = _dcm_matrix.mul_transpose(error[besti]);
916
}
917
918
if (error[besti].is_nan() || error[besti].is_inf()) {
919
// don't allow bad values
920
check_matrix();
921
_last_failure_ms = AP_HAL::millis();
922
return;
923
}
924
925
_error_rp = 0.8f * _error_rp + 0.2f * best_error;
926
927
// base the P gain on the spin rate
928
const float spin_rate = _omega.length();
929
930
// sanity check _kp value
931
if (_kp < AP_AHRS_RP_P_MIN) {
932
_kp.set(AP_AHRS_RP_P_MIN);
933
}
934
935
// we now want to calculate _omega_P and _omega_I. The
936
// _omega_P value is what drags us quickly to the
937
// accelerometer reading.
938
_omega_P = error[besti] * _P_gain(spin_rate) * _kp;
939
if (use_fast_gains()) {
940
_omega_P *= 8;
941
}
942
943
if (fly_forward && _gps.status() >= AP_GPS::GPS_OK_FIX_2D &&
944
_gps.ground_speed() < GPS_SPEED_MIN &&
945
_ins.get_accel().x >= 7 &&
946
pitch > radians(-30) && pitch < radians(30)) {
947
// assume we are in a launch acceleration, and reduce the
948
// rp gain by 50% to reduce the impact of GPS lag on
949
// takeoff attitude when using a catapult
950
_omega_P *= 0.5f;
951
}
952
953
// accumulate some integrator error
954
if (spin_rate < ToRad(SPIN_RATE_LIMIT)) {
955
_omega_I_sum += error[besti] * _ki * _ra_deltat;
956
_omega_I_sum_time += _ra_deltat;
957
}
958
959
if (_omega_I_sum_time >= 5) {
960
// limit the rate of change of omega_I to the hardware
961
// reported maximum gyro drift rate. This ensures that
962
// short term errors don't cause a buildup of omega_I
963
// beyond the physical limits of the device
964
const float change_limit = AP::ins().get_gyro_drift_rate() * _omega_I_sum_time;
965
_omega_I_sum.x = constrain_float(_omega_I_sum.x, -change_limit, change_limit);
966
_omega_I_sum.y = constrain_float(_omega_I_sum.y, -change_limit, change_limit);
967
_omega_I_sum.z = constrain_float(_omega_I_sum.z, -change_limit, change_limit);
968
_omega_I += _omega_I_sum;
969
_omega_I_sum.zero();
970
_omega_I_sum_time = 0;
971
}
972
973
// zero our accumulator ready for the next GPS step
974
memset((void *)&_ra_sum[0], 0, sizeof(_ra_sum));
975
_ra_deltat = 0;
976
_ra_sum_start = last_correction_time;
977
978
// remember the velocity for next time
979
_last_velocity = velocity;
980
}
981
982
983
// update our wind speed estimate
984
void AP_AHRS_DCM::estimate_wind(void)
985
{
986
if (!AP::ahrs().get_wind_estimation_enabled()) {
987
return;
988
}
989
const Vector3f &velocity = _last_velocity;
990
991
// this is based on the wind speed estimation code from MatrixPilot by
992
// Bill Premerlani. Adaption for ArduPilot by Jon Challinger
993
// See http://gentlenav.googlecode.com/files/WindEstimation.pdf
994
const Vector3f fuselageDirection = _dcm_matrix.colx();
995
const Vector3f fuselageDirectionDiff = fuselageDirection - _last_fuse;
996
const uint32_t now = AP_HAL::millis();
997
998
// scrap our data and start over if we're taking too long to get a direction change
999
if (now - _last_wind_time > 10000) {
1000
_last_wind_time = now;
1001
_last_fuse = fuselageDirection;
1002
_last_vel = velocity;
1003
return;
1004
}
1005
1006
float diff_length = fuselageDirectionDiff.length();
1007
if (diff_length > 0.2f) {
1008
// when turning, use the attitude response to estimate
1009
// wind speed
1010
const Vector3f velocityDiff = velocity - _last_vel;
1011
1012
// estimate airspeed it using equation 6
1013
const float V = velocityDiff.length() / diff_length;
1014
1015
const Vector3f fuselageDirectionSum = fuselageDirection + _last_fuse;
1016
const Vector3f velocitySum = velocity + _last_vel;
1017
1018
_last_fuse = fuselageDirection;
1019
_last_vel = velocity;
1020
1021
const float theta = atan2f(velocityDiff.y, velocityDiff.x) - atan2f(fuselageDirectionDiff.y, fuselageDirectionDiff.x);
1022
const float sintheta = sinf(theta);
1023
const float costheta = cosf(theta);
1024
1025
Vector3f wind{
1026
velocitySum.x - V * (costheta * fuselageDirectionSum.x - sintheta * fuselageDirectionSum.y),
1027
velocitySum.y - V * (sintheta * fuselageDirectionSum.x + costheta * fuselageDirectionSum.y),
1028
velocitySum.z - V * fuselageDirectionSum.z
1029
};
1030
wind *= 0.5f;
1031
1032
if (wind.length() < _wind.length() + 20) {
1033
_wind = _wind * 0.95f + wind * 0.05f;
1034
}
1035
1036
_last_wind_time = now;
1037
1038
return;
1039
}
1040
1041
#if AP_AIRSPEED_ENABLED
1042
if (now - _last_wind_time > 2000 && airspeed_sensor_enabled()) {
1043
// when flying straight use airspeed to get wind estimate if available
1044
const Vector3f airspeed = _dcm_matrix.colx() * AP::airspeed()->get_airspeed();
1045
const Vector3f wind = velocity - (airspeed * get_EAS2TAS());
1046
_wind = _wind * 0.92f + wind * 0.08f;
1047
}
1048
#endif
1049
}
1050
1051
#ifdef AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED
1052
void AP_AHRS_DCM::set_external_wind_estimate(float speed, float direction) {
1053
_wind.x = -cosf(radians(direction)) * speed;
1054
_wind.y = -sinf(radians(direction)) * speed;
1055
_wind.z = 0;
1056
}
1057
#endif
1058
1059
// return our current position estimate using
1060
// dead-reckoning or GPS
1061
bool AP_AHRS_DCM::get_location(Location &loc) const
1062
{
1063
loc.lat = _last_lat;
1064
loc.lng = _last_lng;
1065
const auto &baro = AP::baro();
1066
const auto &gps = AP::gps();
1067
if (_gps_use == GPSUse::EnableWithHeight &&
1068
gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
1069
loc.alt = gps.location().alt;
1070
} else {
1071
loc.alt = baro.get_altitude() * 100 + AP::ahrs().get_home().alt;
1072
}
1073
loc.relative_alt = 0;
1074
loc.terrain_alt = 0;
1075
loc.offset(_position_offset_north, _position_offset_east);
1076
if (_have_position) {
1077
const uint32_t now = AP_HAL::millis();
1078
float dt = 0;
1079
gps.get_lag(dt);
1080
dt += constrain_float((now - _last_pos_ms) * 0.001, 0, 0.5);
1081
Vector2f dpos = _last_velocity.xy() * dt;
1082
loc.offset(dpos.x, dpos.y);
1083
}
1084
return _have_position;
1085
}
1086
1087
bool AP_AHRS_DCM::airspeed_EAS(float &airspeed_ret) const
1088
{
1089
#if AP_AIRSPEED_ENABLED
1090
const auto *airspeed = AP::airspeed();
1091
if (airspeed != nullptr) {
1092
return airspeed_EAS(airspeed->get_primary(), airspeed_ret);
1093
}
1094
#endif
1095
// airspeed_estimate will also make this nullptr check and act
1096
// appropriately when we call it with a dummy sensor ID.
1097
return airspeed_EAS(0, airspeed_ret);
1098
}
1099
1100
// return an (equivalent) airspeed estimate:
1101
// - from a real sensor if available
1102
// - otherwise from a GPS-derived wind-triangle estimate (if GPS available)
1103
// - otherwise from a cached wind-triangle estimate value (but returning false)
1104
bool AP_AHRS_DCM::airspeed_EAS(uint8_t airspeed_index, float &airspeed_ret) const
1105
{
1106
// airspeed_ret: will always be filled-in by get_unconstrained_airspeed_EAS which fills in airspeed_ret in this order:
1107
// airspeed as filled-in by an enabled airspeed sensor
1108
// if no airspeed sensor: airspeed estimated using the GPS speed & wind_speed_estimation
1109
// Or if none of the above, fills-in using the previous airspeed estimate
1110
// Return false: if we are using the previous airspeed estimate
1111
if (!get_unconstrained_airspeed_EAS(airspeed_index, airspeed_ret)) {
1112
return false;
1113
}
1114
1115
const float _wind_max = AP::ahrs().get_max_wind();
1116
if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
1117
// constrain the airspeed by the ground speed
1118
// and AHRS_WIND_MAX
1119
const float gnd_speed = AP::gps().ground_speed();
1120
float true_airspeed = airspeed_ret * get_EAS2TAS();
1121
true_airspeed = constrain_float(true_airspeed,
1122
gnd_speed - _wind_max,
1123
gnd_speed + _wind_max);
1124
airspeed_ret = true_airspeed / get_EAS2TAS();
1125
}
1126
1127
return true;
1128
}
1129
1130
// airspeed_ret: will always be filled-in by get_unconstrained_airspeed_EAS which fills in airspeed_ret in this order:
1131
// airspeed as filled-in by an enabled airspeed sensor
1132
// if no airspeed sensor: airspeed estimated using the GPS speed & wind_speed_estimation
1133
// Or if none of the above, fills-in using the previous airspeed estimate
1134
// Return false: if we are using the previous airspeed estimate
1135
bool AP_AHRS_DCM::get_unconstrained_airspeed_EAS(uint8_t airspeed_index, float &airspeed_ret) const
1136
{
1137
#if AP_AIRSPEED_ENABLED
1138
if (airspeed_sensor_enabled(airspeed_index)) {
1139
airspeed_ret = AP::airspeed()->get_airspeed(airspeed_index);
1140
return true;
1141
}
1142
#endif
1143
1144
if (AP::ahrs().get_wind_estimation_enabled() && have_gps()) {
1145
// estimated via GPS speed and wind
1146
airspeed_ret = _last_airspeed_TAS * get_TAS2EAS();
1147
return true;
1148
}
1149
1150
// Else give the last estimate, but return false.
1151
// This is used by the dead-reckoning code
1152
airspeed_ret = _last_airspeed_TAS * get_TAS2EAS();
1153
return false;
1154
}
1155
1156
/*
1157
check if the AHRS subsystem is healthy
1158
*/
1159
bool AP_AHRS_DCM::healthy(void) const
1160
{
1161
// consider ourselves healthy if there have been no failures for 5 seconds
1162
return (_last_failure_ms == 0 || AP_HAL::millis() - _last_failure_ms > 5000);
1163
}
1164
1165
/*
1166
return NED velocity if we have GPS lock
1167
*/
1168
bool AP_AHRS_DCM::get_velocity_NED(Vector3f &vec) const
1169
{
1170
const AP_GPS &_gps = AP::gps();
1171
if (_gps.status() < AP_GPS::GPS_OK_FIX_3D) {
1172
return false;
1173
}
1174
vec = _gps.velocity();
1175
return true;
1176
}
1177
1178
// return a ground speed estimate in m/s
1179
Vector2f AP_AHRS_DCM::groundspeed_vector(void)
1180
{
1181
// Generate estimate of ground speed vector using air data system
1182
Vector2f gndVelADS;
1183
Vector2f gndVelGPS;
1184
float airspeed = 0;
1185
const bool gotAirspeed = airspeed_TAS(airspeed);
1186
const bool gotGPS = (AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D);
1187
if (gotAirspeed) {
1188
const Vector2f airspeed_vector{_cos_yaw * airspeed, _sin_yaw * airspeed};
1189
Vector3f wind;
1190
UNUSED_RESULT(wind_estimate(wind));
1191
gndVelADS = airspeed_vector + wind.xy();
1192
}
1193
1194
// Generate estimate of ground speed vector using GPS
1195
if (gotGPS) {
1196
const float cog = radians(AP::gps().ground_course());
1197
gndVelGPS = Vector2f(cosf(cog), sinf(cog)) * AP::gps().ground_speed();
1198
}
1199
// If both ADS and GPS data is available, apply a complementary filter
1200
if (gotAirspeed && gotGPS) {
1201
// The LPF is applied to the GPS and the HPF is applied to the air data estimate
1202
// before the two are summed
1203
//Define filter coefficients
1204
// alpha and beta must sum to one
1205
// beta = dt/Tau, where
1206
// dt = filter time step (0.1 sec if called by nav loop)
1207
// Tau = cross-over time constant (nominal 2 seconds)
1208
// More lag on GPS requires Tau to be bigger, less lag allows it to be smaller
1209
// To-Do - set Tau as a function of GPS lag.
1210
const float alpha = 1.0f - beta;
1211
// Run LP filters
1212
_lp = gndVelGPS * beta + _lp * alpha;
1213
// Run HP filters
1214
_hp = (gndVelADS - _lastGndVelADS) + _hp * alpha;
1215
// Save the current ADS ground vector for the next time step
1216
_lastGndVelADS = gndVelADS;
1217
// Sum the HP and LP filter outputs
1218
return _hp + _lp;
1219
}
1220
// Only ADS data is available return ADS estimate
1221
if (gotAirspeed && !gotGPS) {
1222
return gndVelADS;
1223
}
1224
// Only GPS data is available so return GPS estimate
1225
if (!gotAirspeed && gotGPS) {
1226
return gndVelGPS;
1227
}
1228
1229
if (airspeed > 0) {
1230
// we have a rough airspeed, and we have a yaw. For
1231
// dead-reckoning purposes we can create a estimated
1232
// groundspeed vector
1233
Vector2f ret{_cos_yaw, _sin_yaw};
1234
ret *= airspeed;
1235
// adjust for estimated wind
1236
Vector3f wind;
1237
UNUSED_RESULT(wind_estimate(wind));
1238
ret.x += wind.x;
1239
ret.y += wind.y;
1240
return ret;
1241
}
1242
1243
return Vector2f(0.0f, 0.0f);
1244
}
1245
1246
// Get a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.
1247
// This is different to the vertical velocity from the EKF which is not always consistent with the vertical position due to the various errors that are being corrected for.
1248
bool AP_AHRS_DCM::get_vert_pos_rate_D(float &velocity) const
1249
{
1250
Vector3f velned;
1251
if (get_velocity_NED(velned)) {
1252
velocity = velned.z;
1253
return true;
1254
} else if (AP::baro().healthy()) {
1255
velocity = -AP::baro().get_climb_rate();
1256
return true;
1257
}
1258
return false;
1259
}
1260
1261
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
1262
// requires_position should be true if horizontal position configuration should be checked (not used)
1263
bool AP_AHRS_DCM::pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const
1264
{
1265
if (!healthy()) {
1266
hal.util->snprintf(failure_msg, failure_msg_len, "Not healthy");
1267
return false;
1268
}
1269
return true;
1270
}
1271
1272
/*
1273
relative-origin functions for fallback in AP_InertialNav
1274
*/
1275
bool AP_AHRS_DCM::get_origin(Location &ret) const
1276
{
1277
ret = last_origin;
1278
if (ret.is_zero()) {
1279
// use home if we never have had an origin
1280
ret = AP::ahrs().get_home();
1281
}
1282
return !ret.is_zero();
1283
}
1284
1285
bool AP_AHRS_DCM::get_relative_position_NED_origin(Vector3f &posNED) const
1286
{
1287
Location origin;
1288
if (!AP_AHRS_DCM::get_origin(origin)) {
1289
return false;
1290
}
1291
Location loc;
1292
if (!AP_AHRS_DCM::get_location(loc)) {
1293
return false;
1294
}
1295
posNED = origin.get_distance_NED(loc);
1296
return true;
1297
}
1298
1299
bool AP_AHRS_DCM::get_relative_position_NE_origin(Vector2f &posNE) const
1300
{
1301
Vector3f posNED;
1302
if (!AP_AHRS_DCM::get_relative_position_NED_origin(posNED)) {
1303
return false;
1304
}
1305
posNE = posNED.xy();
1306
return true;
1307
}
1308
1309
bool AP_AHRS_DCM::get_relative_position_D_origin(float &posD) const
1310
{
1311
Vector3f posNED;
1312
if (!AP_AHRS_DCM::get_relative_position_NED_origin(posNED)) {
1313
return false;
1314
}
1315
posD = posNED.z;
1316
return true;
1317
}
1318
1319
void AP_AHRS_DCM::send_ekf_status_report(GCS_MAVLINK &link) const
1320
{
1321
}
1322
1323
// return true if DCM has a yaw source available
1324
bool AP_AHRS_DCM::yaw_source_available(void) const
1325
{
1326
return AP::compass().use_for_yaw();
1327
}
1328
1329
void AP_AHRS_DCM::get_control_limits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
1330
{
1331
// lower gains in VTOL controllers when flying on DCM
1332
ekfGndSpdLimit = 50.0;
1333
ekfNavVelGainScaler = 0.5;
1334
}
1335
1336
#endif // AP_AHRS_DCM_ENABLED
1337
1338