Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_AHRS/AP_AHRS.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415/*16* NavEKF based AHRS (Attitude Heading Reference System) interface for17* ArduPilot18*19*/2021#include "AP_AHRS_config.h"2223#if AP_AHRS_ENABLED2425#include <AP_HAL/AP_HAL.h>26#include "AP_AHRS.h"27#include "AP_AHRS_View.h"28#include <AP_BoardConfig/AP_BoardConfig.h>29#include <AP_ExternalAHRS/AP_ExternalAHRS.h>30#include <AP_Module/AP_Module.h>31#include <AP_GPS/AP_GPS.h>32#include <AP_Baro/AP_Baro.h>33#include <AP_Compass/AP_Compass.h>34#include <AP_InternalError/AP_InternalError.h>35#include <AP_Logger/AP_Logger.h>36#include <AP_Notify/AP_Notify.h>37#include <AP_Vehicle/AP_Vehicle_Type.h>38#include <GCS_MAVLink/GCS.h>39#include <AP_InertialSensor/AP_InertialSensor.h>40#include <AP_CustomRotations/AP_CustomRotations.h>41#if CONFIG_HAL_BOARD == HAL_BOARD_SITL42#include <SITL/SITL.h>43#endif44#include <AP_NavEKF3/AP_NavEKF3_feature.h>4546#define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10)47#define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20)4849#ifndef HAL_AHRS_EKF_TYPE_DEFAULT50#define HAL_AHRS_EKF_TYPE_DEFAULT 351#endif5253// table of user settable parameters54const AP_Param::GroupInfo AP_AHRS::var_info[] = {55// index 0 and 1 are for old parameters that are no longer not used5657// @Param: GPS_GAIN58// @DisplayName: AHRS GPS gain59// @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.60// @Range: 0.0 1.061// @Increment: 0.0162// @User: Advanced63AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS, gps_gain, 1.0f),6465// @Param: GPS_USE66// @DisplayName: AHRS use GPS for DCM navigation and position-down67// @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.68// @Values: 0:Disabled,1:Use GPS for DCM position,2:Use GPS for DCM position and height69// @User: Advanced70AP_GROUPINFO("GPS_USE", 3, AP_AHRS, _gps_use, float(GPSUse::Enable)),7172// @Param: YAW_P73// @DisplayName: Yaw P74// @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.75// @Range: 0.1 0.476// @Increment: 0.0177// @User: Advanced78AP_GROUPINFO("YAW_P", 4, AP_AHRS, _kp_yaw, 0.2f),7980// @Param: RP_P81// @DisplayName: AHRS RP_P82// @Description: This controls how fast the accelerometers correct the attitude83// @Range: 0.1 0.484// @Increment: 0.0185// @User: Advanced86AP_GROUPINFO("RP_P", 5, AP_AHRS, _kp, 0.2f),8788// @Param: WIND_MAX89// @DisplayName: Maximum wind90// @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.91// @Range: 0 12792// @Units: m/s93// @Increment: 194// @User: Advanced95AP_GROUPINFO("WIND_MAX", 6, AP_AHRS, _wind_max, 0.0f),9697// NOTE: 7 was BARO_USE9899// @Param: TRIM_X100// @DisplayName: AHRS Trim Roll101// @Description: Compensates for the roll angle difference between the control board and the frame. Positive values make the vehicle roll right.102// @Units: rad103// @Range: -0.1745 +0.1745104// @Increment: 0.01105// @User: Standard106107// @Param: TRIM_Y108// @DisplayName: AHRS Trim Pitch109// @Description: Compensates for the pitch angle difference between the control board and the frame. Positive values make the vehicle pitch up/back.110// @Units: rad111// @Range: -0.1745 +0.1745112// @Increment: 0.01113// @User: Standard114115// @Param: TRIM_Z116// @DisplayName: AHRS Trim Yaw117// @Description: Not Used118// @Units: rad119// @Range: -0.1745 +0.1745120// @Increment: 0.01121// @User: Advanced122AP_GROUPINFO("TRIM", 8, AP_AHRS, _trim, 0),123124// @Param: ORIENTATION125// @DisplayName: Board Orientation126// @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.127// @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 2128// @User: Advanced129AP_GROUPINFO("ORIENTATION", 9, AP_AHRS, _board_orientation, 0),130131// @Param: COMP_BETA132// @DisplayName: AHRS Velocity Complementary Filter Beta Coefficient133// @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.134// @Range: 0.001 0.5135// @Increment: 0.01136// @User: Advanced137AP_GROUPINFO("COMP_BETA", 10, AP_AHRS, beta, 0.1f),138139// @Param: GPS_MINSATS140// @DisplayName: AHRS GPS Minimum satellites141// @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.142// @Range: 0 10143// @Increment: 1144// @User: Advanced145AP_GROUPINFO("GPS_MINSATS", 11, AP_AHRS, _gps_minsats, 6),146147// NOTE: index 12 was for GPS_DELAY, but now removed, fixed delay148// of 1 was found to be the best choice149150// 13 was the old EKF_USE151152// @Param: EKF_TYPE153// @DisplayName: Use NavEKF Kalman filter for attitude and position estimation154// @Description: This controls which NavEKF Kalman filter version is used for attitude and position estimation155// @Values: 0:Disabled,2:Enable EKF2,3:Enable EKF3,11:ExternalAHRS156// @User: Advanced157AP_GROUPINFO("EKF_TYPE", 14, AP_AHRS, _ekf_type, HAL_AHRS_EKF_TYPE_DEFAULT),158159// @Param: CUSTOM_ROLL160// @DisplayName: Board orientation roll offset161// @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.162// @Range: -180 180163// @Units: deg164// @Increment: 1165// @User: Advanced166167// index 15168169// @Param: CUSTOM_PIT170// @DisplayName: Board orientation pitch offset171// @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.172// @Range: -180 180173// @Units: deg174// @Increment: 1175// @User: Advanced176177// index 16178179// @Param: CUSTOM_YAW180// @DisplayName: Board orientation yaw offset181// @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.182// @Range: -180 180183// @Units: deg184// @Increment: 1185// @User: Advanced186187// index 17188189// @Param: OPTIONS190// @DisplayName: Optional AHRS behaviour191// @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 consistency192// @Bitmask: 0:DisableDCMFallbackFW, 1:DisableDCMFallbackVTOL, 2:DontDisableAirspeedUsingEKF193// @User: Advanced194AP_GROUPINFO("OPTIONS", 18, AP_AHRS, _options, 0),195196AP_GROUPEND197};198199extern const AP_HAL::HAL& hal;200201// constructor202AP_AHRS::AP_AHRS(uint8_t flags) :203_ekf_flags(flags)204{205_singleton = this;206207// load default values from var_info table208AP_Param::setup_object_defaults(this, var_info);209210#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduSub)211// Copter and Sub force the use of EKF212_ekf_flags |= AP_AHRS::FLAG_ALWAYS_USE_EKF;213#endif214state.dcm_matrix.identity();215216// initialise the controller-to-autopilot-body trim state:217_last_trim = _trim.get();218_rotation_autopilot_body_to_vehicle_body.from_euler(_last_trim.x, _last_trim.y, _last_trim.z);219_rotation_vehicle_body_to_autopilot_body = _rotation_autopilot_body_to_vehicle_body.transposed();220}221222// init sets up INS board orientation223void AP_AHRS::init()224{225// EKF1 is no longer supported - handle case where it is selected226if (_ekf_type.get() == 1) {227AP_BoardConfig::config_error("EKF1 not available");228}229#if !HAL_NAVEKF2_AVAILABLE && HAL_NAVEKF3_AVAILABLE230if (_ekf_type.get() == 2) {231_ekf_type.set(EKFType::THREE);232EKF3.set_enable(true);233}234#elif !HAL_NAVEKF3_AVAILABLE && HAL_NAVEKF2_AVAILABLE235if (_ekf_type.get() == 3) {236_ekf_type.set(EKFType::TWO);237EKF2.set_enable(true);238}239#endif240241#if HAL_NAVEKF2_AVAILABLE && HAL_NAVEKF3_AVAILABLE242// a special case to catch users who had AHRS_EKF_TYPE=2 saved and243// updated to a version where EK2_ENABLE=0244if (_ekf_type.get() == 2 && !EKF2.get_enable() && EKF3.get_enable()) {245_ekf_type.set(EKFType::THREE);246}247#endif248249last_active_ekf_type = (EKFType)_ekf_type.get();250251// init backends252#if AP_AHRS_DCM_ENABLED253dcm.init();254#endif255#if AP_AHRS_EXTERNAL_ENABLED256external.init();257#endif258259#if AP_CUSTOMROTATIONS_ENABLED260// convert to new custom rotation261// PARAMETER_CONVERSION - Added: Nov-2021262if (_board_orientation == ROTATION_CUSTOM_OLD) {263_board_orientation.set_and_save(ROTATION_CUSTOM_1);264AP_Param::ConversionInfo info;265if (AP_Param::find_top_level_key_by_pointer(this, info.old_key)) {266info.type = AP_PARAM_FLOAT;267float rpy[3] = {};268AP_Float rpy_param;269for (info.old_group_element=15; info.old_group_element<=17; info.old_group_element++) {270if (AP_Param::find_old_parameter(&info, &rpy_param)) {271rpy[info.old_group_element-15] = rpy_param.get();272}273}274AP::custom_rotations().convert(ROTATION_CUSTOM_1, rpy[0], rpy[1], rpy[2]);275}276}277#endif // AP_CUSTOMROTATIONS_ENABLED278}279280// updates matrices responsible for rotating vectors from vehicle body281// frame to autopilot body frame from _trim variables282void AP_AHRS::update_trim_rotation_matrices()283{284if (_last_trim == _trim.get()) {285// nothing to do286return;287}288289_last_trim = _trim.get();290_rotation_autopilot_body_to_vehicle_body.from_euler(_last_trim.x, _last_trim.y, _last_trim.z);291_rotation_vehicle_body_to_autopilot_body = _rotation_autopilot_body_to_vehicle_body.transposed();292}293294// return a Quaternion representing our current attitude in NED frame295void AP_AHRS::get_quat_body_to_ned(Quaternion &quat) const296{297quat.from_rotation_matrix(get_rotation_body_to_ned());298}299300// convert a vector from body to earth frame301Vector3f AP_AHRS::body_to_earth(const Vector3f &v) const302{303return get_rotation_body_to_ned() * v;304}305306// convert a vector from earth to body frame307Vector3f AP_AHRS::earth_to_body(const Vector3f &v) const308{309return get_rotation_body_to_ned().mul_transpose(v);310}311312313// reset the current gyro drift estimate314// should be called if gyro offsets are recalculated315void AP_AHRS::reset_gyro_drift(void)316{317// support locked access functions to AHRS data318WITH_SEMAPHORE(_rsem);319320// update DCM321#if AP_AHRS_DCM_ENABLED322dcm.reset_gyro_drift();323#endif324#if AP_AHRS_EXTERNAL_ENABLED325external.reset_gyro_drift();326#endif327328// reset the EKF gyro bias states329#if HAL_NAVEKF2_AVAILABLE330EKF2.resetGyroBias();331#endif332#if HAL_NAVEKF3_AVAILABLE333EKF3.resetGyroBias();334#endif335}336337/*338update state structure after each update()339*/340void AP_AHRS::update_state(void)341{342state.primary_IMU = _get_primary_IMU_index();343state.primary_gyro = _get_primary_gyro_index();344state.primary_accel = _get_primary_accel_index();345state.primary_core = _get_primary_core_index();346state.wind_estimate_ok = _wind_estimate(state.wind_estimate);347state.EAS2TAS = AP_AHRS_Backend::get_EAS2TAS();348state.airspeed_ok = _airspeed_EAS(state.airspeed, state.airspeed_estimate_type);349state.airspeed_true_ok = _airspeed_TAS(state.airspeed_true);350state.airspeed_vec_ok = _airspeed_TAS(state.airspeed_vec);351state.quat_ok = _get_quaternion(state.quat);352state.secondary_attitude_ok = _get_secondary_attitude(state.secondary_attitude);353state.secondary_quat_ok = _get_secondary_quaternion(state.secondary_quat);354state.location_ok = _get_location(state.location);355state.secondary_pos_ok = _get_secondary_position(state.secondary_pos);356state.ground_speed_vec = _groundspeed_vector();357state.ground_speed = _groundspeed();358_getCorrectedDeltaVelocityNED(state.corrected_dv, state.corrected_dv_dt);359state.origin_ok = _get_origin(state.origin);360state.velocity_NED_ok = _get_velocity_NED(state.velocity_NED);361}362363void AP_AHRS::update(bool skip_ins_update)364{365// periodically checks to see if we should update the AHRS366// orientation (e.g. based on the AHRS_ORIENTATION parameter)367// allow for runtime change of orientation368// this makes initial config easier369update_orientation();370371if (!skip_ins_update) {372// tell the IMU to grab some data373AP::ins().update();374}375376// support locked access functions to AHRS data377WITH_SEMAPHORE(_rsem);378379// see if we have to restore home after a watchdog reset:380if (!_checked_watchdog_home) {381load_watchdog_home();382_checked_watchdog_home = true;383}384385// drop back to normal priority if we were boosted by the INS386// calling delay_microseconds_boost()387hal.scheduler->boost_end();388389// update autopilot-body-to-vehicle-body from _trim parameters:390update_trim_rotation_matrices();391392#if AP_AHRS_DCM_ENABLED393update_DCM();394#endif395396// update takeoff/touchdown flags397update_flags();398399#if AP_AHRS_SIM_ENABLED400update_SITL();401#endif402403#if AP_AHRS_EXTERNAL_ENABLED404update_external();405#endif406407if (_ekf_type == 2) {408// if EK2 is primary then run EKF2 first to give it CPU409// priority410#if HAL_NAVEKF2_AVAILABLE411update_EKF2();412#endif413#if HAL_NAVEKF3_AVAILABLE414update_EKF3();415#endif416} else {417// otherwise run EKF3 first418#if HAL_NAVEKF3_AVAILABLE419update_EKF3();420#endif421#if HAL_NAVEKF2_AVAILABLE422update_EKF2();423#endif424}425426#if AP_MODULE_SUPPORTED427// call AHRS_update hook if any428AP_Module::call_hook_AHRS_update(*this);429#endif430431// push gyros if optical flow present432if (hal.opticalflow) {433const Vector3f &exported_gyro_bias = get_gyro_drift();434hal.opticalflow->push_gyro_bias(exported_gyro_bias.x, exported_gyro_bias.y);435}436437if (_view != nullptr) {438// update optional alternative attitude view439_view->update();440}441442// update AOA and SSA443update_AOA_SSA();444445#if HAL_GCS_ENABLED446state.active_EKF = _active_EKF_type();447if (state.active_EKF != last_active_ekf_type) {448last_active_ekf_type = state.active_EKF;449const char *shortname = "???";450switch ((EKFType)state.active_EKF) {451#if AP_AHRS_DCM_ENABLED452case EKFType::DCM:453shortname = "DCM";454break;455#endif456#if AP_AHRS_SIM_ENABLED457case EKFType::SIM:458shortname = "SIM";459break;460#endif461#if AP_AHRS_EXTERNAL_ENABLED462case EKFType::EXTERNAL:463shortname = "External";464break;465#endif466#if HAL_NAVEKF3_AVAILABLE467case EKFType::THREE:468shortname = "EKF3";469break;470#endif471#if HAL_NAVEKF2_AVAILABLE472case EKFType::TWO:473shortname = "EKF2";474break;475#endif476}477GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AHRS: %s active", shortname);478}479#endif // HAL_GCS_ENABLED480481// update published state482update_state();483484#if CONFIG_HAL_BOARD == HAL_BOARD_SITL485/*486add timing jitter to simulate slow EKF response487*/488const auto *sitl = AP::sitl();489if (sitl->loop_time_jitter_us > 0) {490hal.scheduler->delay_microseconds(random() % sitl->loop_time_jitter_us);491}492#endif493}494495/*496* copy results from a backend over AP_AHRS canonical results.497* This updates member variables like roll and pitch, as well as498* updating derived values like sin_roll and sin_pitch.499*/500void AP_AHRS::copy_estimates_from_backend_estimates(const AP_AHRS_Backend::Estimates &results)501{502roll = results.roll_rad;503pitch = results.pitch_rad;504yaw = results.yaw_rad;505506state.dcm_matrix = results.dcm_matrix;507508state.gyro_estimate = results.gyro_estimate;509state.gyro_drift = results.gyro_drift;510511state.accel_ef = results.accel_ef;512state.accel_bias = results.accel_bias;513514update_cd_values();515update_trig();516}517518#if AP_AHRS_DCM_ENABLED519void AP_AHRS::update_DCM()520{521dcm.update();522dcm.get_results(dcm_estimates);523524// we always update the vehicle's canonical roll/pitch/yaw from525// DCM. In normal operation this will usually be over-written by526// an EKF or external AHRS. This is long-held behaviour, but this527// really shouldn't be doing this.528529// if (active_EKF_type() == EKFType::DCM) {530copy_estimates_from_backend_estimates(dcm_estimates);531// }532}533#endif534535#if AP_AHRS_SIM_ENABLED536void AP_AHRS::update_SITL(void)537{538sim.update();539sim.get_results(sim_estimates);540541if (_active_EKF_type() == EKFType::SIM) {542copy_estimates_from_backend_estimates(sim_estimates);543}544}545#endif546547void AP_AHRS::update_notify_from_filter_status(const nav_filter_status &status)548{549AP_Notify::flags.gps_fusion = status.flags.using_gps; // Drives AP_Notify flag for usable GPS.550AP_Notify::flags.gps_glitching = status.flags.gps_glitching;551AP_Notify::flags.have_pos_abs = status.flags.horiz_pos_abs;552}553554#if HAL_NAVEKF2_AVAILABLE555void AP_AHRS::update_EKF2(void)556{557if (!_ekf2_started) {558// wait 1 second for DCM to output a valid tilt error estimate559if (start_time_ms == 0) {560start_time_ms = AP_HAL::millis();561}562#if HAL_LOGGING_ENABLED563// if we're doing Replay logging then don't allow any data564// into the EKF yet. Don't allow it to block us for long.565if (!hal.util->was_watchdog_reset()) {566if (AP_HAL::millis() - start_time_ms < 5000) {567if (!AP::logger().allow_start_ekf()) {568return;569}570}571}572#endif573574if (AP_HAL::millis() - start_time_ms > startup_delay_ms) {575_ekf2_started = EKF2.InitialiseFilter();576}577}578if (_ekf2_started) {579EKF2.UpdateFilter();580if (_active_EKF_type() == EKFType::TWO) {581Vector3f eulers;582EKF2.getRotationBodyToNED(state.dcm_matrix);583EKF2.getEulerAngles(eulers);584roll = eulers.x;585pitch = eulers.y;586yaw = eulers.z;587588update_cd_values();589update_trig();590591// Use the primary EKF to select the primary gyro592const AP_InertialSensor &_ins = AP::ins();593const int8_t primary_imu = EKF2.getPrimaryCoreIMUIndex();594const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_first_usable_gyro();595const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_first_usable_accel();596597// get gyro bias for primary EKF and change sign to give gyro drift598// Note sign convention used by EKF is bias = measurement - truth599Vector3f drift;600EKF2.getGyroBias(drift);601state.gyro_drift = -drift;602603// use the same IMU as the primary EKF and correct for gyro drift604state.gyro_estimate = _ins.get_gyro(primary_gyro) + state.gyro_drift;605606// get z accel bias estimate from active EKF (this is usually for the primary IMU)607float &abias = state.accel_bias.z;608EKF2.getAccelZBias(abias);609610// This EKF is currently using primary_imu, and a bias applies to only that IMU611Vector3f accel = _ins.get_accel(primary_accel);612accel.z -= abias;613state.accel_ef = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel;614615nav_filter_status filt_state;616EKF2.getFilterStatus(filt_state);617update_notify_from_filter_status(filt_state);618}619620/*621if we now have an origin then set in all backends622*/623if (!done_common_origin) {624Location new_origin;625if (EKF2.getOriginLLH(new_origin)) {626done_common_origin = true;627#if HAL_NAVEKF3_AVAILABLE628EKF3.setOriginLLH(new_origin);629#endif630#if AP_AHRS_EXTERNAL_ENABLED631external.set_origin(new_origin);632#endif633}634}635}636}637#endif638639#if HAL_NAVEKF3_AVAILABLE640void AP_AHRS::update_EKF3(void)641{642if (!_ekf3_started) {643// wait 1 second for DCM to output a valid tilt error estimate644if (start_time_ms == 0) {645start_time_ms = AP_HAL::millis();646}647#if HAL_LOGGING_ENABLED648// if we're doing Replay logging then don't allow any data649// into the EKF yet. Don't allow it to block us for long.650if (!hal.util->was_watchdog_reset()) {651if (AP_HAL::millis() - start_time_ms < 5000) {652if (!AP::logger().allow_start_ekf()) {653return;654}655}656}657#endif658if (AP_HAL::millis() - start_time_ms > startup_delay_ms) {659_ekf3_started = EKF3.InitialiseFilter();660}661}662if (_ekf3_started) {663EKF3.UpdateFilter();664if (_active_EKF_type() == EKFType::THREE) {665Vector3f eulers;666EKF3.getRotationBodyToNED(state.dcm_matrix);667EKF3.getEulerAngles(eulers);668roll = eulers.x;669pitch = eulers.y;670yaw = eulers.z;671672update_cd_values();673update_trig();674675const AP_InertialSensor &_ins = AP::ins();676677// Use the primary EKF to select the primary gyro678const int8_t primary_imu = EKF3.getPrimaryCoreIMUIndex();679const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_first_usable_gyro();680const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_first_usable_accel();681682// get gyro bias for primary EKF and change sign to give gyro drift683// Note sign convention used by EKF is bias = measurement - truth684Vector3f drift;685EKF3.getGyroBias(-1, drift);686state.gyro_drift = -drift;687688// use the same IMU as the primary EKF and correct for gyro drift689state.gyro_estimate = _ins.get_gyro(primary_gyro) + state.gyro_drift;690691// get 3-axis accel bias estimates for active EKF (this is usually for the primary IMU)692Vector3f &abias = state.accel_bias;693EKF3.getAccelBias(-1,abias);694695// use the primary IMU for accel earth frame696Vector3f accel = _ins.get_accel(primary_accel);697accel -= abias;698state.accel_ef = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel;699700nav_filter_status filt_state;701EKF3.getFilterStatus(filt_state);702update_notify_from_filter_status(filt_state);703}704/*705if we now have an origin then set in all backends706*/707if (!done_common_origin) {708Location new_origin;709if (EKF3.getOriginLLH(new_origin)) {710done_common_origin = true;711#if HAL_NAVEKF2_AVAILABLE712EKF2.setOriginLLH(new_origin);713#endif714#if AP_AHRS_EXTERNAL_ENABLED715external.set_origin(new_origin);716#endif717}718}719}720}721#endif722723#if AP_AHRS_EXTERNAL_ENABLED724void AP_AHRS::update_external(void)725{726external.update();727external.get_results(external_estimates);728729if (_active_EKF_type() == EKFType::EXTERNAL) {730copy_estimates_from_backend_estimates(external_estimates);731}732733/*734if we now have an origin then set in all backends735*/736if (!done_common_origin) {737Location new_origin;738if (external.get_origin(new_origin)) {739done_common_origin = true;740#if HAL_NAVEKF2_AVAILABLE741EKF2.setOriginLLH(new_origin);742#endif743#if HAL_NAVEKF3_AVAILABLE744EKF3.setOriginLLH(new_origin);745#endif746}747}748}749#endif // AP_AHRS_EXTERNAL_ENABLED750751void AP_AHRS::reset()752{753// support locked access functions to AHRS data754WITH_SEMAPHORE(_rsem);755756#if AP_AHRS_DCM_ENABLED757dcm.reset();758#endif759#if AP_AHRS_SIM_ENABLED760sim.reset();761#endif762763#if AP_AHRS_EXTERNAL_ENABLED764external.reset();765#endif766767#if HAL_NAVEKF2_AVAILABLE768if (_ekf2_started) {769_ekf2_started = EKF2.InitialiseFilter();770}771#endif772#if HAL_NAVEKF3_AVAILABLE773if (_ekf3_started) {774_ekf3_started = EKF3.InitialiseFilter();775}776#endif777}778779// dead-reckoning support780bool AP_AHRS::_get_location(Location &loc) const781{782switch (active_EKF_type()) {783#if AP_AHRS_DCM_ENABLED784case EKFType::DCM:785return dcm_estimates.get_location(loc);786#endif787#if HAL_NAVEKF2_AVAILABLE788case EKFType::TWO:789if (EKF2.getLLH(loc)) {790return true;791}792break;793#endif794795#if HAL_NAVEKF3_AVAILABLE796case EKFType::THREE:797if (EKF3.getLLH(loc)) {798return true;799}800break;801#endif802803#if AP_AHRS_SIM_ENABLED804case EKFType::SIM:805return sim_estimates.get_location(loc);806#endif807808#if AP_AHRS_EXTERNAL_ENABLED809case EKFType::EXTERNAL:810return external_estimates.get_location(loc);811#endif812}813814#if AP_AHRS_DCM_ENABLED815// fall back to position from DCM816if (!always_use_EKF()) {817return dcm_estimates.get_location(loc);818}819#endif820821return false;822}823824// status reporting of estimated errors825float AP_AHRS::get_error_rp(void) const826{827#if AP_AHRS_DCM_ENABLED828return dcm.get_error_rp();829#endif830return 0;831}832833float AP_AHRS::get_error_yaw(void) const834{835#if AP_AHRS_DCM_ENABLED836return dcm.get_error_yaw();837#endif838return 0;839}840841// return a wind estimation vector, in m/s842bool AP_AHRS::_wind_estimate(Vector3f &wind) const843{844switch (active_EKF_type()) {845#if AP_AHRS_DCM_ENABLED846case EKFType::DCM:847return dcm.wind_estimate(wind);848#endif849850#if AP_AHRS_SIM_ENABLED851case EKFType::SIM:852return sim.wind_estimate(wind);853#endif854855#if HAL_NAVEKF2_AVAILABLE856case EKFType::TWO:857EKF2.getWind(wind);858return true;859#endif860861#if HAL_NAVEKF3_AVAILABLE862case EKFType::THREE:863return EKF3.getWind(wind);864#endif865866#if AP_AHRS_EXTERNAL_ENABLED867case EKFType::EXTERNAL:868return external.wind_estimate(wind);869#endif870}871return false;872}873874875/*876* Determine how aligned heading_deg is with the wind. Return result877* is 1.0 when perfectly aligned heading into wind, -1 when perfectly878* aligned with-wind, and zero when perfect cross-wind. There is no879* distinction between a left or right cross-wind. Wind speed is ignored880*/881float AP_AHRS::wind_alignment(const float heading_deg) const882{883Vector3f wind;884if (!wind_estimate(wind)) {885return 0;886}887const float wind_heading_rad = atan2f(-wind.y, -wind.x);888return cosf(wind_heading_rad - radians(heading_deg));889}890891/*892* returns forward head-wind component in m/s. Negative means tail-wind.893*/894float AP_AHRS::head_wind(void) const895{896const float alignment = wind_alignment(yaw_sensor*0.01f);897return alignment * wind_estimate().xy().length();898}899900/*901return true if the current AHRS airspeed estimate is directly derived from an airspeed sensor902*/903bool AP_AHRS::using_airspeed_sensor() const904{905return state.airspeed_estimate_type == AirspeedEstimateType::AIRSPEED_SENSOR;906}907908/*909Return true if a airspeed sensor should be used for the AHRS airspeed estimate910*/911bool AP_AHRS::_should_use_airspeed_sensor(uint8_t airspeed_index) const912{913if (!airspeed_sensor_enabled(airspeed_index)) {914return false;915}916nav_filter_status filter_status;917if (!option_set(Options::DISABLE_AIRSPEED_EKF_CHECK) &&918fly_forward &&919hal.util->get_soft_armed() &&920get_filter_status(filter_status) &&921(filter_status.flags.rejecting_airspeed && !filter_status.flags.dead_reckoning)) {922// special case for when backend is rejecting airspeed data in923// an armed fly_forward state and not dead reckoning. Then the924// airspeed data is highly suspect and will be rejected. We925// will use the synthetic airspeed instead926return false;927}928return true;929}930931// return an airspeed estimate if available. return true932// if we have an estimate933bool AP_AHRS::_airspeed_EAS(float &airspeed_ret, AirspeedEstimateType &airspeed_estimate_type) const934{935#if AP_AHRS_DCM_ENABLED || (AP_AIRSPEED_ENABLED && AP_GPS_ENABLED)936const uint8_t idx = get_active_airspeed_index();937#endif938#if AP_AIRSPEED_ENABLED && AP_GPS_ENABLED939if (_should_use_airspeed_sensor(idx)) {940airspeed_ret = AP::airspeed()->get_airspeed(idx);941942if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {943// constrain the airspeed by the ground speed944// and AHRS_WIND_MAX945const float gnd_speed = AP::gps().ground_speed();946float true_airspeed = airspeed_ret * get_EAS2TAS();947true_airspeed = constrain_float(true_airspeed,948gnd_speed - _wind_max,949gnd_speed + _wind_max);950airspeed_ret = true_airspeed / get_EAS2TAS();951}952airspeed_estimate_type = AirspeedEstimateType::AIRSPEED_SENSOR;953return true;954}955#endif956957if (!get_wind_estimation_enabled()) {958airspeed_estimate_type = AirspeedEstimateType::NO_NEW_ESTIMATE;959return false;960}961962// estimate it via nav velocity and wind estimates963964// get wind estimates965Vector3f wind_vel;966bool have_wind = false;967968switch (active_EKF_type()) {969#if AP_AHRS_DCM_ENABLED970case EKFType::DCM:971airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC;972return dcm.airspeed_EAS(idx, airspeed_ret);973#endif974975#if AP_AHRS_SIM_ENABLED976case EKFType::SIM:977airspeed_estimate_type = AirspeedEstimateType::SIM;978return sim.airspeed_EAS(airspeed_ret);979#endif980981#if HAL_NAVEKF2_AVAILABLE982case EKFType::TWO:983#if AP_AHRS_DCM_ENABLED984airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC;985return dcm.airspeed_EAS(idx, airspeed_ret);986#else987return false;988#endif989#endif990991#if HAL_NAVEKF3_AVAILABLE992case EKFType::THREE:993have_wind = EKF3.getWind(wind_vel);994break;995#endif996997#if AP_AHRS_EXTERNAL_ENABLED998case EKFType::EXTERNAL:999#if AP_AHRS_DCM_ENABLED1000airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC;1001return dcm.airspeed_EAS(idx, airspeed_ret);1002#else1003return false;1004#endif1005#endif1006}10071008// estimate it via nav velocity and wind estimates1009Vector3f nav_vel;1010if (have_wind && have_inertial_nav() && get_velocity_NED(nav_vel)) {1011Vector3f true_airspeed_vec = nav_vel - wind_vel;1012float true_airspeed = true_airspeed_vec.length();1013float gnd_speed = nav_vel.length();1014if (_wind_max > 0) {1015float tas_lim_lower = MAX(0.0f, (gnd_speed - _wind_max));1016float tas_lim_upper = MAX(tas_lim_lower, (gnd_speed + _wind_max));1017true_airspeed = constrain_float(true_airspeed, tas_lim_lower, tas_lim_upper);1018} else {1019true_airspeed = MAX(0.0f, true_airspeed);1020}1021airspeed_ret = true_airspeed / get_EAS2TAS();1022airspeed_estimate_type = AirspeedEstimateType::EKF3_SYNTHETIC;1023return true;1024}10251026#if AP_AHRS_DCM_ENABLED1027// fallback to DCM1028airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC;1029return dcm.airspeed_EAS(idx, airspeed_ret);1030#endif10311032return false;1033}10341035bool AP_AHRS::_airspeed_TAS(float &airspeed_ret) const1036{1037switch (active_EKF_type()) {1038#if AP_AHRS_DCM_ENABLED1039case EKFType::DCM:1040return dcm.airspeed_TAS(airspeed_ret);1041#endif1042#if HAL_NAVEKF2_AVAILABLE1043case EKFType::TWO:1044#endif1045#if HAL_NAVEKF3_AVAILABLE1046case EKFType::THREE:1047#endif1048#if AP_AHRS_SIM_ENABLED1049case EKFType::SIM:1050#endif1051#if AP_AHRS_EXTERNAL_ENABLED1052case EKFType::EXTERNAL:1053#endif1054break;1055}10561057if (!airspeed_estimate(airspeed_ret)) {1058return false;1059}1060airspeed_ret *= get_EAS2TAS();1061return true;1062}10631064// return estimate of true airspeed vector in body frame in m/s1065// returns false if estimate is unavailable1066bool AP_AHRS::_airspeed_TAS(Vector3f &vec) const1067{1068switch (active_EKF_type()) {1069#if AP_AHRS_DCM_ENABLED1070case EKFType::DCM:1071break;1072#endif1073#if HAL_NAVEKF2_AVAILABLE1074case EKFType::TWO:1075return EKF2.getAirSpdVec(vec);1076#endif10771078#if HAL_NAVEKF3_AVAILABLE1079case EKFType::THREE:1080return EKF3.getAirSpdVec(vec);1081#endif10821083#if AP_AHRS_SIM_ENABLED1084case EKFType::SIM:1085break;1086#endif10871088#if AP_AHRS_EXTERNAL_ENABLED1089case EKFType::EXTERNAL:1090break;1091#endif1092}1093return false;1094}10951096// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed1097// returns false if the data is unavailable1098bool AP_AHRS::airspeed_health_data(float &innovation, float &innovationVariance, uint32_t &age_ms) const1099{1100switch (active_EKF_type()) {1101#if AP_AHRS_DCM_ENABLED1102case EKFType::DCM:1103break;1104#endif1105#if HAL_NAVEKF2_AVAILABLE1106case EKFType::TWO:1107break;1108#endif11091110#if HAL_NAVEKF3_AVAILABLE1111case EKFType::THREE:1112return EKF3.getAirSpdHealthData(innovation, innovationVariance, age_ms);1113#endif11141115#if AP_AHRS_SIM_ENABLED1116case EKFType::SIM:1117break;1118#endif11191120#if AP_AHRS_EXTERNAL_ENABLED1121case EKFType::EXTERNAL:1122break;1123#endif1124}1125return false;1126}11271128// return a synthetic EAS estimate (one derived from sensors1129// other than an actual airspeed sensor), if available. return1130// true if we have a synthetic airspeed. ret will not be modified1131// on failure.1132bool AP_AHRS::synthetic_airspeed(float &ret) const1133{1134#if AP_AHRS_DCM_ENABLED1135return dcm.synthetic_airspeed_EAS(ret);1136#endif1137return false;1138}11391140// true if compass is being used1141bool AP_AHRS::use_compass(void)1142{1143switch (active_EKF_type()) {1144#if AP_AHRS_DCM_ENABLED1145case EKFType::DCM:1146break;1147#endif1148#if HAL_NAVEKF2_AVAILABLE1149case EKFType::TWO:1150return EKF2.use_compass();1151#endif11521153#if HAL_NAVEKF3_AVAILABLE1154case EKFType::THREE:1155return EKF3.use_compass();1156#endif11571158#if AP_AHRS_SIM_ENABLED1159case EKFType::SIM:1160return sim.use_compass();1161#endif11621163#if AP_AHRS_EXTERNAL_ENABLED1164case EKFType::EXTERNAL:1165break;1166#endif1167}1168#if AP_AHRS_DCM_ENABLED1169return dcm.use_compass();1170#endif1171return false;1172}11731174// return the quaternion defining the rotation from NED to XYZ (body) axes1175bool AP_AHRS::_get_quaternion(Quaternion &quat) const1176{1177// backends always return in autopilot XYZ frame; rotate result1178// according to trim1179switch (active_EKF_type()) {1180#if AP_AHRS_DCM_ENABLED1181case EKFType::DCM:1182if (!dcm.get_quaternion(quat)) {1183return false;1184}1185break;1186#endif1187#if HAL_NAVEKF2_AVAILABLE1188case EKFType::TWO:1189if (!_ekf2_started) {1190return false;1191}1192EKF2.getQuaternion(quat);1193break;1194#endif1195#if HAL_NAVEKF3_AVAILABLE1196case EKFType::THREE:1197if (!_ekf3_started) {1198return false;1199}1200EKF3.getQuaternion(quat);1201break;1202#endif1203#if AP_AHRS_SIM_ENABLED1204case EKFType::SIM:1205if (!sim.get_quaternion(quat)) {1206return false;1207}1208break;1209#endif1210#if AP_AHRS_EXTERNAL_ENABLED1211case EKFType::EXTERNAL:1212// we assume the external AHRS isn't trimmed with the autopilot!1213return external.get_quaternion(quat);1214#endif1215}12161217quat.rotate(-_trim.get());12181219return true;1220}12211222// return secondary attitude solution if available, as eulers in radians1223bool AP_AHRS::_get_secondary_attitude(Vector3f &eulers) const1224{1225EKFType secondary_ekf_type;1226if (!_get_secondary_EKF_type(secondary_ekf_type)) {1227return false;1228}12291230switch (secondary_ekf_type) {12311232#if AP_AHRS_DCM_ENABLED1233case EKFType::DCM:1234// DCM is secondary1235eulers[0] = dcm_estimates.roll_rad;1236eulers[1] = dcm_estimates.pitch_rad;1237eulers[2] = dcm_estimates.yaw_rad;1238return true;1239#endif12401241#if HAL_NAVEKF2_AVAILABLE1242case EKFType::TWO:1243// EKF2 is secondary1244EKF2.getEulerAngles(eulers);1245return _ekf2_started;1246#endif12471248#if HAL_NAVEKF3_AVAILABLE1249case EKFType::THREE:1250// EKF3 is secondary1251EKF3.getEulerAngles(eulers);1252return _ekf3_started;1253#endif12541255#if AP_AHRS_SIM_ENABLED1256case EKFType::SIM:1257// SITL is secondary (should never happen)1258return false;1259#endif12601261#if AP_AHRS_EXTERNAL_ENABLED1262case EKFType::EXTERNAL: {1263// External is secondary1264eulers[0] = external_estimates.roll_rad;1265eulers[1] = external_estimates.pitch_rad;1266eulers[2] = external_estimates.yaw_rad;1267return true;1268}1269#endif1270}12711272// since there is no default case above, this is unreachable1273return false;1274}127512761277// return secondary attitude solution if available, as quaternion1278bool AP_AHRS::_get_secondary_quaternion(Quaternion &quat) const1279{1280EKFType secondary_ekf_type;1281if (!_get_secondary_EKF_type(secondary_ekf_type)) {1282return false;1283}12841285switch (secondary_ekf_type) {12861287#if AP_AHRS_DCM_ENABLED1288case EKFType::DCM:1289// DCM is secondary1290if (!dcm.get_quaternion(quat)) {1291return false;1292}1293break;1294#endif12951296#if HAL_NAVEKF2_AVAILABLE1297case EKFType::TWO:1298// EKF2 is secondary1299if (!_ekf2_started) {1300return false;1301}1302EKF2.getQuaternion(quat);1303break;1304#endif13051306#if HAL_NAVEKF3_AVAILABLE1307case EKFType::THREE:1308// EKF3 is secondary1309if (!_ekf3_started) {1310return false;1311}1312EKF3.getQuaternion(quat);1313break;1314#endif13151316#if AP_AHRS_SIM_ENABLED1317case EKFType::SIM:1318// SITL is secondary (should never happen)1319return false;1320#endif13211322#if AP_AHRS_EXTERNAL_ENABLED1323case EKFType::EXTERNAL:1324// External is secondary1325return external.get_quaternion(quat);1326#endif1327}13281329quat.rotate(-_trim.get());13301331return true;1332}13331334// return secondary position solution if available1335bool AP_AHRS::_get_secondary_position(Location &loc) const1336{1337EKFType secondary_ekf_type;1338if (!_get_secondary_EKF_type(secondary_ekf_type)) {1339return false;1340}13411342switch (secondary_ekf_type) {13431344#if AP_AHRS_DCM_ENABLED1345case EKFType::DCM:1346// return DCM position1347loc = dcm_estimates.location;1348// FIXME: we intentionally do not return whether location is1349// actually valid here so we continue to send mavlink messages1350// and log data:1351return true;1352#endif13531354#if HAL_NAVEKF2_AVAILABLE1355case EKFType::TWO:1356// EKF2 is secondary1357EKF2.getLLH(loc);1358return _ekf2_started;1359#endif13601361#if HAL_NAVEKF3_AVAILABLE1362case EKFType::THREE:1363// EKF3 is secondary1364EKF3.getLLH(loc);1365return _ekf3_started;1366#endif13671368#if AP_AHRS_SIM_ENABLED1369case EKFType::SIM:1370// SITL is secondary (should never happen)1371return false;1372#endif13731374#if AP_AHRS_EXTERNAL_ENABLED1375case EKFType::EXTERNAL:1376// External is secondary1377return external_estimates.get_location(loc);1378#endif1379}13801381// since there is no default case above, this is unreachable1382return false;1383}13841385// EKF has a better ground speed vector estimate1386Vector2f AP_AHRS::_groundspeed_vector(void)1387{1388switch (active_EKF_type()) {1389#if AP_AHRS_DCM_ENABLED1390case EKFType::DCM:1391return dcm.groundspeed_vector();1392#endif13931394#if HAL_NAVEKF2_AVAILABLE1395case EKFType::TWO: {1396Vector3f vec;1397EKF2.getVelNED(vec);1398return vec.xy();1399}1400#endif14011402#if HAL_NAVEKF3_AVAILABLE1403case EKFType::THREE: {1404Vector3f vec;1405EKF3.getVelNED(vec);1406return vec.xy();1407}1408#endif14091410#if AP_AHRS_SIM_ENABLED1411case EKFType::SIM:1412return sim.groundspeed_vector();1413#endif1414#if AP_AHRS_EXTERNAL_ENABLED1415case EKFType::EXTERNAL: {1416return external.groundspeed_vector();1417}1418#endif1419}1420return Vector2f();1421}14221423float AP_AHRS::_groundspeed(void)1424{1425switch (active_EKF_type()) {1426#if AP_AHRS_DCM_ENABLED1427case EKFType::DCM:1428return dcm.groundspeed();1429#endif1430#if HAL_NAVEKF2_AVAILABLE1431case EKFType::TWO:1432#endif14331434#if HAL_NAVEKF3_AVAILABLE1435case EKFType::THREE:1436#endif14371438#if AP_AHRS_EXTERNAL_ENABLED1439case EKFType::EXTERNAL:1440#endif14411442#if AP_AHRS_SIM_ENABLED1443case EKFType::SIM:1444#endif1445break;1446}1447return groundspeed_vector().length();1448}14491450// set the EKF's origin location in 10e7 degrees. This should only1451// be called when the EKF has no absolute position reference (i.e. GPS)1452// from which to decide the origin on its own1453bool AP_AHRS::set_origin(const Location &loc)1454{1455WITH_SEMAPHORE(_rsem);1456#if HAL_NAVEKF2_AVAILABLE1457const bool ret2 = EKF2.setOriginLLH(loc);1458#endif1459#if HAL_NAVEKF3_AVAILABLE1460const bool ret3 = EKF3.setOriginLLH(loc);1461#endif1462#if AP_AHRS_EXTERNAL_ENABLED1463const bool ret_ext = external.set_origin(loc);1464#endif14651466// return success if active EKF's origin was set1467bool success = false;1468switch (active_EKF_type()) {1469#if AP_AHRS_DCM_ENABLED1470case EKFType::DCM:1471break;1472#endif14731474#if HAL_NAVEKF2_AVAILABLE1475case EKFType::TWO:1476success = ret2;1477break;1478#endif14791480#if HAL_NAVEKF3_AVAILABLE1481case EKFType::THREE:1482success = ret3;1483break;1484#endif14851486#if AP_AHRS_SIM_ENABLED1487case EKFType::SIM:1488// never allow origin set in SITL. The origin is set by the1489// simulation backend1490break;1491#endif1492#if AP_AHRS_EXTERNAL_ENABLED1493case EKFType::EXTERNAL:1494success = ret_ext;1495break;1496#endif1497}14981499if (success) {1500state.origin_ok = _get_origin(state.origin);1501#if HAL_LOGGING_ENABLED1502Log_Write_Home_And_Origin();1503#endif1504}1505return success;1506}15071508#if AP_AHRS_POSITION_RESET_ENABLED1509bool AP_AHRS::handle_external_position_estimate(const Location &loc, float pos_accuracy, uint32_t timestamp_ms)1510{1511#if HAL_NAVEKF3_AVAILABLE1512return EKF3.setLatLng(loc, pos_accuracy, timestamp_ms);1513#endif1514return false;1515}1516#endif15171518// return true if inertial navigation is active1519bool AP_AHRS::have_inertial_nav(void) const1520{1521#if AP_AHRS_DCM_ENABLED1522return active_EKF_type() != EKFType::DCM;1523#endif1524return true;1525}15261527// return a ground velocity in meters/second, North/East/Down1528// order. Must only be called if have_inertial_nav() is true1529bool AP_AHRS::_get_velocity_NED(Vector3f &vec) const1530{1531switch (active_EKF_type()) {1532#if AP_AHRS_DCM_ENABLED1533case EKFType::DCM:1534break;1535#endif1536#if HAL_NAVEKF2_AVAILABLE1537case EKFType::TWO:1538EKF2.getVelNED(vec);1539return true;1540#endif15411542#if HAL_NAVEKF3_AVAILABLE1543case EKFType::THREE:1544EKF3.getVelNED(vec);1545return true;1546#endif15471548#if AP_AHRS_SIM_ENABLED1549case EKFType::SIM:1550return sim.get_velocity_NED(vec);1551#endif1552#if AP_AHRS_EXTERNAL_ENABLED1553case EKFType::EXTERNAL:1554return external.get_velocity_NED(vec);1555#endif1556}1557#if AP_AHRS_DCM_ENABLED1558return dcm.get_velocity_NED(vec);1559#endif1560return false;1561}15621563// returns the expected NED magnetic field1564bool AP_AHRS::get_mag_field_NED(Vector3f &vec) const1565{1566switch (active_EKF_type()) {1567#if AP_AHRS_DCM_ENABLED1568case EKFType::DCM:1569return false;1570#endif1571#if HAL_NAVEKF2_AVAILABLE1572case EKFType::TWO:1573EKF2.getMagNED(vec);1574return true;1575#endif15761577#if HAL_NAVEKF3_AVAILABLE1578case EKFType::THREE:1579EKF3.getMagNED(vec);1580return true;1581#endif15821583#if AP_AHRS_SIM_ENABLED1584case EKFType::SIM:1585return false;1586#endif1587#if AP_AHRS_EXTERNAL_ENABLED1588case EKFType::EXTERNAL:1589return false;1590#endif1591}1592return false;1593}15941595// returns the estimated magnetic field offsets in body frame1596bool AP_AHRS::get_mag_field_correction(Vector3f &vec) const1597{1598switch (active_EKF_type()) {1599#if AP_AHRS_DCM_ENABLED1600case EKFType::DCM:1601return false;1602#endif1603#if HAL_NAVEKF2_AVAILABLE1604case EKFType::TWO:1605EKF2.getMagXYZ(vec);1606return true;1607#endif16081609#if HAL_NAVEKF3_AVAILABLE1610case EKFType::THREE:1611EKF3.getMagXYZ(vec);1612return true;1613#endif16141615#if AP_AHRS_SIM_ENABLED1616case EKFType::SIM:1617return false;1618#endif1619#if AP_AHRS_EXTERNAL_ENABLED1620case EKFType::EXTERNAL:1621return false;1622#endif1623}1624// since there is no default case above, this is unreachable1625return false;1626}16271628// Get a derivative of the vertical position which is kinematically consistent with the vertical position is required by some control loops.1629// 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.1630bool AP_AHRS::get_vert_pos_rate_D(float &velocity) const1631{1632switch (active_EKF_type()) {1633#if AP_AHRS_DCM_ENABLED1634case EKFType::DCM:1635return dcm.get_vert_pos_rate_D(velocity);1636#endif16371638#if HAL_NAVEKF2_AVAILABLE1639case EKFType::TWO:1640velocity = EKF2.getPosDownDerivative();1641return true;1642#endif16431644#if HAL_NAVEKF3_AVAILABLE1645case EKFType::THREE:1646velocity = EKF3.getPosDownDerivative();1647return true;1648#endif16491650#if AP_AHRS_SIM_ENABLED1651case EKFType::SIM:1652return sim.get_vert_pos_rate_D(velocity);1653#endif1654#if AP_AHRS_EXTERNAL_ENABLED1655case EKFType::EXTERNAL:1656return external.get_vert_pos_rate_D(velocity);1657#endif1658}1659// since there is no default case above, this is unreachable1660return false;1661}16621663// get latest height above ground level estimate in metres and a validity flag1664bool AP_AHRS::get_hagl(float &height) const1665{1666switch (active_EKF_type()) {1667#if AP_AHRS_DCM_ENABLED1668case EKFType::DCM:1669return false;1670#endif1671#if HAL_NAVEKF2_AVAILABLE1672case EKFType::TWO:1673return EKF2.getHAGL(height);1674#endif16751676#if HAL_NAVEKF3_AVAILABLE1677case EKFType::THREE:1678return EKF3.getHAGL(height);1679#endif16801681#if AP_AHRS_SIM_ENABLED1682case EKFType::SIM:1683return sim.get_hagl(height);1684#endif1685#if AP_AHRS_EXTERNAL_ENABLED1686case EKFType::EXTERNAL: {1687return false;1688}1689#endif1690}1691// since there is no default case above, this is unreachable1692return false;1693}16941695/*1696return a relative NED position from the origin in meters1697*/1698bool AP_AHRS::get_relative_position_NED_origin(Vector3f &vec) const1699{1700switch (active_EKF_type()) {1701#if AP_AHRS_DCM_ENABLED1702case EKFType::DCM:1703return dcm.get_relative_position_NED_origin(vec);1704#endif1705#if HAL_NAVEKF2_AVAILABLE1706case EKFType::TWO: {1707Vector2f posNE;1708float posD;1709if (EKF2.getPosNE(posNE) && EKF2.getPosD(posD)) {1710// position is valid1711vec.x = posNE.x;1712vec.y = posNE.y;1713vec.z = posD;1714return true;1715}1716return false;1717}1718#endif17191720#if HAL_NAVEKF3_AVAILABLE1721case EKFType::THREE: {1722Vector2f posNE;1723float posD;1724if (EKF3.getPosNE(posNE) && EKF3.getPosD(posD)) {1725// position is valid1726vec.x = posNE.x;1727vec.y = posNE.y;1728vec.z = posD;1729return true;1730}1731return false;1732}1733#endif17341735#if AP_AHRS_SIM_ENABLED1736case EKFType::SIM:1737return sim.get_relative_position_NED_origin(vec);1738#endif1739#if AP_AHRS_EXTERNAL_ENABLED1740case EKFType::EXTERNAL: {1741return external.get_relative_position_NED_origin(vec);1742}1743#endif1744}1745// since there is no default case above, this is unreachable1746return false;1747}17481749/*1750return a relative ground position from home in meters1751*/1752bool AP_AHRS::get_relative_position_NED_home(Vector3f &vec) const1753{1754Location loc;1755if (!_home_is_set ||1756!get_location(loc)) {1757return false;1758}1759vec = _home.get_distance_NED(loc);1760return true;1761}17621763/*1764return a relative position estimate from the origin in meters1765*/1766bool AP_AHRS::get_relative_position_NE_origin(Vector2f &posNE) const1767{1768switch (active_EKF_type()) {1769#if AP_AHRS_DCM_ENABLED1770case EKFType::DCM:1771return dcm.get_relative_position_NE_origin(posNE);1772#endif1773#if HAL_NAVEKF2_AVAILABLE1774case EKFType::TWO: {1775bool position_is_valid = EKF2.getPosNE(posNE);1776return position_is_valid;1777}1778#endif17791780#if HAL_NAVEKF3_AVAILABLE1781case EKFType::THREE: {1782bool position_is_valid = EKF3.getPosNE(posNE);1783return position_is_valid;1784}1785#endif17861787#if AP_AHRS_SIM_ENABLED1788case EKFType::SIM: {1789return sim.get_relative_position_NE_origin(posNE);1790}1791#endif1792#if AP_AHRS_EXTERNAL_ENABLED1793case EKFType::EXTERNAL:1794return external.get_relative_position_NE_origin(posNE);1795#endif1796}1797// since there is no default case above, this is unreachable1798return false;1799}18001801/*1802return a relative ground position from home in meters North/East1803*/1804bool AP_AHRS::get_relative_position_NE_home(Vector2f &posNE) const1805{1806Location loc;1807if (!_home_is_set ||1808!get_location(loc)) {1809return false;1810}18111812posNE = _home.get_distance_NE(loc);1813return true;1814}18151816// write a relative ground position estimate to the origin in meters, North/East order181718181819/*1820return a relative ground position from the origin in meters, down1821*/1822bool AP_AHRS::get_relative_position_D_origin(float &posD) const1823{1824switch (active_EKF_type()) {1825#if AP_AHRS_DCM_ENABLED1826case EKFType::DCM:1827return dcm.get_relative_position_D_origin(posD);1828#endif1829#if HAL_NAVEKF2_AVAILABLE1830case EKFType::TWO: {1831bool position_is_valid = EKF2.getPosD(posD);1832return position_is_valid;1833}1834#endif18351836#if HAL_NAVEKF3_AVAILABLE1837case EKFType::THREE: {1838bool position_is_valid = EKF3.getPosD(posD);1839return position_is_valid;1840}1841#endif18421843#if AP_AHRS_SIM_ENABLED1844case EKFType::SIM:1845return sim.get_relative_position_D_origin(posD);1846#endif1847#if AP_AHRS_EXTERNAL_ENABLED1848case EKFType::EXTERNAL:1849return external.get_relative_position_D_origin(posD);1850#endif1851}1852// since there is no default case above, this is unreachable1853return false;1854}18551856/*1857return relative position from home in meters1858*/1859void AP_AHRS::get_relative_position_D_home(float &posD) const1860{1861if (!_home_is_set) {1862// fall back to an altitude derived from barometric pressure1863// differences vs a calibrated ground pressure:1864posD = -AP::baro().get_altitude();1865return;1866}18671868Location originLLH;1869float originD;1870if (!get_relative_position_D_origin(originD) ||1871!_get_origin(originLLH)) {1872#if AP_GPS_ENABLED1873const auto &gps = AP::gps();1874if (_gps_use == GPSUse::EnableWithHeight &&1875gps.status() >= AP_GPS::GPS_OK_FIX_3D) {1876posD = (_home.alt - gps.location().alt) * 0.01;1877return;1878}1879#endif1880posD = -AP::baro().get_altitude();1881return;1882}18831884posD = originD - ((originLLH.alt - _home.alt) * 0.01f);1885return;1886}1887/*1888canonicalise _ekf_type, forcing it to be 0, 2 or 31889type 1 has been deprecated1890*/1891AP_AHRS::EKFType AP_AHRS::ekf_type(void) const1892{1893EKFType type = (EKFType)_ekf_type.get();1894switch (type) {1895#if AP_AHRS_SIM_ENABLED1896case EKFType::SIM:1897return type;1898#endif1899#if AP_AHRS_EXTERNAL_ENABLED1900case EKFType::EXTERNAL:1901return type;1902#endif1903#if HAL_NAVEKF2_AVAILABLE1904case EKFType::TWO:1905return type;1906#endif1907#if HAL_NAVEKF3_AVAILABLE1908case EKFType::THREE:1909return type;1910#endif1911#if AP_AHRS_DCM_ENABLED1912case EKFType::DCM:1913if (always_use_EKF()) {1914#if HAL_NAVEKF2_AVAILABLE1915return EKFType::TWO;1916#elif HAL_NAVEKF3_AVAILABLE1917return EKFType::THREE;1918#endif1919}1920return EKFType::DCM;1921#endif1922}1923// we can get to here if the user has mis-set AHRS_EKF_TYPE - any1924// value above 3 will get to here. TWO is returned here for no1925// better reason than "tradition".1926#if HAL_NAVEKF2_AVAILABLE1927return EKFType::TWO;1928#elif HAL_NAVEKF3_AVAILABLE1929return EKFType::THREE;1930#elif AP_AHRS_DCM_ENABLED1931return EKFType::DCM;1932#else1933#error "no default backend available"1934#endif1935}19361937AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const1938{1939EKFType ret = fallback_active_EKF_type();19401941switch (ekf_type()) {1942#if AP_AHRS_DCM_ENABLED1943case EKFType::DCM:1944return EKFType::DCM;1945#endif19461947#if HAL_NAVEKF2_AVAILABLE1948case EKFType::TWO: {1949// do we have an EKF2 yet?1950if (!_ekf2_started) {1951return fallback_active_EKF_type();1952}1953if (always_use_EKF()) {1954uint16_t ekf2_faults;1955EKF2.getFilterFaults(ekf2_faults);1956if (ekf2_faults == 0) {1957ret = EKFType::TWO;1958}1959} else if (EKF2.healthy()) {1960ret = EKFType::TWO;1961}1962break;1963}1964#endif19651966#if HAL_NAVEKF3_AVAILABLE1967case EKFType::THREE: {1968// do we have an EKF3 yet?1969if (!_ekf3_started) {1970return fallback_active_EKF_type();1971}1972if (always_use_EKF()) {1973uint16_t ekf3_faults;1974EKF3.getFilterFaults(ekf3_faults);1975if (ekf3_faults == 0) {1976ret = EKFType::THREE;1977}1978} else if (EKF3.healthy()) {1979ret = EKFType::THREE;1980}1981break;1982}1983#endif19841985#if AP_AHRS_SIM_ENABLED1986case EKFType::SIM:1987ret = EKFType::SIM;1988break;1989#endif1990#if AP_AHRS_EXTERNAL_ENABLED1991case EKFType::EXTERNAL:1992ret = EKFType::EXTERNAL;1993break;1994#endif1995}19961997#if AP_AHRS_DCM_ENABLED1998// Handle fallback for fixed wing planes (including VTOL's) and ground vehicles.1999if (_vehicle_class == VehicleClass::FIXED_WING ||2000_vehicle_class == VehicleClass::GROUND) {2001bool should_use_gps = true;2002nav_filter_status filt_state {};2003switch (ret) {2004case EKFType::DCM:2005// already using DCM2006break;2007#if HAL_NAVEKF2_AVAILABLE2008case EKFType::TWO:2009EKF2.getFilterStatus(filt_state);2010should_use_gps = EKF2.configuredToUseGPSForPosXY();2011break;2012#endif2013#if HAL_NAVEKF3_AVAILABLE2014case EKFType::THREE:2015EKF3.getFilterStatus(filt_state);2016should_use_gps = EKF3.configuredToUseGPSForPosXY();2017break;2018#endif2019#if AP_AHRS_SIM_ENABLED2020case EKFType::SIM:2021get_filter_status(filt_state);2022break;2023#endif2024#if AP_AHRS_EXTERNAL_ENABLED2025case EKFType::EXTERNAL:2026get_filter_status(filt_state);2027should_use_gps = true;2028break;2029#endif2030}20312032// Handle fallback for the case where the DCM or EKF is unable to provide attitude or height data.2033const bool can_use_dcm = dcm.yaw_source_available() || fly_forward;2034const bool can_use_ekf = filt_state.flags.attitude && filt_state.flags.vert_vel && filt_state.flags.vert_pos;2035if (!can_use_dcm && can_use_ekf) {2036// no choice - continue to use EKF2037return ret;2038} else if (!can_use_ekf) {2039// No choice - we have to use DCM2040return EKFType::DCM;2041}20422043const bool disable_dcm_fallback = fly_forward?2044option_set(Options::DISABLE_DCM_FALLBACK_FW) : option_set(Options::DISABLE_DCM_FALLBACK_VTOL);2045if (disable_dcm_fallback) {2046// don't fallback2047return ret;2048}20492050// Handle loss of global position when we still have a GPS fix2051if (hal.util->get_soft_armed() &&2052(_gps_use != GPSUse::Disable) &&2053should_use_gps &&2054AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D &&2055(!filt_state.flags.using_gps || !filt_state.flags.horiz_pos_abs)) {2056/*2057If the EKF is not fusing GPS or doesn't have a 2D fix and we have a 3D GPS lock,2058then plane and rover would prefer to use the GPS position from DCM unless the2059fallback has been inhibited by the user.2060Note: The aircraft could be dead reckoning with acceptable accuracy and rejecting a bad GPS2061Note: This is a last resort fallback and makes the navigation highly vulnerable to GPS noise.2062Note: When operating in a VTOL flight mode that actively controls height such as QHOVER,2063the EKF gives better vertical velocity and position estimates and height control characteristics.2064*/2065return EKFType::DCM;2066}20672068// Handle complete loss of navigation2069if (hal.util->get_soft_armed() && filt_state.flags.const_pos_mode) {2070/*2071Provided the EKF has been configured to use GPS, ie should_use_gps is true, then the2072key difference to the case handled above is only the absence of a GPS fix which means2073that DCM will not be able to navigate either so we are primarily concerned with2074providing an attitude, vertical position and vertical velocity estimate.2075*/2076return EKFType::DCM;2077}20782079if (!filt_state.flags.horiz_vel ||2080(!filt_state.flags.horiz_pos_abs && !filt_state.flags.horiz_pos_rel)) {2081if ((!AP::compass().use_for_yaw()) &&2082AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D &&2083AP::gps().ground_speed() < 2) {2084/*2085special handling for non-compass mode when sitting2086still. The EKF may not yet have aligned its yaw. We2087accept EKF as healthy to allow arming. Once we reach2088speed the EKF should get yaw alignment2089*/2090if (filt_state.flags.gps_quality_good) {2091return ret;2092}2093}2094return EKFType::DCM;2095}2096}2097#endif20982099return ret;2100}21012102AP_AHRS::EKFType AP_AHRS::fallback_active_EKF_type(void) const2103{2104#if AP_AHRS_DCM_ENABLED2105return EKFType::DCM;2106#endif21072108#if HAL_NAVEKF3_AVAILABLE2109if (_ekf3_started) {2110return EKFType::THREE;2111}2112#endif21132114#if HAL_NAVEKF2_AVAILABLE2115if (_ekf2_started) {2116return EKFType::TWO;2117}2118#endif21192120#if AP_AHRS_EXTERNAL_ENABLED2121if (external.healthy()) {2122return EKFType::EXTERNAL;2123}2124#endif21252126// so nobody is ready yet. Return something, even if it is not ready:2127#if HAL_NAVEKF3_AVAILABLE2128return EKFType::THREE;2129#elif HAL_NAVEKF2_AVAILABLE2130return EKFType::TWO;2131#elif AP_AHRS_EXTERNAL_ENABLED2132return EKFType::EXTERNAL;2133#endif2134}21352136// get secondary EKF type. returns false if no secondary (i.e. only using DCM)2137bool AP_AHRS::_get_secondary_EKF_type(EKFType &secondary_ekf_type) const2138{21392140switch (active_EKF_type()) {2141#if AP_AHRS_DCM_ENABLED2142case EKFType::DCM:2143// EKF2, EKF3 or External is secondary2144#if HAL_NAVEKF3_AVAILABLE2145if ((EKFType)_ekf_type.get() == EKFType::THREE) {2146secondary_ekf_type = EKFType::THREE;2147return true;2148}2149#endif2150#if HAL_NAVEKF2_AVAILABLE2151if ((EKFType)_ekf_type.get() == EKFType::TWO) {2152secondary_ekf_type = EKFType::TWO;2153return true;2154}2155#endif2156#if AP_AHRS_EXTERNAL_ENABLED2157if ((EKFType)_ekf_type.get() == EKFType::EXTERNAL) {2158secondary_ekf_type = EKFType::EXTERNAL;2159return true;2160}2161#endif2162return false;2163#endif2164#if HAL_NAVEKF2_AVAILABLE2165case EKFType::TWO:2166#endif2167#if HAL_NAVEKF3_AVAILABLE2168case EKFType::THREE:2169#endif2170#if AP_AHRS_SIM_ENABLED2171case EKFType::SIM:2172#endif2173#if AP_AHRS_EXTERNAL_ENABLED2174case EKFType::EXTERNAL:2175#endif2176// DCM is secondary2177secondary_ekf_type = fallback_active_EKF_type();2178return true;2179}21802181// since there is no default case above, this is unreachable2182return false;2183}21842185/*2186check if the AHRS subsystem is healthy2187*/2188bool AP_AHRS::healthy(void) const2189{2190// If EKF is started we switch away if it reports unhealthy. This could be due to bad2191// sensor data. If EKF reversion is inhibited, we only switch across if the EKF encounters2192// an internal processing error, but not for bad sensor data.2193switch (ekf_type()) {21942195#if AP_AHRS_DCM_ENABLED2196case EKFType::DCM:2197return dcm.healthy();2198#endif21992200#if HAL_NAVEKF2_AVAILABLE2201case EKFType::TWO: {2202bool ret = _ekf2_started && EKF2.healthy();2203if (!ret) {2204return false;2205}2206if ((_vehicle_class == VehicleClass::FIXED_WING ||2207_vehicle_class == VehicleClass::GROUND) &&2208active_EKF_type() != EKFType::TWO) {2209// on fixed wing we want to be using EKF to be considered2210// healthy if EKF is enabled2211return false;2212}2213return true;2214}2215#endif22162217#if HAL_NAVEKF3_AVAILABLE2218case EKFType::THREE: {2219bool ret = _ekf3_started && EKF3.healthy();2220if (!ret) {2221return false;2222}2223if ((_vehicle_class == VehicleClass::FIXED_WING ||2224_vehicle_class == VehicleClass::GROUND) &&2225active_EKF_type() != EKFType::THREE) {2226// on fixed wing we want to be using EKF to be considered2227// healthy if EKF is enabled2228return false;2229}2230return true;2231}2232#endif22332234#if AP_AHRS_SIM_ENABLED2235case EKFType::SIM:2236return sim.healthy();2237#endif2238#if AP_AHRS_EXTERNAL_ENABLED2239case EKFType::EXTERNAL:2240return external.healthy();2241#endif2242}22432244return false;2245}22462247// returns false if we fail arming checks, in which case the buffer will be populated with a failure message2248// requires_position should be true if horizontal position configuration should be checked2249bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const2250{2251bool ret = true;2252if (!healthy()) {2253// this rather generic failure might be overwritten by2254// something more specific in the "backend"2255hal.util->snprintf(failure_msg, failure_msg_len, "Not healthy");2256ret = false;2257}22582259#if AP_AHRS_EXTERNAL_ENABLED2260// Always check external AHRS if enabled2261// it is a source for IMU data even if not being used as direct AHRS replacement2262if (AP::externalAHRS().enabled() || (ekf_type() == EKFType::EXTERNAL)) {2263if (!AP::externalAHRS().pre_arm_check(failure_msg, failure_msg_len)) {2264return false;2265}2266}2267#endif22682269if (!attitudes_consistent(failure_msg, failure_msg_len)) {2270return false;2271}22722273// ensure we're using the configured backend, but bypass in compass-less cases:2274if (ekf_type() != active_EKF_type() && AP::compass().use_for_yaw()) {2275hal.util->snprintf(failure_msg, failure_msg_len, "not using configured AHRS type");2276return false;2277}22782279switch (ekf_type()) {2280#if AP_AHRS_SIM_ENABLED2281case EKFType::SIM:2282return ret;2283#endif22842285#if AP_AHRS_DCM_ENABLED2286case EKFType::DCM:2287return dcm.pre_arm_check(requires_position, failure_msg, failure_msg_len) && ret;2288#endif22892290#if AP_AHRS_EXTERNAL_ENABLED2291case EKFType::EXTERNAL:2292return external.pre_arm_check(requires_position, failure_msg, failure_msg_len);2293#endif22942295#if HAL_NAVEKF2_AVAILABLE2296case EKFType::TWO:2297if (!_ekf2_started) {2298hal.util->snprintf(failure_msg, failure_msg_len, "EKF2 not started");2299return false;2300}2301return EKF2.pre_arm_check(failure_msg, failure_msg_len) && ret;2302#endif23032304#if HAL_NAVEKF3_AVAILABLE2305case EKFType::THREE:2306if (!_ekf3_started) {2307hal.util->snprintf(failure_msg, failure_msg_len, "EKF3 not started");2308return false;2309}2310return EKF3.pre_arm_check(requires_position, failure_msg, failure_msg_len) && ret;2311#endif2312}23132314// if we get here then ekf type is invalid2315hal.util->snprintf(failure_msg, failure_msg_len, "invalid EKF type");2316return false;2317}23182319// true if the AHRS has completed initialisation2320bool AP_AHRS::initialised(void) const2321{2322switch (ekf_type()) {2323#if AP_AHRS_DCM_ENABLED2324case EKFType::DCM:2325return true;2326#endif23272328#if HAL_NAVEKF2_AVAILABLE2329case EKFType::TWO:2330// initialisation complete 10sec after ekf has started2331return (_ekf2_started && (AP_HAL::millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));2332#endif23332334#if HAL_NAVEKF3_AVAILABLE2335case EKFType::THREE:2336// initialisation complete 10sec after ekf has started2337return (_ekf3_started && (AP_HAL::millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));2338#endif23392340#if AP_AHRS_SIM_ENABLED2341case EKFType::SIM:2342return true;2343#endif2344#if AP_AHRS_EXTERNAL_ENABLED2345case EKFType::EXTERNAL:2346return external.initialised();2347#endif2348}2349return false;2350};23512352// get_filter_status : returns filter status as a series of flags2353bool AP_AHRS::get_filter_status(nav_filter_status &status) const2354{2355switch (ekf_type()) {2356#if AP_AHRS_DCM_ENABLED2357case EKFType::DCM:2358return dcm.get_filter_status(status);2359#endif23602361#if HAL_NAVEKF2_AVAILABLE2362case EKFType::TWO:2363EKF2.getFilterStatus(status);2364return true;2365#endif23662367#if HAL_NAVEKF3_AVAILABLE2368case EKFType::THREE:2369EKF3.getFilterStatus(status);2370return true;2371#endif23722373#if AP_AHRS_SIM_ENABLED2374case EKFType::SIM:2375return sim.get_filter_status(status);2376#endif2377#if AP_AHRS_EXTERNAL_ENABLED2378case EKFType::EXTERNAL:2379return external.get_filter_status(status);2380#endif2381}23822383return false;2384}23852386// write optical flow data to EKF2387void AP_AHRS::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset, float heightOverride)2388{2389#if HAL_NAVEKF2_AVAILABLE2390EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);2391#endif2392#if EK3_FEATURE_OPTFLOW_FUSION2393EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);2394#endif2395}23962397// retrieve latest corrected optical flow samples (used for calibration)2398bool AP_AHRS::getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const2399{2400#if EK3_FEATURE_OPTFLOW_FUSION2401return EKF3.getOptFlowSample(timeStamp_ms, flowRate, bodyRate, losPred);2402#endif2403return false;2404}24052406// write body frame odometry measurements to the EKF2407void AP_AHRS::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset)2408{2409#if HAL_NAVEKF3_AVAILABLE2410EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, delay_ms, posOffset);2411#endif2412}24132414// Write position and quaternion data from an external navigation system2415void 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)2416{2417#if HAL_NAVEKF2_AVAILABLE2418EKF2.writeExtNavData(pos, quat, posErr, angErr, timeStamp_ms, delay_ms, resetTime_ms);2419#endif2420#if HAL_NAVEKF3_AVAILABLE2421EKF3.writeExtNavData(pos, quat, posErr, angErr, timeStamp_ms, delay_ms, resetTime_ms);2422#endif2423}24242425// 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.2426void AP_AHRS::writeDefaultAirSpeed(float airspeed, float uncertainty)2427{2428#if HAL_NAVEKF2_AVAILABLE2429EKF2.writeDefaultAirSpeed(airspeed);2430#endif2431#if HAL_NAVEKF3_AVAILABLE2432EKF3.writeDefaultAirSpeed(airspeed, uncertainty);2433#endif2434}24352436// Write velocity data from an external navigation system2437void AP_AHRS::writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms)2438{2439#if HAL_NAVEKF2_AVAILABLE2440EKF2.writeExtNavVelData(vel, err, timeStamp_ms, delay_ms);2441#endif2442#if HAL_NAVEKF3_AVAILABLE2443EKF3.writeExtNavVelData(vel, err, timeStamp_ms, delay_ms);2444#endif2445}24462447// get speed limit and XY navigation gain scale factor2448void AP_AHRS::getControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const2449{2450switch (active_EKF_type()) {2451#if AP_AHRS_DCM_ENABLED2452case EKFType::DCM:2453dcm.get_control_limits(ekfGndSpdLimit, ekfNavVelGainScaler);2454break;2455#endif24562457#if HAL_NAVEKF2_AVAILABLE2458case EKFType::TWO:2459EKF2.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);2460break;2461#endif24622463#if HAL_NAVEKF3_AVAILABLE2464case EKFType::THREE:2465EKF3.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);2466break;2467#endif24682469#if AP_AHRS_SIM_ENABLED2470case EKFType::SIM:2471sim.get_control_limits(ekfGndSpdLimit, ekfNavVelGainScaler);2472break;2473#endif2474#if AP_AHRS_EXTERNAL_ENABLED2475case EKFType::EXTERNAL:2476// no limit on gains, large vel limit2477ekfGndSpdLimit = 400;2478ekfNavVelGainScaler = 1;2479break;2480#endif2481}2482}24832484/*2485get gain factor for Z controllers2486*/2487float AP_AHRS::getControlScaleZ(void) const2488{2489#if AP_AHRS_DCM_ENABLED2490if (active_EKF_type() == EKFType::DCM) {2491// when flying on DCM lower gains by 4x to cope with the high2492// lag2493return 0.25;2494}2495#endif2496return 1;2497}24982499// get compass offset estimates2500// true if offsets are valid2501bool AP_AHRS::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const2502{2503switch (ekf_type()) {2504#if AP_AHRS_DCM_ENABLED2505case EKFType::DCM:2506return false;2507#endif2508#if HAL_NAVEKF2_AVAILABLE2509case EKFType::TWO:2510return EKF2.getMagOffsets(mag_idx, magOffsets);2511#endif25122513#if HAL_NAVEKF3_AVAILABLE2514case EKFType::THREE:2515return EKF3.getMagOffsets(mag_idx, magOffsets);2516#endif25172518#if AP_AHRS_SIM_ENABLED2519case EKFType::SIM:2520magOffsets.zero();2521return true;2522#endif2523#if AP_AHRS_EXTERNAL_ENABLED2524case EKFType::EXTERNAL:2525return false;2526#endif2527}2528// since there is no default case above, this is unreachable2529return false;2530}25312532// Retrieves the NED delta velocity corrected2533void AP_AHRS::_getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const2534{2535int8_t imu_idx = -1;2536Vector3f accel_bias;2537switch (active_EKF_type()) {2538#if AP_AHRS_DCM_ENABLED2539case EKFType::DCM:2540break;2541#endif2542#if HAL_NAVEKF2_AVAILABLE2543case EKFType::TWO:2544imu_idx = EKF2.getPrimaryCoreIMUIndex();2545EKF2.getAccelZBias(accel_bias.z);2546break;2547#endif2548#if HAL_NAVEKF3_AVAILABLE2549case EKFType::THREE:2550imu_idx = EKF3.getPrimaryCoreIMUIndex();2551EKF3.getAccelBias(-1,accel_bias);2552break;2553#endif2554#if AP_AHRS_SIM_ENABLED2555case EKFType::SIM:2556break;2557#endif2558#if AP_AHRS_EXTERNAL_ENABLED2559case EKFType::EXTERNAL:2560break;2561#endif2562}2563ret.zero();2564if (imu_idx == -1) {2565AP::ins().get_delta_velocity(ret, dt);2566return;2567}2568AP::ins().get_delta_velocity((uint8_t)imu_idx, ret, dt);2569ret -= accel_bias*dt;2570ret = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * ret;2571ret.z += GRAVITY_MSS*dt;2572}25732574void AP_AHRS::set_failure_inconsistent_message(const char *estimator, const char *axis, float diff_rad, char *failure_msg, const uint8_t failure_msg_len) const2575{2576hal.util->snprintf(failure_msg, failure_msg_len, "%s %s inconsistent %d deg. Wait or reboot", estimator, axis, (int)degrees(diff_rad));2577}25782579// check all cores providing consistent attitudes for prearm checks2580bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const2581{2582// get primary attitude source's attitude as quaternion2583Quaternion primary_quat;2584get_quat_body_to_ned(primary_quat);2585// only check yaw if compasses are being used2586const bool check_yaw = AP::compass().use_for_yaw();2587uint8_t total_ekf_cores = 0;25882589#if HAL_NAVEKF2_AVAILABLE2590// check primary vs ekf22591if (ekf_type() == EKFType::TWO || active_EKF_type() == EKFType::TWO) {2592for (uint8_t i = 0; i < EKF2.activeCores(); i++) {2593Quaternion ekf2_quat;2594EKF2.getQuaternionBodyToNED(i, ekf2_quat);25952596// check roll and pitch difference2597const float rp_diff_rad = primary_quat.roll_pitch_difference(ekf2_quat);2598if (rp_diff_rad > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {2599set_failure_inconsistent_message("EKF2", "Roll/Pitch", rp_diff_rad, failure_msg, failure_msg_len);2600return false;2601}26022603// check yaw difference2604Vector3f angle_diff;2605primary_quat.angular_difference(ekf2_quat).to_axis_angle(angle_diff);2606const float yaw_diff = fabsf(angle_diff.z);2607if (check_yaw && (yaw_diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {2608set_failure_inconsistent_message("EKF2", "Yaw", yaw_diff, failure_msg, failure_msg_len);2609return false;2610}2611}2612total_ekf_cores = EKF2.activeCores();2613}2614#endif26152616#if HAL_NAVEKF3_AVAILABLE2617// check primary vs ekf32618if (ekf_type() == EKFType::THREE || active_EKF_type() == EKFType::THREE) {2619for (uint8_t i = 0; i < EKF3.activeCores(); i++) {2620Quaternion ekf3_quat;2621EKF3.getQuaternionBodyToNED(i, ekf3_quat);26222623// check roll and pitch difference2624const float rp_diff_rad = primary_quat.roll_pitch_difference(ekf3_quat);2625if (rp_diff_rad > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {2626set_failure_inconsistent_message("EKF3", "Roll/Pitch", rp_diff_rad, failure_msg, failure_msg_len);2627return false;2628}26292630// check yaw difference2631Vector3f angle_diff;2632primary_quat.angular_difference(ekf3_quat).to_axis_angle(angle_diff);2633const float yaw_diff = fabsf(angle_diff.z);2634if (check_yaw && (yaw_diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {2635set_failure_inconsistent_message("EKF3", "Yaw", yaw_diff, failure_msg, failure_msg_len);2636return false;2637}2638}2639total_ekf_cores += EKF3.activeCores();2640}2641#endif26422643#if AP_AHRS_DCM_ENABLED2644// check primary vs dcm2645if (!always_use_EKF() || (total_ekf_cores == 1)) {2646Quaternion dcm_quat;2647dcm_quat.from_rotation_matrix(get_DCM_rotation_body_to_ned());26482649// check roll and pitch difference2650const float rp_diff_rad = primary_quat.roll_pitch_difference(dcm_quat);2651if (rp_diff_rad > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {2652set_failure_inconsistent_message("DCM", "Roll/Pitch", rp_diff_rad, failure_msg, failure_msg_len);2653return false;2654}26552656// Check vs DCM yaw if this vehicle could use DCM in flight2657// and if not using an external yaw source (DCM does not support external yaw sources)2658bool using_noncompass_for_yaw = false;2659#if HAL_NAVEKF3_AVAILABLE2660using_noncompass_for_yaw = (ekf_type() == EKFType::THREE) && EKF3.using_noncompass_for_yaw();2661#endif2662if (!always_use_EKF() && !using_noncompass_for_yaw) {2663Vector3f angle_diff;2664primary_quat.angular_difference(dcm_quat).to_axis_angle(angle_diff);2665const float yaw_diff = fabsf(angle_diff.z);2666if (check_yaw && (yaw_diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {2667set_failure_inconsistent_message("DCM", "Yaw", yaw_diff, failure_msg, failure_msg_len);2668return false;2669}2670}2671}2672#endif26732674return true;2675}26762677// return the amount of yaw angle change due to the last yaw angle reset in radians2678// returns the time of the last yaw angle reset or 0 if no reset has ever occurred2679uint32_t AP_AHRS::getLastYawResetAngle(float &yawAng)2680{2681switch (active_EKF_type()) {26822683#if AP_AHRS_DCM_ENABLED2684case EKFType::DCM:2685return dcm.getLastYawResetAngle(yawAng);2686#endif26872688#if HAL_NAVEKF2_AVAILABLE2689case EKFType::TWO:2690return EKF2.getLastYawResetAngle(yawAng);2691#endif26922693#if HAL_NAVEKF3_AVAILABLE2694case EKFType::THREE:2695return EKF3.getLastYawResetAngle(yawAng);2696#endif26972698#if AP_AHRS_SIM_ENABLED2699case EKFType::SIM:2700return sim.getLastYawResetAngle(yawAng);2701#endif2702#if AP_AHRS_EXTERNAL_ENABLED2703case EKFType::EXTERNAL:2704return external.getLastYawResetAngle(yawAng);2705#endif2706}2707return 0;2708}27092710// return the amount of NE position change in metres due to the last reset2711// returns the time of the last reset or 0 if no reset has ever occurred2712uint32_t AP_AHRS::getLastPosNorthEastReset(Vector2f &pos)2713{2714switch (active_EKF_type()) {27152716#if AP_AHRS_DCM_ENABLED2717case EKFType::DCM:2718return 0;2719#endif27202721#if HAL_NAVEKF2_AVAILABLE2722case EKFType::TWO:2723return EKF2.getLastPosNorthEastReset(pos);2724#endif27252726#if HAL_NAVEKF3_AVAILABLE2727case EKFType::THREE:2728return EKF3.getLastPosNorthEastReset(pos);2729#endif27302731#if AP_AHRS_SIM_ENABLED2732case EKFType::SIM:2733return sim.getLastPosNorthEastReset(pos);2734#endif2735#if AP_AHRS_EXTERNAL_ENABLED2736case EKFType::EXTERNAL:2737return 0;2738#endif2739}2740return 0;2741}27422743// return the amount of NE velocity change in metres/sec due to the last reset2744// returns the time of the last reset or 0 if no reset has ever occurred2745uint32_t AP_AHRS::getLastVelNorthEastReset(Vector2f &vel) const2746{2747switch (active_EKF_type()) {27482749#if AP_AHRS_DCM_ENABLED2750case EKFType::DCM:2751return 0;2752#endif27532754#if HAL_NAVEKF2_AVAILABLE2755case EKFType::TWO:2756return EKF2.getLastVelNorthEastReset(vel);2757#endif27582759#if HAL_NAVEKF3_AVAILABLE2760case EKFType::THREE:2761return EKF3.getLastVelNorthEastReset(vel);2762#endif27632764#if AP_AHRS_SIM_ENABLED2765case EKFType::SIM:2766return sim.getLastVelNorthEastReset(vel);2767#endif2768#if AP_AHRS_EXTERNAL_ENABLED2769case EKFType::EXTERNAL:2770return 0;2771#endif2772}2773return 0;2774}277527762777// return the amount of vertical position change due to the last reset in meters2778// returns the time of the last reset or 0 if no reset has ever occurred2779uint32_t AP_AHRS::getLastPosDownReset(float &posDelta)2780{2781switch (active_EKF_type()) {2782#if AP_AHRS_DCM_ENABLED2783case EKFType::DCM:2784return 0;2785#endif27862787#if HAL_NAVEKF2_AVAILABLE2788case EKFType::TWO:2789return EKF2.getLastPosDownReset(posDelta);2790#endif27912792#if HAL_NAVEKF3_AVAILABLE2793case EKFType::THREE:2794return EKF3.getLastPosDownReset(posDelta);2795#endif27962797#if AP_AHRS_SIM_ENABLED2798case EKFType::SIM:2799return sim.getLastPosDownReset(posDelta);2800#endif2801#if AP_AHRS_EXTERNAL_ENABLED2802case EKFType::EXTERNAL:2803return 0;2804#endif2805}2806return 0;2807}28082809// Resets the baro so that it reads zero at the current height2810// Resets the EKF height to zero2811// Adjusts the EKf origin height so that the EKF height + origin height is the same as before2812// Returns true if the height datum reset has been performed2813// If using a range finder for height no reset is performed and it returns false2814bool AP_AHRS::resetHeightDatum(void)2815{2816// support locked access functions to AHRS data2817WITH_SEMAPHORE(_rsem);28182819switch (ekf_type()) {28202821#if AP_AHRS_DCM_ENABLED2822case EKFType::DCM:2823#if HAL_NAVEKF3_AVAILABLE2824EKF3.resetHeightDatum();2825#endif2826#if HAL_NAVEKF2_AVAILABLE2827EKF2.resetHeightDatum();2828#endif2829return false;2830#endif28312832#if HAL_NAVEKF2_AVAILABLE2833case EKFType::TWO:2834#if HAL_NAVEKF3_AVAILABLE2835EKF3.resetHeightDatum();2836#endif2837return EKF2.resetHeightDatum();2838#endif28392840#if HAL_NAVEKF3_AVAILABLE2841case EKFType::THREE:2842#if HAL_NAVEKF2_AVAILABLE2843EKF2.resetHeightDatum();2844#endif2845return EKF3.resetHeightDatum();2846#endif28472848#if AP_AHRS_SIM_ENABLED2849case EKFType::SIM:2850return sim.resetHeightDatum();2851#endif2852#if AP_AHRS_EXTERNAL_ENABLED2853case EKFType::EXTERNAL:2854return false;2855#endif2856}2857return false;2858}28592860// send a EKF_STATUS_REPORT for configured EKF2861void AP_AHRS::send_ekf_status_report(GCS_MAVLINK &link) const2862{2863switch (ekf_type()) {2864#if AP_AHRS_DCM_ENABLED2865case EKFType::DCM:2866// send zero status report2867dcm.send_ekf_status_report(link);2868break;2869#endif2870#if AP_AHRS_SIM_ENABLED2871case EKFType::SIM:2872sim.send_ekf_status_report(link);2873break;2874#endif28752876#if AP_AHRS_EXTERNAL_ENABLED2877case EKFType::EXTERNAL: {2878external.send_ekf_status_report(link);2879break;2880}2881#endif28822883#if HAL_NAVEKF2_AVAILABLE2884case EKFType::TWO:2885return EKF2.send_status_report(link);2886#endif28872888#if HAL_NAVEKF3_AVAILABLE2889case EKFType::THREE:2890return EKF3.send_status_report(link);2891#endif28922893}2894}28952896// return origin for a specified EKF type2897bool AP_AHRS::_get_origin(EKFType type, Location &ret) const2898{2899switch (type) {2900#if AP_AHRS_DCM_ENABLED2901case EKFType::DCM:2902return dcm.get_origin(ret);2903#endif29042905#if HAL_NAVEKF2_AVAILABLE2906case EKFType::TWO:2907return EKF2.getOriginLLH(ret);2908#endif29092910#if HAL_NAVEKF3_AVAILABLE2911case EKFType::THREE:2912return EKF3.getOriginLLH(ret);2913#endif29142915#if AP_AHRS_SIM_ENABLED2916case EKFType::SIM:2917return sim.get_origin(ret);2918#endif2919#if AP_AHRS_EXTERNAL_ENABLED2920case EKFType::EXTERNAL:2921return external.get_origin(ret);2922#endif2923}2924return false;2925}29262927/*2928return origin for the configured EKF type. If we are armed and the2929configured EKF type cannot return an origin then return origin for2930the active EKF type (if available)29312932This copes with users force arming a plane that is running on DCM as2933the EKF has not fully initialised2934*/2935bool AP_AHRS::_get_origin(Location &ret) const2936{2937if (_get_origin(ekf_type(), ret)) {2938return true;2939}2940if (hal.util->get_soft_armed() && _get_origin(active_EKF_type(), ret)) {2941return true;2942}2943return false;2944}29452946bool AP_AHRS::set_home(const Location &loc)2947{2948WITH_SEMAPHORE(_rsem);2949// check location is valid2950if (loc.lat == 0 && loc.lng == 0 && loc.alt == 0) {2951return false;2952}2953if (!loc.check_latlng()) {2954return false;2955}2956// home must always be global frame at the moment as .alt is2957// accessed directly by the vehicles and they may not be rigorous2958// in checking the frame type.2959Location tmp = loc;2960if (!tmp.change_alt_frame(Location::AltFrame::ABSOLUTE)) {2961return false;2962}29632964#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && HAL_LOGGING_ENABLED2965if (!_home_is_set) {2966// record home is set2967AP::logger().Write_Event(LogEvent::SET_HOME);2968}2969#endif29702971_home = tmp;2972_home_is_set = true;29732974#if HAL_LOGGING_ENABLED2975Log_Write_Home_And_Origin();2976#endif29772978// send new home and ekf origin to GCS2979GCS_SEND_MESSAGE(MSG_HOME);2980GCS_SEND_MESSAGE(MSG_ORIGIN);29812982AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;2983pd.home_lat = loc.lat;2984pd.home_lon = loc.lng;2985pd.home_alt_cm = loc.alt;29862987return true;2988}29892990/* if this was a watchdog reset then get home from backup registers */2991void AP_AHRS::load_watchdog_home()2992{2993const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;2994if (hal.util->was_watchdog_reset() && (pd.home_lat != 0 || pd.home_lon != 0)) {2995_home.lat = pd.home_lat;2996_home.lng = pd.home_lon;2997_home.set_alt_cm(pd.home_alt_cm, Location::AltFrame::ABSOLUTE);2998_home_is_set = true;2999_home_locked = true;3000GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Restored watchdog home");3001}3002}30033004// get_hgt_ctrl_limit - get maximum height to be observed by the control loops in metres and a validity flag3005// this is used to limit height during optical flow navigation3006// it will return false when no limiting is required3007bool AP_AHRS::get_hgt_ctrl_limit(float& limit) const3008{3009switch (active_EKF_type()) {3010#if AP_AHRS_DCM_ENABLED3011case EKFType::DCM:3012// We are not using an EKF so no limiting applies3013return false;3014#endif30153016#if HAL_NAVEKF2_AVAILABLE3017case EKFType::TWO:3018return EKF2.getHeightControlLimit(limit);3019#endif30203021#if HAL_NAVEKF3_AVAILABLE3022case EKFType::THREE:3023return EKF3.getHeightControlLimit(limit);3024#endif30253026#if AP_AHRS_SIM_ENABLED3027case EKFType::SIM:3028return sim.get_hgt_ctrl_limit(limit);3029#endif3030#if AP_AHRS_EXTERNAL_ENABLED3031case EKFType::EXTERNAL:3032return false;3033#endif3034}30353036return false;3037}30383039// Set to true if the terrain underneath is stable enough to be used as a height reference3040// this is not related to terrain following3041void AP_AHRS::set_terrain_hgt_stable(bool stable)3042{3043// avoid repeatedly setting variable in NavEKF objects to prevent3044// spurious event logging3045switch (terrainHgtStableState) {3046case TriState::UNKNOWN:3047break;3048case TriState::True:3049if (stable) {3050return;3051}3052break;3053case TriState::False:3054if (!stable) {3055return;3056}3057break;3058}3059terrainHgtStableState = (TriState)stable;30603061#if HAL_NAVEKF2_AVAILABLE3062EKF2.setTerrainHgtStable(stable);3063#endif3064#if HAL_NAVEKF3_AVAILABLE3065EKF3.setTerrainHgtStable(stable);3066#endif3067}30683069// return the innovations for the primarily EKF3070// boolean false is returned if innovations are not available3071bool AP_AHRS::get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const3072{3073switch (ekf_type()) {3074#if AP_AHRS_DCM_ENABLED3075case EKFType::DCM:3076// We are not using an EKF so no data3077return false;3078#endif30793080#if HAL_NAVEKF2_AVAILABLE3081case EKFType::TWO:3082// use EKF to get innovations3083return EKF2.getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov);3084#endif30853086#if HAL_NAVEKF3_AVAILABLE3087case EKFType::THREE:3088// use EKF to get innovations3089return EKF3.getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov);3090#endif30913092#if AP_AHRS_SIM_ENABLED3093case EKFType::SIM:3094return sim.get_innovations(velInnov, posInnov, magInnov, tasInnov, yawInnov);3095#endif30963097#if AP_AHRS_EXTERNAL_ENABLED3098case EKFType::EXTERNAL:3099return false;3100#endif3101}31023103return false;3104}31053106// returns true when the state estimates are significantly degraded by vibration3107bool AP_AHRS::is_vibration_affected() const3108{3109switch (ekf_type()) {3110#if HAL_NAVEKF3_AVAILABLE3111case EKFType::THREE:3112return EKF3.isVibrationAffected();3113#endif3114#if AP_AHRS_DCM_ENABLED3115case EKFType::DCM:3116#endif3117#if HAL_NAVEKF2_AVAILABLE3118case EKFType::TWO:3119#endif3120#if AP_AHRS_SIM_ENABLED3121case EKFType::SIM:3122#endif3123#if AP_AHRS_EXTERNAL_ENABLED3124case EKFType::EXTERNAL:3125#endif3126return false;3127}3128return false;3129}31303131// get_variances - provides the innovations normalised using the innovation variance where a value of 03132// indicates prefect consistency between the measurement and the EKF solution and a value of 1 is the maximum3133// inconsistency that will be accepted by the filter3134// boolean false is returned if variances are not available3135bool AP_AHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const3136{3137switch (ekf_type()) {3138#if AP_AHRS_DCM_ENABLED3139case EKFType::DCM:3140// We are not using an EKF so no data3141return false;3142#endif31433144#if HAL_NAVEKF2_AVAILABLE3145case EKFType::TWO: {3146// use EKF to get variance3147Vector2f offset;3148return EKF2.getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);3149}3150#endif31513152#if HAL_NAVEKF3_AVAILABLE3153case EKFType::THREE: {3154// use EKF to get variance3155Vector2f offset;3156return EKF3.getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);3157}3158#endif31593160#if AP_AHRS_SIM_ENABLED3161case EKFType::SIM:3162return sim.get_variances(velVar, posVar, hgtVar, magVar, tasVar);3163#endif31643165#if AP_AHRS_EXTERNAL_ENABLED3166case EKFType::EXTERNAL:3167return external.get_variances(velVar, posVar, hgtVar, magVar, tasVar);3168#endif3169}31703171return false;3172}31733174// get a source's velocity innovations. source should be from 0 to 7 (see AP_NavEKF_Source::SourceXY)3175// returns true on success and results are placed in innovations and variances arguments3176bool AP_AHRS::get_vel_innovations_and_variances_for_source(uint8_t source, Vector3f &innovations, Vector3f &variances) const3177{3178switch (ekf_type()) {3179#if AP_AHRS_DCM_ENABLED3180case EKFType::DCM:3181// We are not using an EKF so no data3182return false;3183#endif31843185#if HAL_NAVEKF2_AVAILABLE3186case EKFType::TWO:3187// EKF2 does not support source level variances3188return false;3189#endif31903191#if HAL_NAVEKF3_AVAILABLE3192case EKFType::THREE:3193// use EKF to get variance3194return EKF3.getVelInnovationsAndVariancesForSource((AP_NavEKF_Source::SourceXY)source, innovations, variances);3195#endif31963197#if AP_AHRS_SIM_ENABLED3198case EKFType::SIM:3199// SITL does not support source level variances3200return false;3201#endif32023203#if AP_AHRS_EXTERNAL_ENABLED3204case EKFType::EXTERNAL:3205return false;3206#endif3207}32083209return false;3210}32113212//get the index of the active airspeed sensor, wrt the primary core3213uint8_t AP_AHRS::get_active_airspeed_index() const3214{3215#if AP_AIRSPEED_ENABLED3216const auto *airspeed = AP::airspeed();3217if (airspeed == nullptr) {3218return 0;3219}32203221// we only have affinity for EKF3 as of now3222#if HAL_NAVEKF3_AVAILABLE3223if (active_EKF_type() == EKFType::THREE) {3224uint8_t ret = EKF3.getActiveAirspeed();3225if (ret != UINT8_MAX && airspeed->healthy(ret) && airspeed->use(ret)) {3226return ret;3227}3228}3229#endif32303231// for the rest, let the primary airspeed sensor be used3232return airspeed->get_primary();3233#else32343235return 0;3236#endif // AP_AIRSPEED_ENABLED3237}32383239// get the index of the current primary IMU3240uint8_t AP_AHRS::_get_primary_IMU_index() const3241{3242int8_t imu = -1;3243switch (active_EKF_type()) {3244#if AP_AHRS_DCM_ENABLED3245case EKFType::DCM:3246break;3247#endif3248#if HAL_NAVEKF2_AVAILABLE3249case EKFType::TWO:3250// let EKF2 choose primary IMU3251imu = EKF2.getPrimaryCoreIMUIndex();3252break;3253#endif3254#if HAL_NAVEKF3_AVAILABLE3255case EKFType::THREE:3256// let EKF2 choose primary IMU3257imu = EKF3.getPrimaryCoreIMUIndex();3258break;3259#endif3260#if AP_AHRS_SIM_ENABLED3261case EKFType::SIM:3262break;3263#endif3264#if AP_AHRS_EXTERNAL_ENABLED3265case EKFType::EXTERNAL:3266break;3267#endif3268}3269if (imu == -1) {3270imu = AP::ins().get_first_usable_gyro();3271}3272return imu;3273}32743275// return the index of the primary core or -1 if no primary core selected3276int8_t AP_AHRS::_get_primary_core_index() const3277{3278switch (active_EKF_type()) {3279#if AP_AHRS_DCM_ENABLED3280case EKFType::DCM:3281// we have only one core3282return 0;3283#endif3284#if AP_AHRS_SIM_ENABLED3285case EKFType::SIM:3286// we have only one core3287return 0;3288#endif3289#if AP_AHRS_EXTERNAL_ENABLED3290case EKFType::EXTERNAL:3291// we have only one core3292return 0;3293#endif32943295#if HAL_NAVEKF2_AVAILABLE3296case EKFType::TWO:3297return EKF2.getPrimaryCoreIndex();3298#endif32993300#if HAL_NAVEKF3_AVAILABLE3301case EKFType::THREE:3302return EKF3.getPrimaryCoreIndex();3303#endif3304}33053306// we should never get here3307INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);3308return -1;3309}33103311// get the index of the current primary accelerometer sensor3312uint8_t AP_AHRS::_get_primary_accel_index(void) const3313{3314return _get_primary_IMU_index();3315}33163317// get the index of the current primary gyro sensor3318uint8_t AP_AHRS::_get_primary_gyro_index(void) const3319{3320return _get_primary_IMU_index();3321}33223323// see if EKF lane switching is possible to avoid EKF failsafe3324void AP_AHRS::check_lane_switch(void)3325{3326switch (active_EKF_type()) {3327#if AP_AHRS_DCM_ENABLED3328case EKFType::DCM:3329break;3330#endif33313332#if AP_AHRS_SIM_ENABLED3333case EKFType::SIM:3334break;3335#endif33363337#if AP_AHRS_EXTERNAL_ENABLED3338case EKFType::EXTERNAL:3339break;3340#endif33413342#if HAL_NAVEKF2_AVAILABLE3343case EKFType::TWO:3344EKF2.checkLaneSwitch();3345break;3346#endif33473348#if HAL_NAVEKF3_AVAILABLE3349case EKFType::THREE:3350EKF3.checkLaneSwitch();3351break;3352#endif3353}3354}33553356// request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe3357void AP_AHRS::request_yaw_reset(void)3358{3359switch (active_EKF_type()) {3360#if AP_AHRS_DCM_ENABLED3361case EKFType::DCM:3362break;3363#endif3364#if AP_AHRS_SIM_ENABLED3365case EKFType::SIM:3366break;3367#endif33683369#if AP_AHRS_EXTERNAL_ENABLED3370case EKFType::EXTERNAL:3371break;3372#endif33733374#if HAL_NAVEKF2_AVAILABLE3375case EKFType::TWO:3376EKF2.requestYawReset();3377break;3378#endif33793380#if HAL_NAVEKF3_AVAILABLE3381case EKFType::THREE:3382EKF3.requestYawReset();3383break;3384#endif3385}3386}33873388// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary3389void AP_AHRS::set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx)3390{3391#if HAL_NAVEKF3_AVAILABLE3392EKF3.setPosVelYawSourceSet((uint8_t)source_set_idx);3393#endif3394}33953396//returns active source set used, 0=primary, 1=secondary, 2=tertiary3397uint8_t AP_AHRS::get_posvelyaw_source_set() const3398{3399#if HAL_NAVEKF3_AVAILABLE3400return EKF3.get_active_source_set();3401#else3402return 0;3403#endif3404}34053406void AP_AHRS::Log_Write()3407{3408#if HAL_NAVEKF2_AVAILABLE3409EKF2.Log_Write();3410#endif3411#if HAL_NAVEKF3_AVAILABLE3412EKF3.Log_Write();3413#endif34143415Write_AHRS2();3416Write_POS();34173418#if AP_AHRS_SIM_ENABLED3419AP::sitl()->Log_Write_SIMSTATE();3420#endif3421}34223423// check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed3424bool AP_AHRS::using_noncompass_for_yaw(void) const3425{3426switch (active_EKF_type()) {3427#if HAL_NAVEKF2_AVAILABLE3428case EKFType::TWO:3429return EKF2.isExtNavUsedForYaw();3430#endif3431#if AP_AHRS_DCM_ENABLED3432case EKFType::DCM:3433#endif3434#if HAL_NAVEKF3_AVAILABLE3435case EKFType::THREE:3436return EKF3.using_noncompass_for_yaw();3437#endif3438#if AP_AHRS_SIM_ENABLED3439case EKFType::SIM:3440#endif3441#if AP_AHRS_EXTERNAL_ENABLED3442case EKFType::EXTERNAL:3443#endif3444return false;3445}3446// since there is no default case above, this is unreachable3447return false;3448}34493450// check if external nav is providing yaw3451bool AP_AHRS::using_extnav_for_yaw(void) const3452{3453switch (active_EKF_type()) {3454#if HAL_NAVEKF2_AVAILABLE3455case EKFType::TWO:3456return EKF2.isExtNavUsedForYaw();3457#endif3458#if AP_AHRS_DCM_ENABLED3459case EKFType::DCM:3460#endif3461#if HAL_NAVEKF3_AVAILABLE3462case EKFType::THREE:3463return EKF3.using_extnav_for_yaw();3464#endif3465#if AP_AHRS_SIM_ENABLED3466case EKFType::SIM:3467#endif3468#if AP_AHRS_EXTERNAL_ENABLED3469case EKFType::EXTERNAL:3470#endif3471return false;3472}3473// since there is no default case above, this is unreachable3474return false;3475}34763477// set and save the alt noise parameter value3478void AP_AHRS::set_alt_measurement_noise(float noise)3479{3480#if HAL_NAVEKF2_AVAILABLE3481EKF2.set_baro_alt_noise(noise);3482#endif3483#if HAL_NAVEKF3_AVAILABLE3484EKF3.set_baro_alt_noise(noise);3485#endif3486}34873488// check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed3489const EKFGSF_yaw *AP_AHRS::get_yaw_estimator(void) const3490{3491switch (active_EKF_type()) {3492#if HAL_NAVEKF2_AVAILABLE3493case EKFType::TWO:3494return EKF2.get_yawEstimator();3495#endif3496#if AP_AHRS_DCM_ENABLED3497case EKFType::DCM:3498#if HAL_NAVEKF3_AVAILABLE3499return EKF3.get_yawEstimator();3500#else3501return nullptr;3502#endif3503#endif3504#if HAL_NAVEKF3_AVAILABLE3505case EKFType::THREE:3506return EKF3.get_yawEstimator();3507#endif3508#if AP_AHRS_SIM_ENABLED3509case EKFType::SIM:3510#endif3511#if AP_AHRS_EXTERNAL_ENABLED3512case EKFType::EXTERNAL:3513#endif3514return nullptr;3515}3516// since there is no default case above, this is unreachable3517return nullptr;3518}35193520// get current location estimate3521bool AP_AHRS::get_location(Location &loc) const3522{3523loc = state.location;3524return state.location_ok;3525}35263527// return a wind estimation vector, in m/s; returns 0,0,0 on failure3528bool AP_AHRS::wind_estimate(Vector3f &wind) const3529{3530wind = state.wind_estimate;3531return state.wind_estimate_ok;3532}35333534// return an airspeed estimate if available. return true3535// if we have an estimate3536bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const3537{3538airspeed_ret = state.airspeed;3539return state.airspeed_ok;3540}35413542// return an airspeed estimate if available. return true3543// if we have an estimate3544bool AP_AHRS::airspeed_estimate(float &airspeed_ret, AP_AHRS::AirspeedEstimateType &type) const3545{3546airspeed_ret = state.airspeed;3547type = state.airspeed_estimate_type;3548return state.airspeed_ok;3549}35503551// return a true airspeed estimate (navigation airspeed) if3552// available. return true if we have an estimate3553bool AP_AHRS::airspeed_estimate_true(float &airspeed_ret) const3554{3555airspeed_ret = state.airspeed_true;3556return state.airspeed_true_ok;3557}35583559// return estimate of true airspeed vector in body frame in m/s3560// returns false if estimate is unavailable3561bool AP_AHRS::airspeed_vector_true(Vector3f &vec) const3562{3563vec = state.airspeed_vec;3564return state.airspeed_vec_ok;3565}35663567// return the quaternion defining the rotation from NED to XYZ (body) axes3568bool AP_AHRS::get_quaternion(Quaternion &quat) const3569{3570quat = state.quat;3571return state.quat_ok;3572}35733574// returns the inertial navigation origin in lat/lon/alt3575bool AP_AHRS::get_origin(Location &ret) const3576{3577ret = state.origin;3578return state.origin_ok;3579}35803581// return a ground velocity in meters/second, North/East/Down3582// order. Must only be called if have_inertial_nav() is true3583bool AP_AHRS::get_velocity_NED(Vector3f &vec) const3584{3585vec = state.velocity_NED;3586return state.velocity_NED_ok;3587}35883589// return location corresponding to vector relative to the3590// vehicle's origin3591bool AP_AHRS::get_location_from_origin_offset_NED(Location &loc, const Vector3p &offset_ned) const3592{3593if (!get_origin(loc)) {3594return false;3595}3596loc.offset(offset_ned);35973598return true;3599}36003601// return location corresponding to vector relative to the3602// vehicle's home location3603bool AP_AHRS::get_location_from_home_offset_NED(Location &loc, const Vector3p &offset_ned) const3604{3605if (!home_is_set()) {3606return false;3607}3608loc = get_home();3609loc.offset(offset_ned);36103611return true;3612}36133614/*3615get EAS to TAS scaling3616*/3617float AP_AHRS::get_EAS2TAS(void) const3618{3619if (is_positive(state.EAS2TAS)) {3620return state.EAS2TAS;3621}3622return 1.0;3623}36243625// get air density / sea level density - decreases as altitude climbs3626float AP_AHRS::get_air_density_ratio(void) const3627{3628const float eas2tas = get_EAS2TAS();3629return 1.0 / sq(eas2tas);3630}36313632// singleton instance3633AP_AHRS *AP_AHRS::_singleton;36343635namespace AP {36363637AP_AHRS &ahrs()3638{3639return *AP_AHRS::get_singleton();3640}36413642}36433644#endif // AP_AHRS_ENABLED364536463647