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.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
/*
17
* NavEKF based AHRS (Attitude Heading Reference System) interface for
18
* ArduPilot
19
*
20
*/
21
22
#include "AP_AHRS_config.h"
23
24
#if AP_AHRS_ENABLED
25
26
#include <AP_HAL/AP_HAL.h>
27
#include "AP_AHRS.h"
28
#include "AP_AHRS_View.h"
29
#include <AP_BoardConfig/AP_BoardConfig.h>
30
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
31
#include <AP_Module/AP_Module.h>
32
#include <AP_GPS/AP_GPS.h>
33
#include <AP_Baro/AP_Baro.h>
34
#include <AP_Compass/AP_Compass.h>
35
#include <AP_InternalError/AP_InternalError.h>
36
#include <AP_Logger/AP_Logger.h>
37
#include <AP_Notify/AP_Notify.h>
38
#include <AP_Vehicle/AP_Vehicle_Type.h>
39
#include <GCS_MAVLink/GCS.h>
40
#include <AP_InertialSensor/AP_InertialSensor.h>
41
#include <AP_CustomRotations/AP_CustomRotations.h>
42
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
43
#include <SITL/SITL.h>
44
#endif
45
#include <AP_NavEKF3/AP_NavEKF3_feature.h>
46
47
#define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10)
48
#define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20)
49
50
#ifndef HAL_AHRS_EKF_TYPE_DEFAULT
51
#define HAL_AHRS_EKF_TYPE_DEFAULT 3
52
#endif
53
54
// table of user settable parameters
55
const AP_Param::GroupInfo AP_AHRS::var_info[] = {
56
// index 0 and 1 are for old parameters that are no longer not used
57
58
// @Param: GPS_GAIN
59
// @DisplayName: AHRS GPS gain
60
// @Description: This controls how much to use the GPS to correct the attitude. This should never be set to zero for a plane as it would result in the plane losing control in turns. For a plane please use the default value of 1.0.
61
// @Range: 0.0 1.0
62
// @Increment: 0.01
63
// @User: Advanced
64
AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS, gps_gain, 1.0f),
65
66
// @Param: GPS_USE
67
// @DisplayName: AHRS use GPS for DCM navigation and position-down
68
// @Description: This controls whether to use dead-reckoning or GPS based navigation. If set to 0 then the GPS won't be used for navigation, and only dead reckoning will be used. A value of zero should never be used for normal flight. Currently this affects only the DCM-based AHRS: the EKF uses GPS according to its own parameters. A value of 2 means to use GPS for height as well as position - both in DCM estimation and when determining altitude-above-home.
69
// @Values: 0:Disabled,1:Use GPS for DCM position,2:Use GPS for DCM position and height
70
// @User: Advanced
71
AP_GROUPINFO("GPS_USE", 3, AP_AHRS, _gps_use, float(GPSUse::Enable)),
72
73
// @Param: YAW_P
74
// @DisplayName: Yaw P
75
// @Description: This controls the weight the compass or GPS has on the heading. A higher value means the heading will track the yaw source (GPS or compass) more rapidly.
76
// @Range: 0.1 0.4
77
// @Increment: 0.01
78
// @User: Advanced
79
AP_GROUPINFO("YAW_P", 4, AP_AHRS, _kp_yaw, 0.2f),
80
81
// @Param: RP_P
82
// @DisplayName: AHRS RP_P
83
// @Description: This controls how fast the accelerometers correct the attitude
84
// @Range: 0.1 0.4
85
// @Increment: 0.01
86
// @User: Advanced
87
AP_GROUPINFO("RP_P", 5, AP_AHRS, _kp, 0.2f),
88
89
// @Param: WIND_MAX
90
// @DisplayName: Maximum wind
91
// @Description: This sets the maximum allowable difference between ground speed and airspeed. A value of zero means to use the airspeed as is. This allows the plane to cope with a failing airspeed sensor by clipping it to groundspeed plus/minus this limit. See ARSPD_OPTIONS and ARSPD_WIND_MAX to disable airspeed sensors.
92
// @Range: 0 127
93
// @Units: m/s
94
// @Increment: 1
95
// @User: Advanced
96
AP_GROUPINFO("WIND_MAX", 6, AP_AHRS, _wind_max, 0.0f),
97
98
// NOTE: 7 was BARO_USE
99
100
// @Param: TRIM_X
101
// @DisplayName: AHRS Trim Roll
102
// @Description: Compensates for the roll angle difference between the control board and the frame. Positive values make the vehicle roll right.
103
// @Units: rad
104
// @Range: -0.1745 +0.1745
105
// @Increment: 0.01
106
// @User: Standard
107
108
// @Param: TRIM_Y
109
// @DisplayName: AHRS Trim Pitch
110
// @Description: Compensates for the pitch angle difference between the control board and the frame. Positive values make the vehicle pitch up/back.
111
// @Units: rad
112
// @Range: -0.1745 +0.1745
113
// @Increment: 0.01
114
// @User: Standard
115
116
// @Param: TRIM_Z
117
// @DisplayName: AHRS Trim Yaw
118
// @Description: Not Used
119
// @Units: rad
120
// @Range: -0.1745 +0.1745
121
// @Increment: 0.01
122
// @User: Advanced
123
AP_GROUPINFO("TRIM", 8, AP_AHRS, _trim, 0),
124
125
// @Param: ORIENTATION
126
// @DisplayName: Board Orientation
127
// @Description: Overall board orientation relative to the standard orientation for the board type. This rotates the IMU and compass readings to allow the board to be oriented in your vehicle at any 90 or 45 degree angle. The label for each option is specified in the order of rotations for that orientation. This option takes affect on next boot. After changing you will need to re-level your vehicle. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the AHRS_CUSTOM_ROLL/PIT/YAW angles for AHRS orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_ROT1_ROLL/PIT/YAW or CUST_ROT2_ROLL/PIT/YAW angles.
128
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom 4.1 and older,101:Custom 1,102:Custom 2
129
// @User: Advanced
130
AP_GROUPINFO("ORIENTATION", 9, AP_AHRS, _board_orientation, 0),
131
132
// @Param: COMP_BETA
133
// @DisplayName: AHRS Velocity Complementary Filter Beta Coefficient
134
// @Description: This controls the time constant for the cross-over frequency used to fuse AHRS (airspeed and heading) and GPS data to estimate ground velocity. Time constant is 0.1/beta. A larger time constant will use GPS data less and a small time constant will use air data less.
135
// @Range: 0.001 0.5
136
// @Increment: 0.01
137
// @User: Advanced
138
AP_GROUPINFO("COMP_BETA", 10, AP_AHRS, beta, 0.1f),
139
140
// @Param: GPS_MINSATS
141
// @DisplayName: AHRS GPS Minimum satellites
142
// @Description: Minimum number of satellites visible to use GPS for velocity based corrections attitude correction. This defaults to 6, which is about the point at which the velocity numbers from a GPS become too unreliable for accurate correction of the accelerometers.
143
// @Range: 0 10
144
// @Increment: 1
145
// @User: Advanced
146
AP_GROUPINFO("GPS_MINSATS", 11, AP_AHRS, _gps_minsats, 6),
147
148
// NOTE: index 12 was for GPS_DELAY, but now removed, fixed delay
149
// of 1 was found to be the best choice
150
151
// 13 was the old EKF_USE
152
153
// @Param: EKF_TYPE
154
// @DisplayName: Use NavEKF Kalman filter for attitude and position estimation
155
// @Description: This controls which NavEKF Kalman filter version is used for attitude and position estimation
156
// @Values: 0:Disabled,2:Enable EKF2,3:Enable EKF3,11:ExternalAHRS
157
// @User: Advanced
158
AP_GROUPINFO("EKF_TYPE", 14, AP_AHRS, _ekf_type, HAL_AHRS_EKF_TYPE_DEFAULT),
159
160
// @Param: CUSTOM_ROLL
161
// @DisplayName: Board orientation roll offset
162
// @Description: Autopilot mounting position roll offset. Positive values = roll right, negative values = roll left. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
163
// @Range: -180 180
164
// @Units: deg
165
// @Increment: 1
166
// @User: Advanced
167
168
// index 15
169
170
// @Param: CUSTOM_PIT
171
// @DisplayName: Board orientation pitch offset
172
// @Description: Autopilot mounting position pitch offset. Positive values = pitch up, negative values = pitch down. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
173
// @Range: -180 180
174
// @Units: deg
175
// @Increment: 1
176
// @User: Advanced
177
178
// index 16
179
180
// @Param: CUSTOM_YAW
181
// @DisplayName: Board orientation yaw offset
182
// @Description: Autopilot mounting position yaw offset. Positive values = yaw right, negative values = yaw left. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
183
// @Range: -180 180
184
// @Units: deg
185
// @Increment: 1
186
// @User: Advanced
187
188
// index 17
189
190
// @Param: OPTIONS
191
// @DisplayName: Optional AHRS behaviour
192
// @Description: This controls optional AHRS behaviour. Setting DisableDCMFallbackFW will change the AHRS behaviour for fixed wing aircraft in fly-forward flight to not fall back to DCM when the EKF stops navigating. Setting DisableDCMFallbackVTOL will change the AHRS behaviour for fixed wing aircraft in non fly-forward (VTOL) flight to not fall back to DCM when the EKF stops navigating. Setting DontDisableAirspeedUsingEKF disables the EKF based innovation check for airspeed consistency
193
// @Bitmask: 0:DisableDCMFallbackFW, 1:DisableDCMFallbackVTOL, 2:DontDisableAirspeedUsingEKF
194
// @User: Advanced
195
AP_GROUPINFO("OPTIONS", 18, AP_AHRS, _options, 0),
196
197
AP_GROUPEND
198
};
199
200
extern const AP_HAL::HAL& hal;
201
202
// constructor
203
AP_AHRS::AP_AHRS(uint8_t flags) :
204
_ekf_flags(flags)
205
{
206
_singleton = this;
207
208
// load default values from var_info table
209
AP_Param::setup_object_defaults(this, var_info);
210
211
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduSub)
212
// Copter and Sub force the use of EKF
213
_ekf_flags |= AP_AHRS::FLAG_ALWAYS_USE_EKF;
214
#endif
215
state.dcm_matrix.identity();
216
217
// initialise the controller-to-autopilot-body trim state:
218
_last_trim = _trim.get();
219
_rotation_autopilot_body_to_vehicle_body.from_euler(_last_trim.x, _last_trim.y, _last_trim.z);
220
_rotation_vehicle_body_to_autopilot_body = _rotation_autopilot_body_to_vehicle_body.transposed();
221
}
222
223
// init sets up INS board orientation
224
void AP_AHRS::init()
225
{
226
// EKF1 is no longer supported - handle case where it is selected
227
if (_ekf_type.get() == 1) {
228
AP_BoardConfig::config_error("EKF1 not available");
229
}
230
#if !HAL_NAVEKF2_AVAILABLE && HAL_NAVEKF3_AVAILABLE
231
if (_ekf_type.get() == 2) {
232
_ekf_type.set(EKFType::THREE);
233
EKF3.set_enable(true);
234
}
235
#elif !HAL_NAVEKF3_AVAILABLE && HAL_NAVEKF2_AVAILABLE
236
if (_ekf_type.get() == 3) {
237
_ekf_type.set(EKFType::TWO);
238
EKF2.set_enable(true);
239
}
240
#endif
241
242
#if HAL_NAVEKF2_AVAILABLE && HAL_NAVEKF3_AVAILABLE
243
// a special case to catch users who had AHRS_EKF_TYPE=2 saved and
244
// updated to a version where EK2_ENABLE=0
245
if (_ekf_type.get() == 2 && !EKF2.get_enable() && EKF3.get_enable()) {
246
_ekf_type.set(EKFType::THREE);
247
}
248
#endif
249
250
last_active_ekf_type = (EKFType)_ekf_type.get();
251
252
// init backends
253
#if AP_AHRS_DCM_ENABLED
254
dcm.init();
255
#endif
256
#if AP_AHRS_EXTERNAL_ENABLED
257
external.init();
258
#endif
259
260
#if AP_CUSTOMROTATIONS_ENABLED
261
// convert to new custom rotation
262
// PARAMETER_CONVERSION - Added: Nov-2021
263
if (_board_orientation == ROTATION_CUSTOM_OLD) {
264
_board_orientation.set_and_save(ROTATION_CUSTOM_1);
265
AP_Param::ConversionInfo info;
266
if (AP_Param::find_top_level_key_by_pointer(this, info.old_key)) {
267
info.type = AP_PARAM_FLOAT;
268
float rpy[3] = {};
269
AP_Float rpy_param;
270
for (info.old_group_element=15; info.old_group_element<=17; info.old_group_element++) {
271
if (AP_Param::find_old_parameter(&info, &rpy_param)) {
272
rpy[info.old_group_element-15] = rpy_param.get();
273
}
274
}
275
AP::custom_rotations().convert(ROTATION_CUSTOM_1, rpy[0], rpy[1], rpy[2]);
276
}
277
}
278
#endif // AP_CUSTOMROTATIONS_ENABLED
279
}
280
281
// updates matrices responsible for rotating vectors from vehicle body
282
// frame to autopilot body frame from _trim variables
283
void AP_AHRS::update_trim_rotation_matrices()
284
{
285
if (_last_trim == _trim.get()) {
286
// nothing to do
287
return;
288
}
289
290
_last_trim = _trim.get();
291
_rotation_autopilot_body_to_vehicle_body.from_euler(_last_trim.x, _last_trim.y, _last_trim.z);
292
_rotation_vehicle_body_to_autopilot_body = _rotation_autopilot_body_to_vehicle_body.transposed();
293
}
294
295
// return a Quaternion representing our current attitude in NED frame
296
void AP_AHRS::get_quat_body_to_ned(Quaternion &quat) const
297
{
298
quat.from_rotation_matrix(get_rotation_body_to_ned());
299
}
300
301
// convert a vector from body to earth frame
302
Vector3f AP_AHRS::body_to_earth(const Vector3f &v) const
303
{
304
return get_rotation_body_to_ned() * v;
305
}
306
307
// convert a vector from earth to body frame
308
Vector3f AP_AHRS::earth_to_body(const Vector3f &v) const
309
{
310
return get_rotation_body_to_ned().mul_transpose(v);
311
}
312
313
314
// reset the current gyro drift estimate
315
// should be called if gyro offsets are recalculated
316
void AP_AHRS::reset_gyro_drift(void)
317
{
318
// support locked access functions to AHRS data
319
WITH_SEMAPHORE(_rsem);
320
321
// update DCM
322
#if AP_AHRS_DCM_ENABLED
323
dcm.reset_gyro_drift();
324
#endif
325
#if AP_AHRS_EXTERNAL_ENABLED
326
external.reset_gyro_drift();
327
#endif
328
329
// reset the EKF gyro bias states
330
#if HAL_NAVEKF2_AVAILABLE
331
EKF2.resetGyroBias();
332
#endif
333
#if HAL_NAVEKF3_AVAILABLE
334
EKF3.resetGyroBias();
335
#endif
336
}
337
338
/*
339
update state structure after each update()
340
*/
341
void AP_AHRS::update_state(void)
342
{
343
state.primary_IMU = _get_primary_IMU_index();
344
state.primary_gyro = _get_primary_gyro_index();
345
state.primary_accel = _get_primary_accel_index();
346
state.primary_core = _get_primary_core_index();
347
state.wind_estimate_ok = _wind_estimate(state.wind_estimate);
348
state.EAS2TAS = AP_AHRS_Backend::get_EAS2TAS();
349
state.airspeed_ok = _airspeed_EAS(state.airspeed, state.airspeed_estimate_type);
350
state.airspeed_true_ok = _airspeed_TAS(state.airspeed_true);
351
state.airspeed_vec_ok = _airspeed_TAS(state.airspeed_vec);
352
state.quat_ok = _get_quaternion(state.quat);
353
state.secondary_attitude_ok = _get_secondary_attitude(state.secondary_attitude);
354
state.secondary_quat_ok = _get_secondary_quaternion(state.secondary_quat);
355
state.location_ok = _get_location(state.location);
356
state.secondary_pos_ok = _get_secondary_position(state.secondary_pos);
357
state.ground_speed_vec = _groundspeed_vector();
358
state.ground_speed = _groundspeed();
359
_getCorrectedDeltaVelocityNED(state.corrected_dv, state.corrected_dv_dt);
360
state.origin_ok = _get_origin(state.origin);
361
state.velocity_NED_ok = _get_velocity_NED(state.velocity_NED);
362
}
363
364
void AP_AHRS::update(bool skip_ins_update)
365
{
366
// periodically checks to see if we should update the AHRS
367
// orientation (e.g. based on the AHRS_ORIENTATION parameter)
368
// allow for runtime change of orientation
369
// this makes initial config easier
370
update_orientation();
371
372
if (!skip_ins_update) {
373
// tell the IMU to grab some data
374
AP::ins().update();
375
}
376
377
// support locked access functions to AHRS data
378
WITH_SEMAPHORE(_rsem);
379
380
// see if we have to restore home after a watchdog reset:
381
if (!_checked_watchdog_home) {
382
load_watchdog_home();
383
_checked_watchdog_home = true;
384
}
385
386
// drop back to normal priority if we were boosted by the INS
387
// calling delay_microseconds_boost()
388
hal.scheduler->boost_end();
389
390
// update autopilot-body-to-vehicle-body from _trim parameters:
391
update_trim_rotation_matrices();
392
393
#if AP_AHRS_DCM_ENABLED
394
update_DCM();
395
#endif
396
397
// update takeoff/touchdown flags
398
update_flags();
399
400
#if AP_AHRS_SIM_ENABLED
401
update_SITL();
402
#endif
403
404
#if AP_AHRS_EXTERNAL_ENABLED
405
update_external();
406
#endif
407
408
if (_ekf_type == 2) {
409
// if EK2 is primary then run EKF2 first to give it CPU
410
// priority
411
#if HAL_NAVEKF2_AVAILABLE
412
update_EKF2();
413
#endif
414
#if HAL_NAVEKF3_AVAILABLE
415
update_EKF3();
416
#endif
417
} else {
418
// otherwise run EKF3 first
419
#if HAL_NAVEKF3_AVAILABLE
420
update_EKF3();
421
#endif
422
#if HAL_NAVEKF2_AVAILABLE
423
update_EKF2();
424
#endif
425
}
426
427
#if AP_MODULE_SUPPORTED
428
// call AHRS_update hook if any
429
AP_Module::call_hook_AHRS_update(*this);
430
#endif
431
432
// push gyros if optical flow present
433
if (hal.opticalflow) {
434
const Vector3f &exported_gyro_bias = get_gyro_drift();
435
hal.opticalflow->push_gyro_bias(exported_gyro_bias.x, exported_gyro_bias.y);
436
}
437
438
if (_view != nullptr) {
439
// update optional alternative attitude view
440
_view->update();
441
}
442
443
// update AOA and SSA
444
update_AOA_SSA();
445
446
#if HAL_GCS_ENABLED
447
state.active_EKF = _active_EKF_type();
448
if (state.active_EKF != last_active_ekf_type) {
449
last_active_ekf_type = state.active_EKF;
450
const char *shortname = "???";
451
switch ((EKFType)state.active_EKF) {
452
#if AP_AHRS_DCM_ENABLED
453
case EKFType::DCM:
454
shortname = "DCM";
455
break;
456
#endif
457
#if AP_AHRS_SIM_ENABLED
458
case EKFType::SIM:
459
shortname = "SIM";
460
break;
461
#endif
462
#if AP_AHRS_EXTERNAL_ENABLED
463
case EKFType::EXTERNAL:
464
shortname = "External";
465
break;
466
#endif
467
#if HAL_NAVEKF3_AVAILABLE
468
case EKFType::THREE:
469
shortname = "EKF3";
470
break;
471
#endif
472
#if HAL_NAVEKF2_AVAILABLE
473
case EKFType::TWO:
474
shortname = "EKF2";
475
break;
476
#endif
477
}
478
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AHRS: %s active", shortname);
479
}
480
#endif // HAL_GCS_ENABLED
481
482
// update published state
483
update_state();
484
485
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
486
/*
487
add timing jitter to simulate slow EKF response
488
*/
489
const auto *sitl = AP::sitl();
490
if (sitl->loop_time_jitter_us > 0) {
491
hal.scheduler->delay_microseconds(random() % sitl->loop_time_jitter_us);
492
}
493
#endif
494
}
495
496
/*
497
* copy results from a backend over AP_AHRS canonical results.
498
* This updates member variables like roll and pitch, as well as
499
* updating derived values like sin_roll and sin_pitch.
500
*/
501
void AP_AHRS::copy_estimates_from_backend_estimates(const AP_AHRS_Backend::Estimates &results)
502
{
503
roll = results.roll_rad;
504
pitch = results.pitch_rad;
505
yaw = results.yaw_rad;
506
507
state.dcm_matrix = results.dcm_matrix;
508
509
state.gyro_estimate = results.gyro_estimate;
510
state.gyro_drift = results.gyro_drift;
511
512
state.accel_ef = results.accel_ef;
513
state.accel_bias = results.accel_bias;
514
515
update_cd_values();
516
update_trig();
517
}
518
519
#if AP_AHRS_DCM_ENABLED
520
void AP_AHRS::update_DCM()
521
{
522
dcm.update();
523
dcm.get_results(dcm_estimates);
524
525
// we always update the vehicle's canonical roll/pitch/yaw from
526
// DCM. In normal operation this will usually be over-written by
527
// an EKF or external AHRS. This is long-held behaviour, but this
528
// really shouldn't be doing this.
529
530
// if (active_EKF_type() == EKFType::DCM) {
531
copy_estimates_from_backend_estimates(dcm_estimates);
532
// }
533
}
534
#endif
535
536
#if AP_AHRS_SIM_ENABLED
537
void AP_AHRS::update_SITL(void)
538
{
539
sim.update();
540
sim.get_results(sim_estimates);
541
542
if (_active_EKF_type() == EKFType::SIM) {
543
copy_estimates_from_backend_estimates(sim_estimates);
544
}
545
}
546
#endif
547
548
void AP_AHRS::update_notify_from_filter_status(const nav_filter_status &status)
549
{
550
AP_Notify::flags.gps_fusion = status.flags.using_gps; // Drives AP_Notify flag for usable GPS.
551
AP_Notify::flags.gps_glitching = status.flags.gps_glitching;
552
AP_Notify::flags.have_pos_abs = status.flags.horiz_pos_abs;
553
}
554
555
#if HAL_NAVEKF2_AVAILABLE
556
void AP_AHRS::update_EKF2(void)
557
{
558
if (!_ekf2_started) {
559
// wait 1 second for DCM to output a valid tilt error estimate
560
if (start_time_ms == 0) {
561
start_time_ms = AP_HAL::millis();
562
}
563
#if HAL_LOGGING_ENABLED
564
// if we're doing Replay logging then don't allow any data
565
// into the EKF yet. Don't allow it to block us for long.
566
if (!hal.util->was_watchdog_reset()) {
567
if (AP_HAL::millis() - start_time_ms < 5000) {
568
if (!AP::logger().allow_start_ekf()) {
569
return;
570
}
571
}
572
}
573
#endif
574
575
if (AP_HAL::millis() - start_time_ms > startup_delay_ms) {
576
_ekf2_started = EKF2.InitialiseFilter();
577
}
578
}
579
if (_ekf2_started) {
580
EKF2.UpdateFilter();
581
if (_active_EKF_type() == EKFType::TWO) {
582
Vector3f eulers;
583
EKF2.getRotationBodyToNED(state.dcm_matrix);
584
EKF2.getEulerAngles(eulers);
585
roll = eulers.x;
586
pitch = eulers.y;
587
yaw = eulers.z;
588
589
update_cd_values();
590
update_trig();
591
592
// Use the primary EKF to select the primary gyro
593
const AP_InertialSensor &_ins = AP::ins();
594
const int8_t primary_imu = EKF2.getPrimaryCoreIMUIndex();
595
const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_first_usable_gyro();
596
const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_first_usable_accel();
597
598
// get gyro bias for primary EKF and change sign to give gyro drift
599
// Note sign convention used by EKF is bias = measurement - truth
600
Vector3f drift;
601
EKF2.getGyroBias(drift);
602
state.gyro_drift = -drift;
603
604
// use the same IMU as the primary EKF and correct for gyro drift
605
state.gyro_estimate = _ins.get_gyro(primary_gyro) + state.gyro_drift;
606
607
// get z accel bias estimate from active EKF (this is usually for the primary IMU)
608
float &abias = state.accel_bias.z;
609
EKF2.getAccelZBias(abias);
610
611
// This EKF is currently using primary_imu, and a bias applies to only that IMU
612
Vector3f accel = _ins.get_accel(primary_accel);
613
accel.z -= abias;
614
state.accel_ef = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel;
615
616
nav_filter_status filt_state;
617
EKF2.getFilterStatus(filt_state);
618
update_notify_from_filter_status(filt_state);
619
}
620
621
/*
622
if we now have an origin then set in all backends
623
*/
624
if (!done_common_origin) {
625
Location new_origin;
626
if (EKF2.getOriginLLH(new_origin)) {
627
done_common_origin = true;
628
#if HAL_NAVEKF3_AVAILABLE
629
EKF3.setOriginLLH(new_origin);
630
#endif
631
#if AP_AHRS_EXTERNAL_ENABLED
632
external.set_origin(new_origin);
633
#endif
634
}
635
}
636
}
637
}
638
#endif
639
640
#if HAL_NAVEKF3_AVAILABLE
641
void AP_AHRS::update_EKF3(void)
642
{
643
if (!_ekf3_started) {
644
// wait 1 second for DCM to output a valid tilt error estimate
645
if (start_time_ms == 0) {
646
start_time_ms = AP_HAL::millis();
647
}
648
#if HAL_LOGGING_ENABLED
649
// if we're doing Replay logging then don't allow any data
650
// into the EKF yet. Don't allow it to block us for long.
651
if (!hal.util->was_watchdog_reset()) {
652
if (AP_HAL::millis() - start_time_ms < 5000) {
653
if (!AP::logger().allow_start_ekf()) {
654
return;
655
}
656
}
657
}
658
#endif
659
if (AP_HAL::millis() - start_time_ms > startup_delay_ms) {
660
_ekf3_started = EKF3.InitialiseFilter();
661
}
662
}
663
if (_ekf3_started) {
664
EKF3.UpdateFilter();
665
if (_active_EKF_type() == EKFType::THREE) {
666
Vector3f eulers;
667
EKF3.getRotationBodyToNED(state.dcm_matrix);
668
EKF3.getEulerAngles(eulers);
669
roll = eulers.x;
670
pitch = eulers.y;
671
yaw = eulers.z;
672
673
update_cd_values();
674
update_trig();
675
676
const AP_InertialSensor &_ins = AP::ins();
677
678
// Use the primary EKF to select the primary gyro
679
const int8_t primary_imu = EKF3.getPrimaryCoreIMUIndex();
680
const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_first_usable_gyro();
681
const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_first_usable_accel();
682
683
// get gyro bias for primary EKF and change sign to give gyro drift
684
// Note sign convention used by EKF is bias = measurement - truth
685
Vector3f drift;
686
EKF3.getGyroBias(-1, drift);
687
state.gyro_drift = -drift;
688
689
// use the same IMU as the primary EKF and correct for gyro drift
690
state.gyro_estimate = _ins.get_gyro(primary_gyro) + state.gyro_drift;
691
692
// get 3-axis accel bias estimates for active EKF (this is usually for the primary IMU)
693
Vector3f &abias = state.accel_bias;
694
EKF3.getAccelBias(-1,abias);
695
696
// use the primary IMU for accel earth frame
697
Vector3f accel = _ins.get_accel(primary_accel);
698
accel -= abias;
699
state.accel_ef = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel;
700
701
nav_filter_status filt_state;
702
EKF3.getFilterStatus(filt_state);
703
update_notify_from_filter_status(filt_state);
704
}
705
/*
706
if we now have an origin then set in all backends
707
*/
708
if (!done_common_origin) {
709
Location new_origin;
710
if (EKF3.getOriginLLH(new_origin)) {
711
done_common_origin = true;
712
#if HAL_NAVEKF2_AVAILABLE
713
EKF2.setOriginLLH(new_origin);
714
#endif
715
#if AP_AHRS_EXTERNAL_ENABLED
716
external.set_origin(new_origin);
717
#endif
718
}
719
}
720
}
721
}
722
#endif
723
724
#if AP_AHRS_EXTERNAL_ENABLED
725
void AP_AHRS::update_external(void)
726
{
727
external.update();
728
external.get_results(external_estimates);
729
730
if (_active_EKF_type() == EKFType::EXTERNAL) {
731
copy_estimates_from_backend_estimates(external_estimates);
732
}
733
734
/*
735
if we now have an origin then set in all backends
736
*/
737
if (!done_common_origin) {
738
Location new_origin;
739
if (external.get_origin(new_origin)) {
740
done_common_origin = true;
741
#if HAL_NAVEKF2_AVAILABLE
742
EKF2.setOriginLLH(new_origin);
743
#endif
744
#if HAL_NAVEKF3_AVAILABLE
745
EKF3.setOriginLLH(new_origin);
746
#endif
747
}
748
}
749
}
750
#endif // AP_AHRS_EXTERNAL_ENABLED
751
752
void AP_AHRS::reset()
753
{
754
// support locked access functions to AHRS data
755
WITH_SEMAPHORE(_rsem);
756
757
#if AP_AHRS_DCM_ENABLED
758
dcm.reset();
759
#endif
760
#if AP_AHRS_SIM_ENABLED
761
sim.reset();
762
#endif
763
764
#if AP_AHRS_EXTERNAL_ENABLED
765
external.reset();
766
#endif
767
768
#if HAL_NAVEKF2_AVAILABLE
769
if (_ekf2_started) {
770
_ekf2_started = EKF2.InitialiseFilter();
771
}
772
#endif
773
#if HAL_NAVEKF3_AVAILABLE
774
if (_ekf3_started) {
775
_ekf3_started = EKF3.InitialiseFilter();
776
}
777
#endif
778
}
779
780
// dead-reckoning support
781
bool AP_AHRS::_get_location(Location &loc) const
782
{
783
switch (active_EKF_type()) {
784
#if AP_AHRS_DCM_ENABLED
785
case EKFType::DCM:
786
return dcm_estimates.get_location(loc);
787
#endif
788
#if HAL_NAVEKF2_AVAILABLE
789
case EKFType::TWO:
790
if (EKF2.getLLH(loc)) {
791
return true;
792
}
793
break;
794
#endif
795
796
#if HAL_NAVEKF3_AVAILABLE
797
case EKFType::THREE:
798
if (EKF3.getLLH(loc)) {
799
return true;
800
}
801
break;
802
#endif
803
804
#if AP_AHRS_SIM_ENABLED
805
case EKFType::SIM:
806
return sim_estimates.get_location(loc);
807
#endif
808
809
#if AP_AHRS_EXTERNAL_ENABLED
810
case EKFType::EXTERNAL:
811
return external_estimates.get_location(loc);
812
#endif
813
}
814
815
#if AP_AHRS_DCM_ENABLED
816
// fall back to position from DCM
817
if (!always_use_EKF()) {
818
return dcm_estimates.get_location(loc);
819
}
820
#endif
821
822
return false;
823
}
824
825
// status reporting of estimated errors
826
float AP_AHRS::get_error_rp(void) const
827
{
828
#if AP_AHRS_DCM_ENABLED
829
return dcm.get_error_rp();
830
#endif
831
return 0;
832
}
833
834
float AP_AHRS::get_error_yaw(void) const
835
{
836
#if AP_AHRS_DCM_ENABLED
837
return dcm.get_error_yaw();
838
#endif
839
return 0;
840
}
841
842
// return a wind estimation vector, in m/s
843
bool AP_AHRS::_wind_estimate(Vector3f &wind) const
844
{
845
switch (active_EKF_type()) {
846
#if AP_AHRS_DCM_ENABLED
847
case EKFType::DCM:
848
return dcm.wind_estimate(wind);
849
#endif
850
851
#if AP_AHRS_SIM_ENABLED
852
case EKFType::SIM:
853
return sim.wind_estimate(wind);
854
#endif
855
856
#if HAL_NAVEKF2_AVAILABLE
857
case EKFType::TWO:
858
EKF2.getWind(wind);
859
return true;
860
#endif
861
862
#if HAL_NAVEKF3_AVAILABLE
863
case EKFType::THREE:
864
return EKF3.getWind(wind);
865
#endif
866
867
#if AP_AHRS_EXTERNAL_ENABLED
868
case EKFType::EXTERNAL:
869
return external.wind_estimate(wind);
870
#endif
871
}
872
return false;
873
}
874
875
876
/*
877
* Determine how aligned heading_deg is with the wind. Return result
878
* is 1.0 when perfectly aligned heading into wind, -1 when perfectly
879
* aligned with-wind, and zero when perfect cross-wind. There is no
880
* distinction between a left or right cross-wind. Wind speed is ignored
881
*/
882
float AP_AHRS::wind_alignment(const float heading_deg) const
883
{
884
Vector3f wind;
885
if (!wind_estimate(wind)) {
886
return 0;
887
}
888
const float wind_heading_rad = atan2f(-wind.y, -wind.x);
889
return cosf(wind_heading_rad - radians(heading_deg));
890
}
891
892
/*
893
* returns forward head-wind component in m/s. Negative means tail-wind.
894
*/
895
float AP_AHRS::head_wind(void) const
896
{
897
const float alignment = wind_alignment(yaw_sensor*0.01f);
898
return alignment * wind_estimate().xy().length();
899
}
900
901
/*
902
return true if the current AHRS airspeed estimate is directly derived from an airspeed sensor
903
*/
904
bool AP_AHRS::using_airspeed_sensor() const
905
{
906
return state.airspeed_estimate_type == AirspeedEstimateType::AIRSPEED_SENSOR;
907
}
908
909
/*
910
Return true if a airspeed sensor should be used for the AHRS airspeed estimate
911
*/
912
bool AP_AHRS::_should_use_airspeed_sensor(uint8_t airspeed_index) const
913
{
914
if (!airspeed_sensor_enabled(airspeed_index)) {
915
return false;
916
}
917
nav_filter_status filter_status;
918
if (!option_set(Options::DISABLE_AIRSPEED_EKF_CHECK) &&
919
fly_forward &&
920
hal.util->get_soft_armed() &&
921
get_filter_status(filter_status) &&
922
(filter_status.flags.rejecting_airspeed && !filter_status.flags.dead_reckoning)) {
923
// special case for when backend is rejecting airspeed data in
924
// an armed fly_forward state and not dead reckoning. Then the
925
// airspeed data is highly suspect and will be rejected. We
926
// will use the synthetic airspeed instead
927
return false;
928
}
929
return true;
930
}
931
932
// return an airspeed estimate if available. return true
933
// if we have an estimate
934
bool AP_AHRS::_airspeed_EAS(float &airspeed_ret, AirspeedEstimateType &airspeed_estimate_type) const
935
{
936
#if AP_AHRS_DCM_ENABLED || (AP_AIRSPEED_ENABLED && AP_GPS_ENABLED)
937
const uint8_t idx = get_active_airspeed_index();
938
#endif
939
#if AP_AIRSPEED_ENABLED && AP_GPS_ENABLED
940
if (_should_use_airspeed_sensor(idx)) {
941
airspeed_ret = AP::airspeed()->get_airspeed(idx);
942
943
if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
944
// constrain the airspeed by the ground speed
945
// and AHRS_WIND_MAX
946
const float gnd_speed = AP::gps().ground_speed();
947
float true_airspeed = airspeed_ret * get_EAS2TAS();
948
true_airspeed = constrain_float(true_airspeed,
949
gnd_speed - _wind_max,
950
gnd_speed + _wind_max);
951
airspeed_ret = true_airspeed / get_EAS2TAS();
952
}
953
airspeed_estimate_type = AirspeedEstimateType::AIRSPEED_SENSOR;
954
return true;
955
}
956
#endif
957
958
if (!get_wind_estimation_enabled()) {
959
airspeed_estimate_type = AirspeedEstimateType::NO_NEW_ESTIMATE;
960
return false;
961
}
962
963
// estimate it via nav velocity and wind estimates
964
965
// get wind estimates
966
Vector3f wind_vel;
967
bool have_wind = false;
968
969
switch (active_EKF_type()) {
970
#if AP_AHRS_DCM_ENABLED
971
case EKFType::DCM:
972
airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC;
973
return dcm.airspeed_EAS(idx, airspeed_ret);
974
#endif
975
976
#if AP_AHRS_SIM_ENABLED
977
case EKFType::SIM:
978
airspeed_estimate_type = AirspeedEstimateType::SIM;
979
return sim.airspeed_EAS(airspeed_ret);
980
#endif
981
982
#if HAL_NAVEKF2_AVAILABLE
983
case EKFType::TWO:
984
#if AP_AHRS_DCM_ENABLED
985
airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC;
986
return dcm.airspeed_EAS(idx, airspeed_ret);
987
#else
988
return false;
989
#endif
990
#endif
991
992
#if HAL_NAVEKF3_AVAILABLE
993
case EKFType::THREE:
994
have_wind = EKF3.getWind(wind_vel);
995
break;
996
#endif
997
998
#if AP_AHRS_EXTERNAL_ENABLED
999
case EKFType::EXTERNAL:
1000
#if AP_AHRS_DCM_ENABLED
1001
airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC;
1002
return dcm.airspeed_EAS(idx, airspeed_ret);
1003
#else
1004
return false;
1005
#endif
1006
#endif
1007
}
1008
1009
// estimate it via nav velocity and wind estimates
1010
Vector3f nav_vel;
1011
if (have_wind && have_inertial_nav() && get_velocity_NED(nav_vel)) {
1012
Vector3f true_airspeed_vec = nav_vel - wind_vel;
1013
float true_airspeed = true_airspeed_vec.length();
1014
float gnd_speed = nav_vel.length();
1015
if (_wind_max > 0) {
1016
float tas_lim_lower = MAX(0.0f, (gnd_speed - _wind_max));
1017
float tas_lim_upper = MAX(tas_lim_lower, (gnd_speed + _wind_max));
1018
true_airspeed = constrain_float(true_airspeed, tas_lim_lower, tas_lim_upper);
1019
} else {
1020
true_airspeed = MAX(0.0f, true_airspeed);
1021
}
1022
airspeed_ret = true_airspeed / get_EAS2TAS();
1023
airspeed_estimate_type = AirspeedEstimateType::EKF3_SYNTHETIC;
1024
return true;
1025
}
1026
1027
#if AP_AHRS_DCM_ENABLED
1028
// fallback to DCM
1029
airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC;
1030
return dcm.airspeed_EAS(idx, airspeed_ret);
1031
#endif
1032
1033
return false;
1034
}
1035
1036
bool AP_AHRS::_airspeed_TAS(float &airspeed_ret) const
1037
{
1038
switch (active_EKF_type()) {
1039
#if AP_AHRS_DCM_ENABLED
1040
case EKFType::DCM:
1041
return dcm.airspeed_TAS(airspeed_ret);
1042
#endif
1043
#if HAL_NAVEKF2_AVAILABLE
1044
case EKFType::TWO:
1045
#endif
1046
#if HAL_NAVEKF3_AVAILABLE
1047
case EKFType::THREE:
1048
#endif
1049
#if AP_AHRS_SIM_ENABLED
1050
case EKFType::SIM:
1051
#endif
1052
#if AP_AHRS_EXTERNAL_ENABLED
1053
case EKFType::EXTERNAL:
1054
#endif
1055
break;
1056
}
1057
1058
if (!airspeed_estimate(airspeed_ret)) {
1059
return false;
1060
}
1061
airspeed_ret *= get_EAS2TAS();
1062
return true;
1063
}
1064
1065
// return estimate of true airspeed vector in body frame in m/s
1066
// returns false if estimate is unavailable
1067
bool AP_AHRS::_airspeed_TAS(Vector3f &vec) const
1068
{
1069
switch (active_EKF_type()) {
1070
#if AP_AHRS_DCM_ENABLED
1071
case EKFType::DCM:
1072
break;
1073
#endif
1074
#if HAL_NAVEKF2_AVAILABLE
1075
case EKFType::TWO:
1076
return EKF2.getAirSpdVec(vec);
1077
#endif
1078
1079
#if HAL_NAVEKF3_AVAILABLE
1080
case EKFType::THREE:
1081
return EKF3.getAirSpdVec(vec);
1082
#endif
1083
1084
#if AP_AHRS_SIM_ENABLED
1085
case EKFType::SIM:
1086
break;
1087
#endif
1088
1089
#if AP_AHRS_EXTERNAL_ENABLED
1090
case EKFType::EXTERNAL:
1091
break;
1092
#endif
1093
}
1094
return false;
1095
}
1096
1097
// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed
1098
// returns false if the data is unavailable
1099
bool AP_AHRS::airspeed_health_data(float &innovation, float &innovationVariance, uint32_t &age_ms) const
1100
{
1101
switch (active_EKF_type()) {
1102
#if AP_AHRS_DCM_ENABLED
1103
case EKFType::DCM:
1104
break;
1105
#endif
1106
#if HAL_NAVEKF2_AVAILABLE
1107
case EKFType::TWO:
1108
break;
1109
#endif
1110
1111
#if HAL_NAVEKF3_AVAILABLE
1112
case EKFType::THREE:
1113
return EKF3.getAirSpdHealthData(innovation, innovationVariance, age_ms);
1114
#endif
1115
1116
#if AP_AHRS_SIM_ENABLED
1117
case EKFType::SIM:
1118
break;
1119
#endif
1120
1121
#if AP_AHRS_EXTERNAL_ENABLED
1122
case EKFType::EXTERNAL:
1123
break;
1124
#endif
1125
}
1126
return false;
1127
}
1128
1129
// return a synthetic EAS estimate (one derived from sensors
1130
// other than an actual airspeed sensor), if available. return
1131
// true if we have a synthetic airspeed. ret will not be modified
1132
// on failure.
1133
bool AP_AHRS::synthetic_airspeed(float &ret) const
1134
{
1135
#if AP_AHRS_DCM_ENABLED
1136
return dcm.synthetic_airspeed_EAS(ret);
1137
#endif
1138
return false;
1139
}
1140
1141
// true if compass is being used
1142
bool AP_AHRS::use_compass(void)
1143
{
1144
switch (active_EKF_type()) {
1145
#if AP_AHRS_DCM_ENABLED
1146
case EKFType::DCM:
1147
break;
1148
#endif
1149
#if HAL_NAVEKF2_AVAILABLE
1150
case EKFType::TWO:
1151
return EKF2.use_compass();
1152
#endif
1153
1154
#if HAL_NAVEKF3_AVAILABLE
1155
case EKFType::THREE:
1156
return EKF3.use_compass();
1157
#endif
1158
1159
#if AP_AHRS_SIM_ENABLED
1160
case EKFType::SIM:
1161
return sim.use_compass();
1162
#endif
1163
1164
#if AP_AHRS_EXTERNAL_ENABLED
1165
case EKFType::EXTERNAL:
1166
break;
1167
#endif
1168
}
1169
#if AP_AHRS_DCM_ENABLED
1170
return dcm.use_compass();
1171
#endif
1172
return false;
1173
}
1174
1175
// return the quaternion defining the rotation from NED to XYZ (body) axes
1176
bool AP_AHRS::_get_quaternion(Quaternion &quat) const
1177
{
1178
// backends always return in autopilot XYZ frame; rotate result
1179
// according to trim
1180
switch (active_EKF_type()) {
1181
#if AP_AHRS_DCM_ENABLED
1182
case EKFType::DCM:
1183
if (!dcm.get_quaternion(quat)) {
1184
return false;
1185
}
1186
break;
1187
#endif
1188
#if HAL_NAVEKF2_AVAILABLE
1189
case EKFType::TWO:
1190
if (!_ekf2_started) {
1191
return false;
1192
}
1193
EKF2.getQuaternion(quat);
1194
break;
1195
#endif
1196
#if HAL_NAVEKF3_AVAILABLE
1197
case EKFType::THREE:
1198
if (!_ekf3_started) {
1199
return false;
1200
}
1201
EKF3.getQuaternion(quat);
1202
break;
1203
#endif
1204
#if AP_AHRS_SIM_ENABLED
1205
case EKFType::SIM:
1206
if (!sim.get_quaternion(quat)) {
1207
return false;
1208
}
1209
break;
1210
#endif
1211
#if AP_AHRS_EXTERNAL_ENABLED
1212
case EKFType::EXTERNAL:
1213
// we assume the external AHRS isn't trimmed with the autopilot!
1214
return external.get_quaternion(quat);
1215
#endif
1216
}
1217
1218
quat.rotate(-_trim.get());
1219
1220
return true;
1221
}
1222
1223
// return secondary attitude solution if available, as eulers in radians
1224
bool AP_AHRS::_get_secondary_attitude(Vector3f &eulers) const
1225
{
1226
EKFType secondary_ekf_type;
1227
if (!_get_secondary_EKF_type(secondary_ekf_type)) {
1228
return false;
1229
}
1230
1231
switch (secondary_ekf_type) {
1232
1233
#if AP_AHRS_DCM_ENABLED
1234
case EKFType::DCM:
1235
// DCM is secondary
1236
eulers[0] = dcm_estimates.roll_rad;
1237
eulers[1] = dcm_estimates.pitch_rad;
1238
eulers[2] = dcm_estimates.yaw_rad;
1239
return true;
1240
#endif
1241
1242
#if HAL_NAVEKF2_AVAILABLE
1243
case EKFType::TWO:
1244
// EKF2 is secondary
1245
EKF2.getEulerAngles(eulers);
1246
return _ekf2_started;
1247
#endif
1248
1249
#if HAL_NAVEKF3_AVAILABLE
1250
case EKFType::THREE:
1251
// EKF3 is secondary
1252
EKF3.getEulerAngles(eulers);
1253
return _ekf3_started;
1254
#endif
1255
1256
#if AP_AHRS_SIM_ENABLED
1257
case EKFType::SIM:
1258
// SITL is secondary (should never happen)
1259
return false;
1260
#endif
1261
1262
#if AP_AHRS_EXTERNAL_ENABLED
1263
case EKFType::EXTERNAL: {
1264
// External is secondary
1265
eulers[0] = external_estimates.roll_rad;
1266
eulers[1] = external_estimates.pitch_rad;
1267
eulers[2] = external_estimates.yaw_rad;
1268
return true;
1269
}
1270
#endif
1271
}
1272
1273
// since there is no default case above, this is unreachable
1274
return false;
1275
}
1276
1277
1278
// return secondary attitude solution if available, as quaternion
1279
bool AP_AHRS::_get_secondary_quaternion(Quaternion &quat) const
1280
{
1281
EKFType secondary_ekf_type;
1282
if (!_get_secondary_EKF_type(secondary_ekf_type)) {
1283
return false;
1284
}
1285
1286
switch (secondary_ekf_type) {
1287
1288
#if AP_AHRS_DCM_ENABLED
1289
case EKFType::DCM:
1290
// DCM is secondary
1291
if (!dcm.get_quaternion(quat)) {
1292
return false;
1293
}
1294
break;
1295
#endif
1296
1297
#if HAL_NAVEKF2_AVAILABLE
1298
case EKFType::TWO:
1299
// EKF2 is secondary
1300
if (!_ekf2_started) {
1301
return false;
1302
}
1303
EKF2.getQuaternion(quat);
1304
break;
1305
#endif
1306
1307
#if HAL_NAVEKF3_AVAILABLE
1308
case EKFType::THREE:
1309
// EKF3 is secondary
1310
if (!_ekf3_started) {
1311
return false;
1312
}
1313
EKF3.getQuaternion(quat);
1314
break;
1315
#endif
1316
1317
#if AP_AHRS_SIM_ENABLED
1318
case EKFType::SIM:
1319
// SITL is secondary (should never happen)
1320
return false;
1321
#endif
1322
1323
#if AP_AHRS_EXTERNAL_ENABLED
1324
case EKFType::EXTERNAL:
1325
// External is secondary
1326
return external.get_quaternion(quat);
1327
#endif
1328
}
1329
1330
quat.rotate(-_trim.get());
1331
1332
return true;
1333
}
1334
1335
// return secondary position solution if available
1336
bool AP_AHRS::_get_secondary_position(Location &loc) const
1337
{
1338
EKFType secondary_ekf_type;
1339
if (!_get_secondary_EKF_type(secondary_ekf_type)) {
1340
return false;
1341
}
1342
1343
switch (secondary_ekf_type) {
1344
1345
#if AP_AHRS_DCM_ENABLED
1346
case EKFType::DCM:
1347
// return DCM position
1348
loc = dcm_estimates.location;
1349
// FIXME: we intentionally do not return whether location is
1350
// actually valid here so we continue to send mavlink messages
1351
// and log data:
1352
return true;
1353
#endif
1354
1355
#if HAL_NAVEKF2_AVAILABLE
1356
case EKFType::TWO:
1357
// EKF2 is secondary
1358
EKF2.getLLH(loc);
1359
return _ekf2_started;
1360
#endif
1361
1362
#if HAL_NAVEKF3_AVAILABLE
1363
case EKFType::THREE:
1364
// EKF3 is secondary
1365
EKF3.getLLH(loc);
1366
return _ekf3_started;
1367
#endif
1368
1369
#if AP_AHRS_SIM_ENABLED
1370
case EKFType::SIM:
1371
// SITL is secondary (should never happen)
1372
return false;
1373
#endif
1374
1375
#if AP_AHRS_EXTERNAL_ENABLED
1376
case EKFType::EXTERNAL:
1377
// External is secondary
1378
return external_estimates.get_location(loc);
1379
#endif
1380
}
1381
1382
// since there is no default case above, this is unreachable
1383
return false;
1384
}
1385
1386
// EKF has a better ground speed vector estimate
1387
Vector2f AP_AHRS::_groundspeed_vector(void)
1388
{
1389
switch (active_EKF_type()) {
1390
#if AP_AHRS_DCM_ENABLED
1391
case EKFType::DCM:
1392
return dcm.groundspeed_vector();
1393
#endif
1394
1395
#if HAL_NAVEKF2_AVAILABLE
1396
case EKFType::TWO: {
1397
Vector3f vec;
1398
EKF2.getVelNED(vec);
1399
return vec.xy();
1400
}
1401
#endif
1402
1403
#if HAL_NAVEKF3_AVAILABLE
1404
case EKFType::THREE: {
1405
Vector3f vec;
1406
EKF3.getVelNED(vec);
1407
return vec.xy();
1408
}
1409
#endif
1410
1411
#if AP_AHRS_SIM_ENABLED
1412
case EKFType::SIM:
1413
return sim.groundspeed_vector();
1414
#endif
1415
#if AP_AHRS_EXTERNAL_ENABLED
1416
case EKFType::EXTERNAL: {
1417
return external.groundspeed_vector();
1418
}
1419
#endif
1420
}
1421
return Vector2f();
1422
}
1423
1424
float AP_AHRS::_groundspeed(void)
1425
{
1426
switch (active_EKF_type()) {
1427
#if AP_AHRS_DCM_ENABLED
1428
case EKFType::DCM:
1429
return dcm.groundspeed();
1430
#endif
1431
#if HAL_NAVEKF2_AVAILABLE
1432
case EKFType::TWO:
1433
#endif
1434
1435
#if HAL_NAVEKF3_AVAILABLE
1436
case EKFType::THREE:
1437
#endif
1438
1439
#if AP_AHRS_EXTERNAL_ENABLED
1440
case EKFType::EXTERNAL:
1441
#endif
1442
1443
#if AP_AHRS_SIM_ENABLED
1444
case EKFType::SIM:
1445
#endif
1446
break;
1447
}
1448
return groundspeed_vector().length();
1449
}
1450
1451
// set the EKF's origin location in 10e7 degrees. This should only
1452
// be called when the EKF has no absolute position reference (i.e. GPS)
1453
// from which to decide the origin on its own
1454
bool AP_AHRS::set_origin(const Location &loc)
1455
{
1456
WITH_SEMAPHORE(_rsem);
1457
#if HAL_NAVEKF2_AVAILABLE
1458
const bool ret2 = EKF2.setOriginLLH(loc);
1459
#endif
1460
#if HAL_NAVEKF3_AVAILABLE
1461
const bool ret3 = EKF3.setOriginLLH(loc);
1462
#endif
1463
#if AP_AHRS_EXTERNAL_ENABLED
1464
const bool ret_ext = external.set_origin(loc);
1465
#endif
1466
1467
// return success if active EKF's origin was set
1468
bool success = false;
1469
switch (active_EKF_type()) {
1470
#if AP_AHRS_DCM_ENABLED
1471
case EKFType::DCM:
1472
break;
1473
#endif
1474
1475
#if HAL_NAVEKF2_AVAILABLE
1476
case EKFType::TWO:
1477
success = ret2;
1478
break;
1479
#endif
1480
1481
#if HAL_NAVEKF3_AVAILABLE
1482
case EKFType::THREE:
1483
success = ret3;
1484
break;
1485
#endif
1486
1487
#if AP_AHRS_SIM_ENABLED
1488
case EKFType::SIM:
1489
// never allow origin set in SITL. The origin is set by the
1490
// simulation backend
1491
break;
1492
#endif
1493
#if AP_AHRS_EXTERNAL_ENABLED
1494
case EKFType::EXTERNAL:
1495
success = ret_ext;
1496
break;
1497
#endif
1498
}
1499
1500
if (success) {
1501
state.origin_ok = _get_origin(state.origin);
1502
#if HAL_LOGGING_ENABLED
1503
Log_Write_Home_And_Origin();
1504
#endif
1505
}
1506
return success;
1507
}
1508
1509
#if AP_AHRS_POSITION_RESET_ENABLED
1510
bool AP_AHRS::handle_external_position_estimate(const Location &loc, float pos_accuracy, uint32_t timestamp_ms)
1511
{
1512
#if HAL_NAVEKF3_AVAILABLE
1513
return EKF3.setLatLng(loc, pos_accuracy, timestamp_ms);
1514
#endif
1515
return false;
1516
}
1517
#endif
1518
1519
// return true if inertial navigation is active
1520
bool AP_AHRS::have_inertial_nav(void) const
1521
{
1522
#if AP_AHRS_DCM_ENABLED
1523
return active_EKF_type() != EKFType::DCM;
1524
#endif
1525
return true;
1526
}
1527
1528
// return a ground velocity in meters/second, North/East/Down
1529
// order. Must only be called if have_inertial_nav() is true
1530
bool AP_AHRS::_get_velocity_NED(Vector3f &vec) const
1531
{
1532
switch (active_EKF_type()) {
1533
#if AP_AHRS_DCM_ENABLED
1534
case EKFType::DCM:
1535
break;
1536
#endif
1537
#if HAL_NAVEKF2_AVAILABLE
1538
case EKFType::TWO:
1539
EKF2.getVelNED(vec);
1540
return true;
1541
#endif
1542
1543
#if HAL_NAVEKF3_AVAILABLE
1544
case EKFType::THREE:
1545
EKF3.getVelNED(vec);
1546
return true;
1547
#endif
1548
1549
#if AP_AHRS_SIM_ENABLED
1550
case EKFType::SIM:
1551
return sim.get_velocity_NED(vec);
1552
#endif
1553
#if AP_AHRS_EXTERNAL_ENABLED
1554
case EKFType::EXTERNAL:
1555
return external.get_velocity_NED(vec);
1556
#endif
1557
}
1558
#if AP_AHRS_DCM_ENABLED
1559
return dcm.get_velocity_NED(vec);
1560
#endif
1561
return false;
1562
}
1563
1564
// returns the expected NED magnetic field
1565
bool AP_AHRS::get_mag_field_NED(Vector3f &vec) const
1566
{
1567
switch (active_EKF_type()) {
1568
#if AP_AHRS_DCM_ENABLED
1569
case EKFType::DCM:
1570
return false;
1571
#endif
1572
#if HAL_NAVEKF2_AVAILABLE
1573
case EKFType::TWO:
1574
EKF2.getMagNED(vec);
1575
return true;
1576
#endif
1577
1578
#if HAL_NAVEKF3_AVAILABLE
1579
case EKFType::THREE:
1580
EKF3.getMagNED(vec);
1581
return true;
1582
#endif
1583
1584
#if AP_AHRS_SIM_ENABLED
1585
case EKFType::SIM:
1586
return false;
1587
#endif
1588
#if AP_AHRS_EXTERNAL_ENABLED
1589
case EKFType::EXTERNAL:
1590
return false;
1591
#endif
1592
}
1593
return false;
1594
}
1595
1596
// returns the estimated magnetic field offsets in body frame
1597
bool AP_AHRS::get_mag_field_correction(Vector3f &vec) const
1598
{
1599
switch (active_EKF_type()) {
1600
#if AP_AHRS_DCM_ENABLED
1601
case EKFType::DCM:
1602
return false;
1603
#endif
1604
#if HAL_NAVEKF2_AVAILABLE
1605
case EKFType::TWO:
1606
EKF2.getMagXYZ(vec);
1607
return true;
1608
#endif
1609
1610
#if HAL_NAVEKF3_AVAILABLE
1611
case EKFType::THREE:
1612
EKF3.getMagXYZ(vec);
1613
return true;
1614
#endif
1615
1616
#if AP_AHRS_SIM_ENABLED
1617
case EKFType::SIM:
1618
return false;
1619
#endif
1620
#if AP_AHRS_EXTERNAL_ENABLED
1621
case EKFType::EXTERNAL:
1622
return false;
1623
#endif
1624
}
1625
// since there is no default case above, this is unreachable
1626
return false;
1627
}
1628
1629
// Get a derivative of the vertical position which is kinematically consistent with the vertical position is required by some control loops.
1630
// 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.
1631
bool AP_AHRS::get_vert_pos_rate_D(float &velocity) const
1632
{
1633
switch (active_EKF_type()) {
1634
#if AP_AHRS_DCM_ENABLED
1635
case EKFType::DCM:
1636
return dcm.get_vert_pos_rate_D(velocity);
1637
#endif
1638
1639
#if HAL_NAVEKF2_AVAILABLE
1640
case EKFType::TWO:
1641
velocity = EKF2.getPosDownDerivative();
1642
return true;
1643
#endif
1644
1645
#if HAL_NAVEKF3_AVAILABLE
1646
case EKFType::THREE:
1647
velocity = EKF3.getPosDownDerivative();
1648
return true;
1649
#endif
1650
1651
#if AP_AHRS_SIM_ENABLED
1652
case EKFType::SIM:
1653
return sim.get_vert_pos_rate_D(velocity);
1654
#endif
1655
#if AP_AHRS_EXTERNAL_ENABLED
1656
case EKFType::EXTERNAL:
1657
return external.get_vert_pos_rate_D(velocity);
1658
#endif
1659
}
1660
// since there is no default case above, this is unreachable
1661
return false;
1662
}
1663
1664
// get latest height above ground level estimate in metres and a validity flag
1665
bool AP_AHRS::get_hagl(float &height) const
1666
{
1667
switch (active_EKF_type()) {
1668
#if AP_AHRS_DCM_ENABLED
1669
case EKFType::DCM:
1670
return false;
1671
#endif
1672
#if HAL_NAVEKF2_AVAILABLE
1673
case EKFType::TWO:
1674
return EKF2.getHAGL(height);
1675
#endif
1676
1677
#if HAL_NAVEKF3_AVAILABLE
1678
case EKFType::THREE:
1679
return EKF3.getHAGL(height);
1680
#endif
1681
1682
#if AP_AHRS_SIM_ENABLED
1683
case EKFType::SIM:
1684
return sim.get_hagl(height);
1685
#endif
1686
#if AP_AHRS_EXTERNAL_ENABLED
1687
case EKFType::EXTERNAL: {
1688
return false;
1689
}
1690
#endif
1691
}
1692
// since there is no default case above, this is unreachable
1693
return false;
1694
}
1695
1696
/*
1697
return a relative NED position from the origin in meters
1698
*/
1699
bool AP_AHRS::get_relative_position_NED_origin(Vector3f &vec) const
1700
{
1701
switch (active_EKF_type()) {
1702
#if AP_AHRS_DCM_ENABLED
1703
case EKFType::DCM:
1704
return dcm.get_relative_position_NED_origin(vec);
1705
#endif
1706
#if HAL_NAVEKF2_AVAILABLE
1707
case EKFType::TWO: {
1708
Vector2f posNE;
1709
float posD;
1710
if (EKF2.getPosNE(posNE) && EKF2.getPosD(posD)) {
1711
// position is valid
1712
vec.x = posNE.x;
1713
vec.y = posNE.y;
1714
vec.z = posD;
1715
return true;
1716
}
1717
return false;
1718
}
1719
#endif
1720
1721
#if HAL_NAVEKF3_AVAILABLE
1722
case EKFType::THREE: {
1723
Vector2f posNE;
1724
float posD;
1725
if (EKF3.getPosNE(posNE) && EKF3.getPosD(posD)) {
1726
// position is valid
1727
vec.x = posNE.x;
1728
vec.y = posNE.y;
1729
vec.z = posD;
1730
return true;
1731
}
1732
return false;
1733
}
1734
#endif
1735
1736
#if AP_AHRS_SIM_ENABLED
1737
case EKFType::SIM:
1738
return sim.get_relative_position_NED_origin(vec);
1739
#endif
1740
#if AP_AHRS_EXTERNAL_ENABLED
1741
case EKFType::EXTERNAL: {
1742
return external.get_relative_position_NED_origin(vec);
1743
}
1744
#endif
1745
}
1746
// since there is no default case above, this is unreachable
1747
return false;
1748
}
1749
1750
/*
1751
return a relative ground position from home in meters
1752
*/
1753
bool AP_AHRS::get_relative_position_NED_home(Vector3f &vec) const
1754
{
1755
Location loc;
1756
if (!_home_is_set ||
1757
!get_location(loc)) {
1758
return false;
1759
}
1760
vec = _home.get_distance_NED(loc);
1761
return true;
1762
}
1763
1764
/*
1765
return a relative position estimate from the origin in meters
1766
*/
1767
bool AP_AHRS::get_relative_position_NE_origin(Vector2f &posNE) const
1768
{
1769
switch (active_EKF_type()) {
1770
#if AP_AHRS_DCM_ENABLED
1771
case EKFType::DCM:
1772
return dcm.get_relative_position_NE_origin(posNE);
1773
#endif
1774
#if HAL_NAVEKF2_AVAILABLE
1775
case EKFType::TWO: {
1776
bool position_is_valid = EKF2.getPosNE(posNE);
1777
return position_is_valid;
1778
}
1779
#endif
1780
1781
#if HAL_NAVEKF3_AVAILABLE
1782
case EKFType::THREE: {
1783
bool position_is_valid = EKF3.getPosNE(posNE);
1784
return position_is_valid;
1785
}
1786
#endif
1787
1788
#if AP_AHRS_SIM_ENABLED
1789
case EKFType::SIM: {
1790
return sim.get_relative_position_NE_origin(posNE);
1791
}
1792
#endif
1793
#if AP_AHRS_EXTERNAL_ENABLED
1794
case EKFType::EXTERNAL:
1795
return external.get_relative_position_NE_origin(posNE);
1796
#endif
1797
}
1798
// since there is no default case above, this is unreachable
1799
return false;
1800
}
1801
1802
/*
1803
return a relative ground position from home in meters North/East
1804
*/
1805
bool AP_AHRS::get_relative_position_NE_home(Vector2f &posNE) const
1806
{
1807
Location loc;
1808
if (!_home_is_set ||
1809
!get_location(loc)) {
1810
return false;
1811
}
1812
1813
posNE = _home.get_distance_NE(loc);
1814
return true;
1815
}
1816
1817
// write a relative ground position estimate to the origin in meters, North/East order
1818
1819
1820
/*
1821
return a relative ground position from the origin in meters, down
1822
*/
1823
bool AP_AHRS::get_relative_position_D_origin(float &posD) const
1824
{
1825
switch (active_EKF_type()) {
1826
#if AP_AHRS_DCM_ENABLED
1827
case EKFType::DCM:
1828
return dcm.get_relative_position_D_origin(posD);
1829
#endif
1830
#if HAL_NAVEKF2_AVAILABLE
1831
case EKFType::TWO: {
1832
bool position_is_valid = EKF2.getPosD(posD);
1833
return position_is_valid;
1834
}
1835
#endif
1836
1837
#if HAL_NAVEKF3_AVAILABLE
1838
case EKFType::THREE: {
1839
bool position_is_valid = EKF3.getPosD(posD);
1840
return position_is_valid;
1841
}
1842
#endif
1843
1844
#if AP_AHRS_SIM_ENABLED
1845
case EKFType::SIM:
1846
return sim.get_relative_position_D_origin(posD);
1847
#endif
1848
#if AP_AHRS_EXTERNAL_ENABLED
1849
case EKFType::EXTERNAL:
1850
return external.get_relative_position_D_origin(posD);
1851
#endif
1852
}
1853
// since there is no default case above, this is unreachable
1854
return false;
1855
}
1856
1857
/*
1858
return relative position from home in meters
1859
*/
1860
void AP_AHRS::get_relative_position_D_home(float &posD) const
1861
{
1862
if (!_home_is_set) {
1863
// fall back to an altitude derived from barometric pressure
1864
// differences vs a calibrated ground pressure:
1865
posD = -AP::baro().get_altitude();
1866
return;
1867
}
1868
1869
Location originLLH;
1870
float originD;
1871
if (!get_relative_position_D_origin(originD) ||
1872
!_get_origin(originLLH)) {
1873
#if AP_GPS_ENABLED
1874
const auto &gps = AP::gps();
1875
if (_gps_use == GPSUse::EnableWithHeight &&
1876
gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
1877
posD = (_home.alt - gps.location().alt) * 0.01;
1878
return;
1879
}
1880
#endif
1881
posD = -AP::baro().get_altitude();
1882
return;
1883
}
1884
1885
posD = originD - ((originLLH.alt - _home.alt) * 0.01f);
1886
return;
1887
}
1888
/*
1889
canonicalise _ekf_type, forcing it to be 0, 2 or 3
1890
type 1 has been deprecated
1891
*/
1892
AP_AHRS::EKFType AP_AHRS::ekf_type(void) const
1893
{
1894
EKFType type = (EKFType)_ekf_type.get();
1895
switch (type) {
1896
#if AP_AHRS_SIM_ENABLED
1897
case EKFType::SIM:
1898
return type;
1899
#endif
1900
#if AP_AHRS_EXTERNAL_ENABLED
1901
case EKFType::EXTERNAL:
1902
return type;
1903
#endif
1904
#if HAL_NAVEKF2_AVAILABLE
1905
case EKFType::TWO:
1906
return type;
1907
#endif
1908
#if HAL_NAVEKF3_AVAILABLE
1909
case EKFType::THREE:
1910
return type;
1911
#endif
1912
#if AP_AHRS_DCM_ENABLED
1913
case EKFType::DCM:
1914
if (always_use_EKF()) {
1915
#if HAL_NAVEKF2_AVAILABLE
1916
return EKFType::TWO;
1917
#elif HAL_NAVEKF3_AVAILABLE
1918
return EKFType::THREE;
1919
#endif
1920
}
1921
return EKFType::DCM;
1922
#endif
1923
}
1924
// we can get to here if the user has mis-set AHRS_EKF_TYPE - any
1925
// value above 3 will get to here. TWO is returned here for no
1926
// better reason than "tradition".
1927
#if HAL_NAVEKF2_AVAILABLE
1928
return EKFType::TWO;
1929
#elif HAL_NAVEKF3_AVAILABLE
1930
return EKFType::THREE;
1931
#elif AP_AHRS_DCM_ENABLED
1932
return EKFType::DCM;
1933
#else
1934
#error "no default backend available"
1935
#endif
1936
}
1937
1938
AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const
1939
{
1940
EKFType ret = fallback_active_EKF_type();
1941
1942
switch (ekf_type()) {
1943
#if AP_AHRS_DCM_ENABLED
1944
case EKFType::DCM:
1945
return EKFType::DCM;
1946
#endif
1947
1948
#if HAL_NAVEKF2_AVAILABLE
1949
case EKFType::TWO: {
1950
// do we have an EKF2 yet?
1951
if (!_ekf2_started) {
1952
return fallback_active_EKF_type();
1953
}
1954
if (always_use_EKF()) {
1955
uint16_t ekf2_faults;
1956
EKF2.getFilterFaults(ekf2_faults);
1957
if (ekf2_faults == 0) {
1958
ret = EKFType::TWO;
1959
}
1960
} else if (EKF2.healthy()) {
1961
ret = EKFType::TWO;
1962
}
1963
break;
1964
}
1965
#endif
1966
1967
#if HAL_NAVEKF3_AVAILABLE
1968
case EKFType::THREE: {
1969
// do we have an EKF3 yet?
1970
if (!_ekf3_started) {
1971
return fallback_active_EKF_type();
1972
}
1973
if (always_use_EKF()) {
1974
uint16_t ekf3_faults;
1975
EKF3.getFilterFaults(ekf3_faults);
1976
if (ekf3_faults == 0) {
1977
ret = EKFType::THREE;
1978
}
1979
} else if (EKF3.healthy()) {
1980
ret = EKFType::THREE;
1981
}
1982
break;
1983
}
1984
#endif
1985
1986
#if AP_AHRS_SIM_ENABLED
1987
case EKFType::SIM:
1988
ret = EKFType::SIM;
1989
break;
1990
#endif
1991
#if AP_AHRS_EXTERNAL_ENABLED
1992
case EKFType::EXTERNAL:
1993
ret = EKFType::EXTERNAL;
1994
break;
1995
#endif
1996
}
1997
1998
#if AP_AHRS_DCM_ENABLED
1999
// Handle fallback for fixed wing planes (including VTOL's) and ground vehicles.
2000
if (_vehicle_class == VehicleClass::FIXED_WING ||
2001
_vehicle_class == VehicleClass::GROUND) {
2002
bool should_use_gps = true;
2003
nav_filter_status filt_state {};
2004
switch (ret) {
2005
case EKFType::DCM:
2006
// already using DCM
2007
break;
2008
#if HAL_NAVEKF2_AVAILABLE
2009
case EKFType::TWO:
2010
EKF2.getFilterStatus(filt_state);
2011
should_use_gps = EKF2.configuredToUseGPSForPosXY();
2012
break;
2013
#endif
2014
#if HAL_NAVEKF3_AVAILABLE
2015
case EKFType::THREE:
2016
EKF3.getFilterStatus(filt_state);
2017
should_use_gps = EKF3.configuredToUseGPSForPosXY();
2018
break;
2019
#endif
2020
#if AP_AHRS_SIM_ENABLED
2021
case EKFType::SIM:
2022
get_filter_status(filt_state);
2023
break;
2024
#endif
2025
#if AP_AHRS_EXTERNAL_ENABLED
2026
case EKFType::EXTERNAL:
2027
get_filter_status(filt_state);
2028
should_use_gps = true;
2029
break;
2030
#endif
2031
}
2032
2033
// Handle fallback for the case where the DCM or EKF is unable to provide attitude or height data.
2034
const bool can_use_dcm = dcm.yaw_source_available() || fly_forward;
2035
const bool can_use_ekf = filt_state.flags.attitude && filt_state.flags.vert_vel && filt_state.flags.vert_pos;
2036
if (!can_use_dcm && can_use_ekf) {
2037
// no choice - continue to use EKF
2038
return ret;
2039
} else if (!can_use_ekf) {
2040
// No choice - we have to use DCM
2041
return EKFType::DCM;
2042
}
2043
2044
const bool disable_dcm_fallback = fly_forward?
2045
option_set(Options::DISABLE_DCM_FALLBACK_FW) : option_set(Options::DISABLE_DCM_FALLBACK_VTOL);
2046
if (disable_dcm_fallback) {
2047
// don't fallback
2048
return ret;
2049
}
2050
2051
// Handle loss of global position when we still have a GPS fix
2052
if (hal.util->get_soft_armed() &&
2053
(_gps_use != GPSUse::Disable) &&
2054
should_use_gps &&
2055
AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D &&
2056
(!filt_state.flags.using_gps || !filt_state.flags.horiz_pos_abs)) {
2057
/*
2058
If the EKF is not fusing GPS or doesn't have a 2D fix and we have a 3D GPS lock,
2059
then plane and rover would prefer to use the GPS position from DCM unless the
2060
fallback has been inhibited by the user.
2061
Note: The aircraft could be dead reckoning with acceptable accuracy and rejecting a bad GPS
2062
Note: This is a last resort fallback and makes the navigation highly vulnerable to GPS noise.
2063
Note: When operating in a VTOL flight mode that actively controls height such as QHOVER,
2064
the EKF gives better vertical velocity and position estimates and height control characteristics.
2065
*/
2066
return EKFType::DCM;
2067
}
2068
2069
// Handle complete loss of navigation
2070
if (hal.util->get_soft_armed() && filt_state.flags.const_pos_mode) {
2071
/*
2072
Provided the EKF has been configured to use GPS, ie should_use_gps is true, then the
2073
key difference to the case handled above is only the absence of a GPS fix which means
2074
that DCM will not be able to navigate either so we are primarily concerned with
2075
providing an attitude, vertical position and vertical velocity estimate.
2076
*/
2077
return EKFType::DCM;
2078
}
2079
2080
if (!filt_state.flags.horiz_vel ||
2081
(!filt_state.flags.horiz_pos_abs && !filt_state.flags.horiz_pos_rel)) {
2082
if ((!AP::compass().use_for_yaw()) &&
2083
AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D &&
2084
AP::gps().ground_speed() < 2) {
2085
/*
2086
special handling for non-compass mode when sitting
2087
still. The EKF may not yet have aligned its yaw. We
2088
accept EKF as healthy to allow arming. Once we reach
2089
speed the EKF should get yaw alignment
2090
*/
2091
if (filt_state.flags.gps_quality_good) {
2092
return ret;
2093
}
2094
}
2095
return EKFType::DCM;
2096
}
2097
}
2098
#endif
2099
2100
return ret;
2101
}
2102
2103
AP_AHRS::EKFType AP_AHRS::fallback_active_EKF_type(void) const
2104
{
2105
#if AP_AHRS_DCM_ENABLED
2106
return EKFType::DCM;
2107
#endif
2108
2109
#if HAL_NAVEKF3_AVAILABLE
2110
if (_ekf3_started) {
2111
return EKFType::THREE;
2112
}
2113
#endif
2114
2115
#if HAL_NAVEKF2_AVAILABLE
2116
if (_ekf2_started) {
2117
return EKFType::TWO;
2118
}
2119
#endif
2120
2121
#if AP_AHRS_EXTERNAL_ENABLED
2122
if (external.healthy()) {
2123
return EKFType::EXTERNAL;
2124
}
2125
#endif
2126
2127
// so nobody is ready yet. Return something, even if it is not ready:
2128
#if HAL_NAVEKF3_AVAILABLE
2129
return EKFType::THREE;
2130
#elif HAL_NAVEKF2_AVAILABLE
2131
return EKFType::TWO;
2132
#elif AP_AHRS_EXTERNAL_ENABLED
2133
return EKFType::EXTERNAL;
2134
#endif
2135
}
2136
2137
// get secondary EKF type. returns false if no secondary (i.e. only using DCM)
2138
bool AP_AHRS::_get_secondary_EKF_type(EKFType &secondary_ekf_type) const
2139
{
2140
2141
switch (active_EKF_type()) {
2142
#if AP_AHRS_DCM_ENABLED
2143
case EKFType::DCM:
2144
// EKF2, EKF3 or External is secondary
2145
#if HAL_NAVEKF3_AVAILABLE
2146
if ((EKFType)_ekf_type.get() == EKFType::THREE) {
2147
secondary_ekf_type = EKFType::THREE;
2148
return true;
2149
}
2150
#endif
2151
#if HAL_NAVEKF2_AVAILABLE
2152
if ((EKFType)_ekf_type.get() == EKFType::TWO) {
2153
secondary_ekf_type = EKFType::TWO;
2154
return true;
2155
}
2156
#endif
2157
#if AP_AHRS_EXTERNAL_ENABLED
2158
if ((EKFType)_ekf_type.get() == EKFType::EXTERNAL) {
2159
secondary_ekf_type = EKFType::EXTERNAL;
2160
return true;
2161
}
2162
#endif
2163
return false;
2164
#endif
2165
#if HAL_NAVEKF2_AVAILABLE
2166
case EKFType::TWO:
2167
#endif
2168
#if HAL_NAVEKF3_AVAILABLE
2169
case EKFType::THREE:
2170
#endif
2171
#if AP_AHRS_SIM_ENABLED
2172
case EKFType::SIM:
2173
#endif
2174
#if AP_AHRS_EXTERNAL_ENABLED
2175
case EKFType::EXTERNAL:
2176
#endif
2177
// DCM is secondary
2178
secondary_ekf_type = fallback_active_EKF_type();
2179
return true;
2180
}
2181
2182
// since there is no default case above, this is unreachable
2183
return false;
2184
}
2185
2186
/*
2187
check if the AHRS subsystem is healthy
2188
*/
2189
bool AP_AHRS::healthy(void) const
2190
{
2191
// If EKF is started we switch away if it reports unhealthy. This could be due to bad
2192
// sensor data. If EKF reversion is inhibited, we only switch across if the EKF encounters
2193
// an internal processing error, but not for bad sensor data.
2194
switch (ekf_type()) {
2195
2196
#if AP_AHRS_DCM_ENABLED
2197
case EKFType::DCM:
2198
return dcm.healthy();
2199
#endif
2200
2201
#if HAL_NAVEKF2_AVAILABLE
2202
case EKFType::TWO: {
2203
bool ret = _ekf2_started && EKF2.healthy();
2204
if (!ret) {
2205
return false;
2206
}
2207
if ((_vehicle_class == VehicleClass::FIXED_WING ||
2208
_vehicle_class == VehicleClass::GROUND) &&
2209
active_EKF_type() != EKFType::TWO) {
2210
// on fixed wing we want to be using EKF to be considered
2211
// healthy if EKF is enabled
2212
return false;
2213
}
2214
return true;
2215
}
2216
#endif
2217
2218
#if HAL_NAVEKF3_AVAILABLE
2219
case EKFType::THREE: {
2220
bool ret = _ekf3_started && EKF3.healthy();
2221
if (!ret) {
2222
return false;
2223
}
2224
if ((_vehicle_class == VehicleClass::FIXED_WING ||
2225
_vehicle_class == VehicleClass::GROUND) &&
2226
active_EKF_type() != EKFType::THREE) {
2227
// on fixed wing we want to be using EKF to be considered
2228
// healthy if EKF is enabled
2229
return false;
2230
}
2231
return true;
2232
}
2233
#endif
2234
2235
#if AP_AHRS_SIM_ENABLED
2236
case EKFType::SIM:
2237
return sim.healthy();
2238
#endif
2239
#if AP_AHRS_EXTERNAL_ENABLED
2240
case EKFType::EXTERNAL:
2241
return external.healthy();
2242
#endif
2243
}
2244
2245
return false;
2246
}
2247
2248
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
2249
// requires_position should be true if horizontal position configuration should be checked
2250
bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const
2251
{
2252
bool ret = true;
2253
if (!healthy()) {
2254
// this rather generic failure might be overwritten by
2255
// something more specific in the "backend"
2256
hal.util->snprintf(failure_msg, failure_msg_len, "Not healthy");
2257
ret = false;
2258
}
2259
2260
#if AP_AHRS_EXTERNAL_ENABLED
2261
// Always check external AHRS if enabled
2262
// it is a source for IMU data even if not being used as direct AHRS replacement
2263
if (AP::externalAHRS().enabled() || (ekf_type() == EKFType::EXTERNAL)) {
2264
if (!AP::externalAHRS().pre_arm_check(failure_msg, failure_msg_len)) {
2265
return false;
2266
}
2267
}
2268
#endif
2269
2270
if (!attitudes_consistent(failure_msg, failure_msg_len)) {
2271
return false;
2272
}
2273
2274
// ensure we're using the configured backend, but bypass in compass-less cases:
2275
if (ekf_type() != active_EKF_type() && AP::compass().use_for_yaw()) {
2276
hal.util->snprintf(failure_msg, failure_msg_len, "not using configured AHRS type");
2277
return false;
2278
}
2279
2280
switch (ekf_type()) {
2281
#if AP_AHRS_SIM_ENABLED
2282
case EKFType::SIM:
2283
return ret;
2284
#endif
2285
2286
#if AP_AHRS_DCM_ENABLED
2287
case EKFType::DCM:
2288
return dcm.pre_arm_check(requires_position, failure_msg, failure_msg_len) && ret;
2289
#endif
2290
2291
#if AP_AHRS_EXTERNAL_ENABLED
2292
case EKFType::EXTERNAL:
2293
return external.pre_arm_check(requires_position, failure_msg, failure_msg_len);
2294
#endif
2295
2296
#if HAL_NAVEKF2_AVAILABLE
2297
case EKFType::TWO:
2298
if (!_ekf2_started) {
2299
hal.util->snprintf(failure_msg, failure_msg_len, "EKF2 not started");
2300
return false;
2301
}
2302
return EKF2.pre_arm_check(failure_msg, failure_msg_len) && ret;
2303
#endif
2304
2305
#if HAL_NAVEKF3_AVAILABLE
2306
case EKFType::THREE:
2307
if (!_ekf3_started) {
2308
hal.util->snprintf(failure_msg, failure_msg_len, "EKF3 not started");
2309
return false;
2310
}
2311
return EKF3.pre_arm_check(requires_position, failure_msg, failure_msg_len) && ret;
2312
#endif
2313
}
2314
2315
// if we get here then ekf type is invalid
2316
hal.util->snprintf(failure_msg, failure_msg_len, "invalid EKF type");
2317
return false;
2318
}
2319
2320
// true if the AHRS has completed initialisation
2321
bool AP_AHRS::initialised(void) const
2322
{
2323
switch (ekf_type()) {
2324
#if AP_AHRS_DCM_ENABLED
2325
case EKFType::DCM:
2326
return true;
2327
#endif
2328
2329
#if HAL_NAVEKF2_AVAILABLE
2330
case EKFType::TWO:
2331
// initialisation complete 10sec after ekf has started
2332
return (_ekf2_started && (AP_HAL::millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));
2333
#endif
2334
2335
#if HAL_NAVEKF3_AVAILABLE
2336
case EKFType::THREE:
2337
// initialisation complete 10sec after ekf has started
2338
return (_ekf3_started && (AP_HAL::millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));
2339
#endif
2340
2341
#if AP_AHRS_SIM_ENABLED
2342
case EKFType::SIM:
2343
return true;
2344
#endif
2345
#if AP_AHRS_EXTERNAL_ENABLED
2346
case EKFType::EXTERNAL:
2347
return external.initialised();
2348
#endif
2349
}
2350
return false;
2351
};
2352
2353
// get_filter_status : returns filter status as a series of flags
2354
bool AP_AHRS::get_filter_status(nav_filter_status &status) const
2355
{
2356
switch (ekf_type()) {
2357
#if AP_AHRS_DCM_ENABLED
2358
case EKFType::DCM:
2359
return dcm.get_filter_status(status);
2360
#endif
2361
2362
#if HAL_NAVEKF2_AVAILABLE
2363
case EKFType::TWO:
2364
EKF2.getFilterStatus(status);
2365
return true;
2366
#endif
2367
2368
#if HAL_NAVEKF3_AVAILABLE
2369
case EKFType::THREE:
2370
EKF3.getFilterStatus(status);
2371
return true;
2372
#endif
2373
2374
#if AP_AHRS_SIM_ENABLED
2375
case EKFType::SIM:
2376
return sim.get_filter_status(status);
2377
#endif
2378
#if AP_AHRS_EXTERNAL_ENABLED
2379
case EKFType::EXTERNAL:
2380
return external.get_filter_status(status);
2381
#endif
2382
}
2383
2384
return false;
2385
}
2386
2387
// write optical flow data to EKF
2388
void AP_AHRS::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset, float heightOverride)
2389
{
2390
#if HAL_NAVEKF2_AVAILABLE
2391
EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);
2392
#endif
2393
#if EK3_FEATURE_OPTFLOW_FUSION
2394
EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);
2395
#endif
2396
}
2397
2398
// retrieve latest corrected optical flow samples (used for calibration)
2399
bool AP_AHRS::getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const
2400
{
2401
#if EK3_FEATURE_OPTFLOW_FUSION
2402
return EKF3.getOptFlowSample(timeStamp_ms, flowRate, bodyRate, losPred);
2403
#endif
2404
return false;
2405
}
2406
2407
// write body frame odometry measurements to the EKF
2408
void AP_AHRS::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset)
2409
{
2410
#if HAL_NAVEKF3_AVAILABLE
2411
EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, delay_ms, posOffset);
2412
#endif
2413
}
2414
2415
// Write position and quaternion data from an external navigation system
2416
void AP_AHRS::writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms)
2417
{
2418
#if HAL_NAVEKF2_AVAILABLE
2419
EKF2.writeExtNavData(pos, quat, posErr, angErr, timeStamp_ms, delay_ms, resetTime_ms);
2420
#endif
2421
#if HAL_NAVEKF3_AVAILABLE
2422
EKF3.writeExtNavData(pos, quat, posErr, angErr, timeStamp_ms, delay_ms, resetTime_ms);
2423
#endif
2424
}
2425
2426
// Writes the default equivalent airspeed and 1-sigma uncertainty in m/s to be used in forward flight if a measured airspeed is required and not available.
2427
void AP_AHRS::writeDefaultAirSpeed(float airspeed, float uncertainty)
2428
{
2429
#if HAL_NAVEKF2_AVAILABLE
2430
EKF2.writeDefaultAirSpeed(airspeed);
2431
#endif
2432
#if HAL_NAVEKF3_AVAILABLE
2433
EKF3.writeDefaultAirSpeed(airspeed, uncertainty);
2434
#endif
2435
}
2436
2437
// Write velocity data from an external navigation system
2438
void AP_AHRS::writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms)
2439
{
2440
#if HAL_NAVEKF2_AVAILABLE
2441
EKF2.writeExtNavVelData(vel, err, timeStamp_ms, delay_ms);
2442
#endif
2443
#if HAL_NAVEKF3_AVAILABLE
2444
EKF3.writeExtNavVelData(vel, err, timeStamp_ms, delay_ms);
2445
#endif
2446
}
2447
2448
// get speed limit and XY navigation gain scale factor
2449
void AP_AHRS::getControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
2450
{
2451
switch (active_EKF_type()) {
2452
#if AP_AHRS_DCM_ENABLED
2453
case EKFType::DCM:
2454
dcm.get_control_limits(ekfGndSpdLimit, ekfNavVelGainScaler);
2455
break;
2456
#endif
2457
2458
#if HAL_NAVEKF2_AVAILABLE
2459
case EKFType::TWO:
2460
EKF2.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
2461
break;
2462
#endif
2463
2464
#if HAL_NAVEKF3_AVAILABLE
2465
case EKFType::THREE:
2466
EKF3.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
2467
break;
2468
#endif
2469
2470
#if AP_AHRS_SIM_ENABLED
2471
case EKFType::SIM:
2472
sim.get_control_limits(ekfGndSpdLimit, ekfNavVelGainScaler);
2473
break;
2474
#endif
2475
#if AP_AHRS_EXTERNAL_ENABLED
2476
case EKFType::EXTERNAL:
2477
// no limit on gains, large vel limit
2478
ekfGndSpdLimit = 400;
2479
ekfNavVelGainScaler = 1;
2480
break;
2481
#endif
2482
}
2483
}
2484
2485
/*
2486
get gain factor for Z controllers
2487
*/
2488
float AP_AHRS::getControlScaleZ(void) const
2489
{
2490
#if AP_AHRS_DCM_ENABLED
2491
if (active_EKF_type() == EKFType::DCM) {
2492
// when flying on DCM lower gains by 4x to cope with the high
2493
// lag
2494
return 0.25;
2495
}
2496
#endif
2497
return 1;
2498
}
2499
2500
// get compass offset estimates
2501
// true if offsets are valid
2502
bool AP_AHRS::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
2503
{
2504
switch (ekf_type()) {
2505
#if AP_AHRS_DCM_ENABLED
2506
case EKFType::DCM:
2507
return false;
2508
#endif
2509
#if HAL_NAVEKF2_AVAILABLE
2510
case EKFType::TWO:
2511
return EKF2.getMagOffsets(mag_idx, magOffsets);
2512
#endif
2513
2514
#if HAL_NAVEKF3_AVAILABLE
2515
case EKFType::THREE:
2516
return EKF3.getMagOffsets(mag_idx, magOffsets);
2517
#endif
2518
2519
#if AP_AHRS_SIM_ENABLED
2520
case EKFType::SIM:
2521
magOffsets.zero();
2522
return true;
2523
#endif
2524
#if AP_AHRS_EXTERNAL_ENABLED
2525
case EKFType::EXTERNAL:
2526
return false;
2527
#endif
2528
}
2529
// since there is no default case above, this is unreachable
2530
return false;
2531
}
2532
2533
// Retrieves the NED delta velocity corrected
2534
void AP_AHRS::_getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const
2535
{
2536
int8_t imu_idx = -1;
2537
Vector3f accel_bias;
2538
switch (active_EKF_type()) {
2539
#if AP_AHRS_DCM_ENABLED
2540
case EKFType::DCM:
2541
break;
2542
#endif
2543
#if HAL_NAVEKF2_AVAILABLE
2544
case EKFType::TWO:
2545
imu_idx = EKF2.getPrimaryCoreIMUIndex();
2546
EKF2.getAccelZBias(accel_bias.z);
2547
break;
2548
#endif
2549
#if HAL_NAVEKF3_AVAILABLE
2550
case EKFType::THREE:
2551
imu_idx = EKF3.getPrimaryCoreIMUIndex();
2552
EKF3.getAccelBias(-1,accel_bias);
2553
break;
2554
#endif
2555
#if AP_AHRS_SIM_ENABLED
2556
case EKFType::SIM:
2557
break;
2558
#endif
2559
#if AP_AHRS_EXTERNAL_ENABLED
2560
case EKFType::EXTERNAL:
2561
break;
2562
#endif
2563
}
2564
ret.zero();
2565
if (imu_idx == -1) {
2566
AP::ins().get_delta_velocity(ret, dt);
2567
return;
2568
}
2569
AP::ins().get_delta_velocity((uint8_t)imu_idx, ret, dt);
2570
ret -= accel_bias*dt;
2571
ret = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * ret;
2572
ret.z += GRAVITY_MSS*dt;
2573
}
2574
2575
void AP_AHRS::set_failure_inconsistent_message(const char *estimator, const char *axis, float diff_rad, char *failure_msg, const uint8_t failure_msg_len) const
2576
{
2577
hal.util->snprintf(failure_msg, failure_msg_len, "%s %s inconsistent %d deg. Wait or reboot", estimator, axis, (int)degrees(diff_rad));
2578
}
2579
2580
// check all cores providing consistent attitudes for prearm checks
2581
bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const
2582
{
2583
// get primary attitude source's attitude as quaternion
2584
Quaternion primary_quat;
2585
get_quat_body_to_ned(primary_quat);
2586
// only check yaw if compasses are being used
2587
const bool check_yaw = AP::compass().use_for_yaw();
2588
uint8_t total_ekf_cores = 0;
2589
2590
#if HAL_NAVEKF2_AVAILABLE
2591
// check primary vs ekf2
2592
if (ekf_type() == EKFType::TWO || active_EKF_type() == EKFType::TWO) {
2593
for (uint8_t i = 0; i < EKF2.activeCores(); i++) {
2594
Quaternion ekf2_quat;
2595
EKF2.getQuaternionBodyToNED(i, ekf2_quat);
2596
2597
// check roll and pitch difference
2598
const float rp_diff_rad = primary_quat.roll_pitch_difference(ekf2_quat);
2599
if (rp_diff_rad > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {
2600
set_failure_inconsistent_message("EKF2", "Roll/Pitch", rp_diff_rad, failure_msg, failure_msg_len);
2601
return false;
2602
}
2603
2604
// check yaw difference
2605
Vector3f angle_diff;
2606
primary_quat.angular_difference(ekf2_quat).to_axis_angle(angle_diff);
2607
const float yaw_diff = fabsf(angle_diff.z);
2608
if (check_yaw && (yaw_diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {
2609
set_failure_inconsistent_message("EKF2", "Yaw", yaw_diff, failure_msg, failure_msg_len);
2610
return false;
2611
}
2612
}
2613
total_ekf_cores = EKF2.activeCores();
2614
}
2615
#endif
2616
2617
#if HAL_NAVEKF3_AVAILABLE
2618
// check primary vs ekf3
2619
if (ekf_type() == EKFType::THREE || active_EKF_type() == EKFType::THREE) {
2620
for (uint8_t i = 0; i < EKF3.activeCores(); i++) {
2621
Quaternion ekf3_quat;
2622
EKF3.getQuaternionBodyToNED(i, ekf3_quat);
2623
2624
// check roll and pitch difference
2625
const float rp_diff_rad = primary_quat.roll_pitch_difference(ekf3_quat);
2626
if (rp_diff_rad > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {
2627
set_failure_inconsistent_message("EKF3", "Roll/Pitch", rp_diff_rad, failure_msg, failure_msg_len);
2628
return false;
2629
}
2630
2631
// check yaw difference
2632
Vector3f angle_diff;
2633
primary_quat.angular_difference(ekf3_quat).to_axis_angle(angle_diff);
2634
const float yaw_diff = fabsf(angle_diff.z);
2635
if (check_yaw && (yaw_diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {
2636
set_failure_inconsistent_message("EKF3", "Yaw", yaw_diff, failure_msg, failure_msg_len);
2637
return false;
2638
}
2639
}
2640
total_ekf_cores += EKF3.activeCores();
2641
}
2642
#endif
2643
2644
#if AP_AHRS_DCM_ENABLED
2645
// check primary vs dcm
2646
if (!always_use_EKF() || (total_ekf_cores == 1)) {
2647
Quaternion dcm_quat;
2648
dcm_quat.from_rotation_matrix(get_DCM_rotation_body_to_ned());
2649
2650
// check roll and pitch difference
2651
const float rp_diff_rad = primary_quat.roll_pitch_difference(dcm_quat);
2652
if (rp_diff_rad > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {
2653
set_failure_inconsistent_message("DCM", "Roll/Pitch", rp_diff_rad, failure_msg, failure_msg_len);
2654
return false;
2655
}
2656
2657
// Check vs DCM yaw if this vehicle could use DCM in flight
2658
// and if not using an external yaw source (DCM does not support external yaw sources)
2659
bool using_noncompass_for_yaw = false;
2660
#if HAL_NAVEKF3_AVAILABLE
2661
using_noncompass_for_yaw = (ekf_type() == EKFType::THREE) && EKF3.using_noncompass_for_yaw();
2662
#endif
2663
if (!always_use_EKF() && !using_noncompass_for_yaw) {
2664
Vector3f angle_diff;
2665
primary_quat.angular_difference(dcm_quat).to_axis_angle(angle_diff);
2666
const float yaw_diff = fabsf(angle_diff.z);
2667
if (check_yaw && (yaw_diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {
2668
set_failure_inconsistent_message("DCM", "Yaw", yaw_diff, failure_msg, failure_msg_len);
2669
return false;
2670
}
2671
}
2672
}
2673
#endif
2674
2675
return true;
2676
}
2677
2678
// return the amount of yaw angle change due to the last yaw angle reset in radians
2679
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
2680
uint32_t AP_AHRS::getLastYawResetAngle(float &yawAng)
2681
{
2682
switch (active_EKF_type()) {
2683
2684
#if AP_AHRS_DCM_ENABLED
2685
case EKFType::DCM:
2686
return dcm.getLastYawResetAngle(yawAng);
2687
#endif
2688
2689
#if HAL_NAVEKF2_AVAILABLE
2690
case EKFType::TWO:
2691
return EKF2.getLastYawResetAngle(yawAng);
2692
#endif
2693
2694
#if HAL_NAVEKF3_AVAILABLE
2695
case EKFType::THREE:
2696
return EKF3.getLastYawResetAngle(yawAng);
2697
#endif
2698
2699
#if AP_AHRS_SIM_ENABLED
2700
case EKFType::SIM:
2701
return sim.getLastYawResetAngle(yawAng);
2702
#endif
2703
#if AP_AHRS_EXTERNAL_ENABLED
2704
case EKFType::EXTERNAL:
2705
return external.getLastYawResetAngle(yawAng);
2706
#endif
2707
}
2708
return 0;
2709
}
2710
2711
// return the amount of NE position change in metres due to the last reset
2712
// returns the time of the last reset or 0 if no reset has ever occurred
2713
uint32_t AP_AHRS::getLastPosNorthEastReset(Vector2f &pos)
2714
{
2715
switch (active_EKF_type()) {
2716
2717
#if AP_AHRS_DCM_ENABLED
2718
case EKFType::DCM:
2719
return 0;
2720
#endif
2721
2722
#if HAL_NAVEKF2_AVAILABLE
2723
case EKFType::TWO:
2724
return EKF2.getLastPosNorthEastReset(pos);
2725
#endif
2726
2727
#if HAL_NAVEKF3_AVAILABLE
2728
case EKFType::THREE:
2729
return EKF3.getLastPosNorthEastReset(pos);
2730
#endif
2731
2732
#if AP_AHRS_SIM_ENABLED
2733
case EKFType::SIM:
2734
return sim.getLastPosNorthEastReset(pos);
2735
#endif
2736
#if AP_AHRS_EXTERNAL_ENABLED
2737
case EKFType::EXTERNAL:
2738
return 0;
2739
#endif
2740
}
2741
return 0;
2742
}
2743
2744
// return the amount of NE velocity change in metres/sec due to the last reset
2745
// returns the time of the last reset or 0 if no reset has ever occurred
2746
uint32_t AP_AHRS::getLastVelNorthEastReset(Vector2f &vel) const
2747
{
2748
switch (active_EKF_type()) {
2749
2750
#if AP_AHRS_DCM_ENABLED
2751
case EKFType::DCM:
2752
return 0;
2753
#endif
2754
2755
#if HAL_NAVEKF2_AVAILABLE
2756
case EKFType::TWO:
2757
return EKF2.getLastVelNorthEastReset(vel);
2758
#endif
2759
2760
#if HAL_NAVEKF3_AVAILABLE
2761
case EKFType::THREE:
2762
return EKF3.getLastVelNorthEastReset(vel);
2763
#endif
2764
2765
#if AP_AHRS_SIM_ENABLED
2766
case EKFType::SIM:
2767
return sim.getLastVelNorthEastReset(vel);
2768
#endif
2769
#if AP_AHRS_EXTERNAL_ENABLED
2770
case EKFType::EXTERNAL:
2771
return 0;
2772
#endif
2773
}
2774
return 0;
2775
}
2776
2777
2778
// return the amount of vertical position change due to the last reset in meters
2779
// returns the time of the last reset or 0 if no reset has ever occurred
2780
uint32_t AP_AHRS::getLastPosDownReset(float &posDelta)
2781
{
2782
switch (active_EKF_type()) {
2783
#if AP_AHRS_DCM_ENABLED
2784
case EKFType::DCM:
2785
return 0;
2786
#endif
2787
2788
#if HAL_NAVEKF2_AVAILABLE
2789
case EKFType::TWO:
2790
return EKF2.getLastPosDownReset(posDelta);
2791
#endif
2792
2793
#if HAL_NAVEKF3_AVAILABLE
2794
case EKFType::THREE:
2795
return EKF3.getLastPosDownReset(posDelta);
2796
#endif
2797
2798
#if AP_AHRS_SIM_ENABLED
2799
case EKFType::SIM:
2800
return sim.getLastPosDownReset(posDelta);
2801
#endif
2802
#if AP_AHRS_EXTERNAL_ENABLED
2803
case EKFType::EXTERNAL:
2804
return 0;
2805
#endif
2806
}
2807
return 0;
2808
}
2809
2810
// Resets the baro so that it reads zero at the current height
2811
// Resets the EKF height to zero
2812
// Adjusts the EKf origin height so that the EKF height + origin height is the same as before
2813
// Returns true if the height datum reset has been performed
2814
// If using a range finder for height no reset is performed and it returns false
2815
bool AP_AHRS::resetHeightDatum(void)
2816
{
2817
// support locked access functions to AHRS data
2818
WITH_SEMAPHORE(_rsem);
2819
2820
switch (ekf_type()) {
2821
2822
#if AP_AHRS_DCM_ENABLED
2823
case EKFType::DCM:
2824
#if HAL_NAVEKF3_AVAILABLE
2825
EKF3.resetHeightDatum();
2826
#endif
2827
#if HAL_NAVEKF2_AVAILABLE
2828
EKF2.resetHeightDatum();
2829
#endif
2830
return false;
2831
#endif
2832
2833
#if HAL_NAVEKF2_AVAILABLE
2834
case EKFType::TWO:
2835
#if HAL_NAVEKF3_AVAILABLE
2836
EKF3.resetHeightDatum();
2837
#endif
2838
return EKF2.resetHeightDatum();
2839
#endif
2840
2841
#if HAL_NAVEKF3_AVAILABLE
2842
case EKFType::THREE:
2843
#if HAL_NAVEKF2_AVAILABLE
2844
EKF2.resetHeightDatum();
2845
#endif
2846
return EKF3.resetHeightDatum();
2847
#endif
2848
2849
#if AP_AHRS_SIM_ENABLED
2850
case EKFType::SIM:
2851
return sim.resetHeightDatum();
2852
#endif
2853
#if AP_AHRS_EXTERNAL_ENABLED
2854
case EKFType::EXTERNAL:
2855
return false;
2856
#endif
2857
}
2858
return false;
2859
}
2860
2861
// send a EKF_STATUS_REPORT for configured EKF
2862
void AP_AHRS::send_ekf_status_report(GCS_MAVLINK &link) const
2863
{
2864
switch (ekf_type()) {
2865
#if AP_AHRS_DCM_ENABLED
2866
case EKFType::DCM:
2867
// send zero status report
2868
dcm.send_ekf_status_report(link);
2869
break;
2870
#endif
2871
#if AP_AHRS_SIM_ENABLED
2872
case EKFType::SIM:
2873
sim.send_ekf_status_report(link);
2874
break;
2875
#endif
2876
2877
#if AP_AHRS_EXTERNAL_ENABLED
2878
case EKFType::EXTERNAL: {
2879
external.send_ekf_status_report(link);
2880
break;
2881
}
2882
#endif
2883
2884
#if HAL_NAVEKF2_AVAILABLE
2885
case EKFType::TWO:
2886
return EKF2.send_status_report(link);
2887
#endif
2888
2889
#if HAL_NAVEKF3_AVAILABLE
2890
case EKFType::THREE:
2891
return EKF3.send_status_report(link);
2892
#endif
2893
2894
}
2895
}
2896
2897
// return origin for a specified EKF type
2898
bool AP_AHRS::_get_origin(EKFType type, Location &ret) const
2899
{
2900
switch (type) {
2901
#if AP_AHRS_DCM_ENABLED
2902
case EKFType::DCM:
2903
return dcm.get_origin(ret);
2904
#endif
2905
2906
#if HAL_NAVEKF2_AVAILABLE
2907
case EKFType::TWO:
2908
return EKF2.getOriginLLH(ret);
2909
#endif
2910
2911
#if HAL_NAVEKF3_AVAILABLE
2912
case EKFType::THREE:
2913
return EKF3.getOriginLLH(ret);
2914
#endif
2915
2916
#if AP_AHRS_SIM_ENABLED
2917
case EKFType::SIM:
2918
return sim.get_origin(ret);
2919
#endif
2920
#if AP_AHRS_EXTERNAL_ENABLED
2921
case EKFType::EXTERNAL:
2922
return external.get_origin(ret);
2923
#endif
2924
}
2925
return false;
2926
}
2927
2928
/*
2929
return origin for the configured EKF type. If we are armed and the
2930
configured EKF type cannot return an origin then return origin for
2931
the active EKF type (if available)
2932
2933
This copes with users force arming a plane that is running on DCM as
2934
the EKF has not fully initialised
2935
*/
2936
bool AP_AHRS::_get_origin(Location &ret) const
2937
{
2938
if (_get_origin(ekf_type(), ret)) {
2939
return true;
2940
}
2941
if (hal.util->get_soft_armed() && _get_origin(active_EKF_type(), ret)) {
2942
return true;
2943
}
2944
return false;
2945
}
2946
2947
bool AP_AHRS::set_home(const Location &loc)
2948
{
2949
WITH_SEMAPHORE(_rsem);
2950
// check location is valid
2951
if (loc.lat == 0 && loc.lng == 0 && loc.alt == 0) {
2952
return false;
2953
}
2954
if (!loc.check_latlng()) {
2955
return false;
2956
}
2957
// home must always be global frame at the moment as .alt is
2958
// accessed directly by the vehicles and they may not be rigorous
2959
// in checking the frame type.
2960
Location tmp = loc;
2961
if (!tmp.change_alt_frame(Location::AltFrame::ABSOLUTE)) {
2962
return false;
2963
}
2964
2965
#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && HAL_LOGGING_ENABLED
2966
if (!_home_is_set) {
2967
// record home is set
2968
AP::logger().Write_Event(LogEvent::SET_HOME);
2969
}
2970
#endif
2971
2972
_home = tmp;
2973
_home_is_set = true;
2974
2975
#if HAL_LOGGING_ENABLED
2976
Log_Write_Home_And_Origin();
2977
#endif
2978
2979
// send new home and ekf origin to GCS
2980
GCS_SEND_MESSAGE(MSG_HOME);
2981
GCS_SEND_MESSAGE(MSG_ORIGIN);
2982
2983
AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
2984
pd.home_lat = loc.lat;
2985
pd.home_lon = loc.lng;
2986
pd.home_alt_cm = loc.alt;
2987
2988
return true;
2989
}
2990
2991
/* if this was a watchdog reset then get home from backup registers */
2992
void AP_AHRS::load_watchdog_home()
2993
{
2994
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
2995
if (hal.util->was_watchdog_reset() && (pd.home_lat != 0 || pd.home_lon != 0)) {
2996
_home.lat = pd.home_lat;
2997
_home.lng = pd.home_lon;
2998
_home.set_alt_cm(pd.home_alt_cm, Location::AltFrame::ABSOLUTE);
2999
_home_is_set = true;
3000
_home_locked = true;
3001
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Restored watchdog home");
3002
}
3003
}
3004
3005
// get_hgt_ctrl_limit - get maximum height to be observed by the control loops in metres and a validity flag
3006
// this is used to limit height during optical flow navigation
3007
// it will return false when no limiting is required
3008
bool AP_AHRS::get_hgt_ctrl_limit(float& limit) const
3009
{
3010
switch (active_EKF_type()) {
3011
#if AP_AHRS_DCM_ENABLED
3012
case EKFType::DCM:
3013
// We are not using an EKF so no limiting applies
3014
return false;
3015
#endif
3016
3017
#if HAL_NAVEKF2_AVAILABLE
3018
case EKFType::TWO:
3019
return EKF2.getHeightControlLimit(limit);
3020
#endif
3021
3022
#if HAL_NAVEKF3_AVAILABLE
3023
case EKFType::THREE:
3024
return EKF3.getHeightControlLimit(limit);
3025
#endif
3026
3027
#if AP_AHRS_SIM_ENABLED
3028
case EKFType::SIM:
3029
return sim.get_hgt_ctrl_limit(limit);
3030
#endif
3031
#if AP_AHRS_EXTERNAL_ENABLED
3032
case EKFType::EXTERNAL:
3033
return false;
3034
#endif
3035
}
3036
3037
return false;
3038
}
3039
3040
// Set to true if the terrain underneath is stable enough to be used as a height reference
3041
// this is not related to terrain following
3042
void AP_AHRS::set_terrain_hgt_stable(bool stable)
3043
{
3044
// avoid repeatedly setting variable in NavEKF objects to prevent
3045
// spurious event logging
3046
switch (terrainHgtStableState) {
3047
case TriState::UNKNOWN:
3048
break;
3049
case TriState::True:
3050
if (stable) {
3051
return;
3052
}
3053
break;
3054
case TriState::False:
3055
if (!stable) {
3056
return;
3057
}
3058
break;
3059
}
3060
terrainHgtStableState = (TriState)stable;
3061
3062
#if HAL_NAVEKF2_AVAILABLE
3063
EKF2.setTerrainHgtStable(stable);
3064
#endif
3065
#if HAL_NAVEKF3_AVAILABLE
3066
EKF3.setTerrainHgtStable(stable);
3067
#endif
3068
}
3069
3070
// return the innovations for the primarily EKF
3071
// boolean false is returned if innovations are not available
3072
bool AP_AHRS::get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
3073
{
3074
switch (ekf_type()) {
3075
#if AP_AHRS_DCM_ENABLED
3076
case EKFType::DCM:
3077
// We are not using an EKF so no data
3078
return false;
3079
#endif
3080
3081
#if HAL_NAVEKF2_AVAILABLE
3082
case EKFType::TWO:
3083
// use EKF to get innovations
3084
return EKF2.getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov);
3085
#endif
3086
3087
#if HAL_NAVEKF3_AVAILABLE
3088
case EKFType::THREE:
3089
// use EKF to get innovations
3090
return EKF3.getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov);
3091
#endif
3092
3093
#if AP_AHRS_SIM_ENABLED
3094
case EKFType::SIM:
3095
return sim.get_innovations(velInnov, posInnov, magInnov, tasInnov, yawInnov);
3096
#endif
3097
3098
#if AP_AHRS_EXTERNAL_ENABLED
3099
case EKFType::EXTERNAL:
3100
return false;
3101
#endif
3102
}
3103
3104
return false;
3105
}
3106
3107
// returns true when the state estimates are significantly degraded by vibration
3108
bool AP_AHRS::is_vibration_affected() const
3109
{
3110
switch (ekf_type()) {
3111
#if HAL_NAVEKF3_AVAILABLE
3112
case EKFType::THREE:
3113
return EKF3.isVibrationAffected();
3114
#endif
3115
#if AP_AHRS_DCM_ENABLED
3116
case EKFType::DCM:
3117
#endif
3118
#if HAL_NAVEKF2_AVAILABLE
3119
case EKFType::TWO:
3120
#endif
3121
#if AP_AHRS_SIM_ENABLED
3122
case EKFType::SIM:
3123
#endif
3124
#if AP_AHRS_EXTERNAL_ENABLED
3125
case EKFType::EXTERNAL:
3126
#endif
3127
return false;
3128
}
3129
return false;
3130
}
3131
3132
// get_variances - provides the innovations normalised using the innovation variance where a value of 0
3133
// indicates prefect consistency between the measurement and the EKF solution and a value of 1 is the maximum
3134
// inconsistency that will be accepted by the filter
3135
// boolean false is returned if variances are not available
3136
bool AP_AHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const
3137
{
3138
switch (ekf_type()) {
3139
#if AP_AHRS_DCM_ENABLED
3140
case EKFType::DCM:
3141
// We are not using an EKF so no data
3142
return false;
3143
#endif
3144
3145
#if HAL_NAVEKF2_AVAILABLE
3146
case EKFType::TWO: {
3147
// use EKF to get variance
3148
Vector2f offset;
3149
return EKF2.getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
3150
}
3151
#endif
3152
3153
#if HAL_NAVEKF3_AVAILABLE
3154
case EKFType::THREE: {
3155
// use EKF to get variance
3156
Vector2f offset;
3157
return EKF3.getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
3158
}
3159
#endif
3160
3161
#if AP_AHRS_SIM_ENABLED
3162
case EKFType::SIM:
3163
return sim.get_variances(velVar, posVar, hgtVar, magVar, tasVar);
3164
#endif
3165
3166
#if AP_AHRS_EXTERNAL_ENABLED
3167
case EKFType::EXTERNAL:
3168
return external.get_variances(velVar, posVar, hgtVar, magVar, tasVar);
3169
#endif
3170
}
3171
3172
return false;
3173
}
3174
3175
// get a source's velocity innovations. source should be from 0 to 7 (see AP_NavEKF_Source::SourceXY)
3176
// returns true on success and results are placed in innovations and variances arguments
3177
bool AP_AHRS::get_vel_innovations_and_variances_for_source(uint8_t source, Vector3f &innovations, Vector3f &variances) const
3178
{
3179
switch (ekf_type()) {
3180
#if AP_AHRS_DCM_ENABLED
3181
case EKFType::DCM:
3182
// We are not using an EKF so no data
3183
return false;
3184
#endif
3185
3186
#if HAL_NAVEKF2_AVAILABLE
3187
case EKFType::TWO:
3188
// EKF2 does not support source level variances
3189
return false;
3190
#endif
3191
3192
#if HAL_NAVEKF3_AVAILABLE
3193
case EKFType::THREE:
3194
// use EKF to get variance
3195
return EKF3.getVelInnovationsAndVariancesForSource((AP_NavEKF_Source::SourceXY)source, innovations, variances);
3196
#endif
3197
3198
#if AP_AHRS_SIM_ENABLED
3199
case EKFType::SIM:
3200
// SITL does not support source level variances
3201
return false;
3202
#endif
3203
3204
#if AP_AHRS_EXTERNAL_ENABLED
3205
case EKFType::EXTERNAL:
3206
return false;
3207
#endif
3208
}
3209
3210
return false;
3211
}
3212
3213
//get the index of the active airspeed sensor, wrt the primary core
3214
uint8_t AP_AHRS::get_active_airspeed_index() const
3215
{
3216
#if AP_AIRSPEED_ENABLED
3217
const auto *airspeed = AP::airspeed();
3218
if (airspeed == nullptr) {
3219
return 0;
3220
}
3221
3222
// we only have affinity for EKF3 as of now
3223
#if HAL_NAVEKF3_AVAILABLE
3224
if (active_EKF_type() == EKFType::THREE) {
3225
uint8_t ret = EKF3.getActiveAirspeed();
3226
if (ret != UINT8_MAX && airspeed->healthy(ret) && airspeed->use(ret)) {
3227
return ret;
3228
}
3229
}
3230
#endif
3231
3232
// for the rest, let the primary airspeed sensor be used
3233
return airspeed->get_primary();
3234
#else
3235
3236
return 0;
3237
#endif // AP_AIRSPEED_ENABLED
3238
}
3239
3240
// get the index of the current primary IMU
3241
uint8_t AP_AHRS::_get_primary_IMU_index() const
3242
{
3243
int8_t imu = -1;
3244
switch (active_EKF_type()) {
3245
#if AP_AHRS_DCM_ENABLED
3246
case EKFType::DCM:
3247
break;
3248
#endif
3249
#if HAL_NAVEKF2_AVAILABLE
3250
case EKFType::TWO:
3251
// let EKF2 choose primary IMU
3252
imu = EKF2.getPrimaryCoreIMUIndex();
3253
break;
3254
#endif
3255
#if HAL_NAVEKF3_AVAILABLE
3256
case EKFType::THREE:
3257
// let EKF2 choose primary IMU
3258
imu = EKF3.getPrimaryCoreIMUIndex();
3259
break;
3260
#endif
3261
#if AP_AHRS_SIM_ENABLED
3262
case EKFType::SIM:
3263
break;
3264
#endif
3265
#if AP_AHRS_EXTERNAL_ENABLED
3266
case EKFType::EXTERNAL:
3267
break;
3268
#endif
3269
}
3270
if (imu == -1) {
3271
imu = AP::ins().get_first_usable_gyro();
3272
}
3273
return imu;
3274
}
3275
3276
// return the index of the primary core or -1 if no primary core selected
3277
int8_t AP_AHRS::_get_primary_core_index() const
3278
{
3279
switch (active_EKF_type()) {
3280
#if AP_AHRS_DCM_ENABLED
3281
case EKFType::DCM:
3282
// we have only one core
3283
return 0;
3284
#endif
3285
#if AP_AHRS_SIM_ENABLED
3286
case EKFType::SIM:
3287
// we have only one core
3288
return 0;
3289
#endif
3290
#if AP_AHRS_EXTERNAL_ENABLED
3291
case EKFType::EXTERNAL:
3292
// we have only one core
3293
return 0;
3294
#endif
3295
3296
#if HAL_NAVEKF2_AVAILABLE
3297
case EKFType::TWO:
3298
return EKF2.getPrimaryCoreIndex();
3299
#endif
3300
3301
#if HAL_NAVEKF3_AVAILABLE
3302
case EKFType::THREE:
3303
return EKF3.getPrimaryCoreIndex();
3304
#endif
3305
}
3306
3307
// we should never get here
3308
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
3309
return -1;
3310
}
3311
3312
// get the index of the current primary accelerometer sensor
3313
uint8_t AP_AHRS::_get_primary_accel_index(void) const
3314
{
3315
return _get_primary_IMU_index();
3316
}
3317
3318
// get the index of the current primary gyro sensor
3319
uint8_t AP_AHRS::_get_primary_gyro_index(void) const
3320
{
3321
return _get_primary_IMU_index();
3322
}
3323
3324
// see if EKF lane switching is possible to avoid EKF failsafe
3325
void AP_AHRS::check_lane_switch(void)
3326
{
3327
switch (active_EKF_type()) {
3328
#if AP_AHRS_DCM_ENABLED
3329
case EKFType::DCM:
3330
break;
3331
#endif
3332
3333
#if AP_AHRS_SIM_ENABLED
3334
case EKFType::SIM:
3335
break;
3336
#endif
3337
3338
#if AP_AHRS_EXTERNAL_ENABLED
3339
case EKFType::EXTERNAL:
3340
break;
3341
#endif
3342
3343
#if HAL_NAVEKF2_AVAILABLE
3344
case EKFType::TWO:
3345
EKF2.checkLaneSwitch();
3346
break;
3347
#endif
3348
3349
#if HAL_NAVEKF3_AVAILABLE
3350
case EKFType::THREE:
3351
EKF3.checkLaneSwitch();
3352
break;
3353
#endif
3354
}
3355
}
3356
3357
// request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe
3358
void AP_AHRS::request_yaw_reset(void)
3359
{
3360
switch (active_EKF_type()) {
3361
#if AP_AHRS_DCM_ENABLED
3362
case EKFType::DCM:
3363
break;
3364
#endif
3365
#if AP_AHRS_SIM_ENABLED
3366
case EKFType::SIM:
3367
break;
3368
#endif
3369
3370
#if AP_AHRS_EXTERNAL_ENABLED
3371
case EKFType::EXTERNAL:
3372
break;
3373
#endif
3374
3375
#if HAL_NAVEKF2_AVAILABLE
3376
case EKFType::TWO:
3377
EKF2.requestYawReset();
3378
break;
3379
#endif
3380
3381
#if HAL_NAVEKF3_AVAILABLE
3382
case EKFType::THREE:
3383
EKF3.requestYawReset();
3384
break;
3385
#endif
3386
}
3387
}
3388
3389
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
3390
void AP_AHRS::set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx)
3391
{
3392
#if HAL_NAVEKF3_AVAILABLE
3393
EKF3.setPosVelYawSourceSet((uint8_t)source_set_idx);
3394
#endif
3395
}
3396
3397
//returns active source set used, 0=primary, 1=secondary, 2=tertiary
3398
uint8_t AP_AHRS::get_posvelyaw_source_set() const
3399
{
3400
#if HAL_NAVEKF3_AVAILABLE
3401
return EKF3.get_active_source_set();
3402
#else
3403
return 0;
3404
#endif
3405
}
3406
3407
void AP_AHRS::Log_Write()
3408
{
3409
#if HAL_NAVEKF2_AVAILABLE
3410
EKF2.Log_Write();
3411
#endif
3412
#if HAL_NAVEKF3_AVAILABLE
3413
EKF3.Log_Write();
3414
#endif
3415
3416
Write_AHRS2();
3417
Write_POS();
3418
3419
#if AP_AHRS_SIM_ENABLED
3420
AP::sitl()->Log_Write_SIMSTATE();
3421
#endif
3422
}
3423
3424
// check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed
3425
bool AP_AHRS::using_noncompass_for_yaw(void) const
3426
{
3427
switch (active_EKF_type()) {
3428
#if HAL_NAVEKF2_AVAILABLE
3429
case EKFType::TWO:
3430
return EKF2.isExtNavUsedForYaw();
3431
#endif
3432
#if AP_AHRS_DCM_ENABLED
3433
case EKFType::DCM:
3434
#endif
3435
#if HAL_NAVEKF3_AVAILABLE
3436
case EKFType::THREE:
3437
return EKF3.using_noncompass_for_yaw();
3438
#endif
3439
#if AP_AHRS_SIM_ENABLED
3440
case EKFType::SIM:
3441
#endif
3442
#if AP_AHRS_EXTERNAL_ENABLED
3443
case EKFType::EXTERNAL:
3444
#endif
3445
return false;
3446
}
3447
// since there is no default case above, this is unreachable
3448
return false;
3449
}
3450
3451
// check if external nav is providing yaw
3452
bool AP_AHRS::using_extnav_for_yaw(void) const
3453
{
3454
switch (active_EKF_type()) {
3455
#if HAL_NAVEKF2_AVAILABLE
3456
case EKFType::TWO:
3457
return EKF2.isExtNavUsedForYaw();
3458
#endif
3459
#if AP_AHRS_DCM_ENABLED
3460
case EKFType::DCM:
3461
#endif
3462
#if HAL_NAVEKF3_AVAILABLE
3463
case EKFType::THREE:
3464
return EKF3.using_extnav_for_yaw();
3465
#endif
3466
#if AP_AHRS_SIM_ENABLED
3467
case EKFType::SIM:
3468
#endif
3469
#if AP_AHRS_EXTERNAL_ENABLED
3470
case EKFType::EXTERNAL:
3471
#endif
3472
return false;
3473
}
3474
// since there is no default case above, this is unreachable
3475
return false;
3476
}
3477
3478
// set and save the alt noise parameter value
3479
void AP_AHRS::set_alt_measurement_noise(float noise)
3480
{
3481
#if HAL_NAVEKF2_AVAILABLE
3482
EKF2.set_baro_alt_noise(noise);
3483
#endif
3484
#if HAL_NAVEKF3_AVAILABLE
3485
EKF3.set_baro_alt_noise(noise);
3486
#endif
3487
}
3488
3489
// check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed
3490
const EKFGSF_yaw *AP_AHRS::get_yaw_estimator(void) const
3491
{
3492
switch (active_EKF_type()) {
3493
#if HAL_NAVEKF2_AVAILABLE
3494
case EKFType::TWO:
3495
return EKF2.get_yawEstimator();
3496
#endif
3497
#if AP_AHRS_DCM_ENABLED
3498
case EKFType::DCM:
3499
#if HAL_NAVEKF3_AVAILABLE
3500
return EKF3.get_yawEstimator();
3501
#else
3502
return nullptr;
3503
#endif
3504
#endif
3505
#if HAL_NAVEKF3_AVAILABLE
3506
case EKFType::THREE:
3507
return EKF3.get_yawEstimator();
3508
#endif
3509
#if AP_AHRS_SIM_ENABLED
3510
case EKFType::SIM:
3511
#endif
3512
#if AP_AHRS_EXTERNAL_ENABLED
3513
case EKFType::EXTERNAL:
3514
#endif
3515
return nullptr;
3516
}
3517
// since there is no default case above, this is unreachable
3518
return nullptr;
3519
}
3520
3521
// get current location estimate
3522
bool AP_AHRS::get_location(Location &loc) const
3523
{
3524
loc = state.location;
3525
return state.location_ok;
3526
}
3527
3528
// return a wind estimation vector, in m/s; returns 0,0,0 on failure
3529
bool AP_AHRS::wind_estimate(Vector3f &wind) const
3530
{
3531
wind = state.wind_estimate;
3532
return state.wind_estimate_ok;
3533
}
3534
3535
// return an airspeed estimate if available. return true
3536
// if we have an estimate
3537
bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const
3538
{
3539
airspeed_ret = state.airspeed;
3540
return state.airspeed_ok;
3541
}
3542
3543
// return an airspeed estimate if available. return true
3544
// if we have an estimate
3545
bool AP_AHRS::airspeed_estimate(float &airspeed_ret, AP_AHRS::AirspeedEstimateType &type) const
3546
{
3547
airspeed_ret = state.airspeed;
3548
type = state.airspeed_estimate_type;
3549
return state.airspeed_ok;
3550
}
3551
3552
// return a true airspeed estimate (navigation airspeed) if
3553
// available. return true if we have an estimate
3554
bool AP_AHRS::airspeed_estimate_true(float &airspeed_ret) const
3555
{
3556
airspeed_ret = state.airspeed_true;
3557
return state.airspeed_true_ok;
3558
}
3559
3560
// return estimate of true airspeed vector in body frame in m/s
3561
// returns false if estimate is unavailable
3562
bool AP_AHRS::airspeed_vector_true(Vector3f &vec) const
3563
{
3564
vec = state.airspeed_vec;
3565
return state.airspeed_vec_ok;
3566
}
3567
3568
// return the quaternion defining the rotation from NED to XYZ (body) axes
3569
bool AP_AHRS::get_quaternion(Quaternion &quat) const
3570
{
3571
quat = state.quat;
3572
return state.quat_ok;
3573
}
3574
3575
// returns the inertial navigation origin in lat/lon/alt
3576
bool AP_AHRS::get_origin(Location &ret) const
3577
{
3578
ret = state.origin;
3579
return state.origin_ok;
3580
}
3581
3582
// return a ground velocity in meters/second, North/East/Down
3583
// order. Must only be called if have_inertial_nav() is true
3584
bool AP_AHRS::get_velocity_NED(Vector3f &vec) const
3585
{
3586
vec = state.velocity_NED;
3587
return state.velocity_NED_ok;
3588
}
3589
3590
// return location corresponding to vector relative to the
3591
// vehicle's origin
3592
bool AP_AHRS::get_location_from_origin_offset_NED(Location &loc, const Vector3p &offset_ned) const
3593
{
3594
if (!get_origin(loc)) {
3595
return false;
3596
}
3597
loc.offset(offset_ned);
3598
3599
return true;
3600
}
3601
3602
// return location corresponding to vector relative to the
3603
// vehicle's home location
3604
bool AP_AHRS::get_location_from_home_offset_NED(Location &loc, const Vector3p &offset_ned) const
3605
{
3606
if (!home_is_set()) {
3607
return false;
3608
}
3609
loc = get_home();
3610
loc.offset(offset_ned);
3611
3612
return true;
3613
}
3614
3615
/*
3616
get EAS to TAS scaling
3617
*/
3618
float AP_AHRS::get_EAS2TAS(void) const
3619
{
3620
if (is_positive(state.EAS2TAS)) {
3621
return state.EAS2TAS;
3622
}
3623
return 1.0;
3624
}
3625
3626
// get air density / sea level density - decreases as altitude climbs
3627
float AP_AHRS::get_air_density_ratio(void) const
3628
{
3629
const float eas2tas = get_EAS2TAS();
3630
return 1.0 / sq(eas2tas);
3631
}
3632
3633
// singleton instance
3634
AP_AHRS *AP_AHRS::_singleton;
3635
3636
namespace AP {
3637
3638
AP_AHRS &ahrs()
3639
{
3640
return *AP_AHRS::get_singleton();
3641
}
3642
3643
}
3644
3645
#endif // AP_AHRS_ENABLED
3646
3647