From aa49e92edca952d0384436447b3008f247a5e8d3 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Sun, 21 Feb 2021 09:24:25 +1100 Subject: [PATCH] AP_AHRS: Remove unused AP_AHRS_NavEKF::yaw_alignment_complete API --- libraries/AP_AHRS/AP_AHRS_NavEKF.cpp | 37 ---------------------------- libraries/AP_AHRS/AP_AHRS_NavEKF.h | 1 - 2 files changed, 38 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index 2155ce22c7..dc5f8034e4 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -2554,43 +2554,6 @@ bool AP_AHRS_NavEKF::get_variances(float &velVar, float &posVar, float &hgtVar, return false; } -bool AP_AHRS_NavEKF::yaw_alignment_complete(void) const -{ - switch (ekf_type()) { - case EKFType::NONE: - // We are not using an EKF so no data - return true; - -#if HAL_NAVEKF2_AVAILABLE - case EKFType::TWO: { - // not provided - return true; - } -#endif - -#if HAL_NAVEKF3_AVAILABLE - case EKFType::THREE: { - // use EKF to get variance - return EKF3.yawAlignmentComplete(); - } -#endif - -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - case EKFType::SITL: - // not provided - return true; -#endif - -#if HAL_EXTERNAL_AHRS_ENABLED - case EKFType::EXTERNAL: - // not provided - return false; -#endif - } - - return false; -} - // get a source's velocity innovations. source should be from 0 to 7 (see AP_NavEKF_Source::SourceXY) // returns true on success and results are placed in innovations and variances arguments bool AP_AHRS_NavEKF::get_vel_innovations_and_variances_for_source(uint8_t source, Vector3f &innovations, Vector3f &variances) const diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index 36b75a9047..6d2ce627a3 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -282,7 +282,6 @@ public: void setTakeoffExpected(bool val); void setTouchdownExpected(bool val); - bool yaw_alignment_complete(void) const; bool getGpsGlitchStatus() const;