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