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