From e7be608a4a5eff158402c1207847e958f39171fd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 18 Aug 2021 16:34:37 +0900 Subject: [PATCH] AP_AHRS: rename is_ext_nav_used_for_yaw to using_noncompass_for_yaw --- libraries/AP_AHRS/AP_AHRS.cpp | 12 ++++++------ libraries/AP_AHRS/AP_AHRS.h | 4 ++-- libraries/AP_AHRS/AP_AHRS_Backend.h | 4 ++-- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 08e696d9e1..21cae9bcb2 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -2314,11 +2314,11 @@ bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_ // Check vs DCM yaw if this vehicle could use DCM in flight // and if not using an external yaw source (DCM does not support external yaw sources) - bool using_external_yaw = false; + bool using_noncompass_for_yaw = false; #if HAL_NAVEKF3_AVAILABLE - using_external_yaw = ekf_type() == EKFType::THREE && EKF3.using_external_yaw(); + using_noncompass_for_yaw = (ekf_type() == EKFType::THREE) && EKF3.using_noncompass_for_yaw(); #endif - if (!always_use_EKF() && !using_external_yaw) { + if (!always_use_EKF() && !using_noncompass_for_yaw) { Vector3f angle_diff; primary_quat.angular_difference(dcm_quat).to_axis_angle(angle_diff); const float yaw_diff = fabsf(angle_diff.z); @@ -3022,8 +3022,8 @@ void AP_AHRS::Log_Write() #endif } -// check whether compass can be bypassed for arming check in case when external navigation data is available -bool AP_AHRS::is_ext_nav_used_for_yaw(void) const +// check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed +bool AP_AHRS::using_noncompass_for_yaw(void) const { switch (active_EKF_type()) { #if HAL_NAVEKF2_AVAILABLE @@ -3033,7 +3033,7 @@ bool AP_AHRS::is_ext_nav_used_for_yaw(void) const case EKFType::NONE: #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - return EKF3.using_external_yaw(); + return EKF3.using_noncompass_for_yaw(); #endif #if CONFIG_HAL_BOARD == HAL_BOARD_SITL case EKFType::SIM: diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index c55628ff4e..886b8a542b 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -326,8 +326,8 @@ public: void Log_Write(); - // check whether external navigation is providing yaw. Allows compass pre-arm checks to be bypassed - bool is_ext_nav_used_for_yaw(void) const override; + // check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed + bool using_noncompass_for_yaw(void) const override; // set and save the ALT_M_NSE parameter value void set_alt_measurement_noise(float noise) override; diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.h b/libraries/AP_AHRS/AP_AHRS_Backend.h index 92f320e1f2..98d5f88bff 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.h +++ b/libraries/AP_AHRS/AP_AHRS_Backend.h @@ -90,8 +90,8 @@ public: // see if EKF lane switching is possible to avoid EKF failsafe virtual void check_lane_switch(void) {} - // check whether external navigation is providing yaw. Allows compass pre-arm checks to be bypassed - virtual bool is_ext_nav_used_for_yaw(void) const { return false; } + // check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed + virtual bool using_noncompass_for_yaw(void) const { return false; } // request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe virtual void request_yaw_reset(void) {}