From 6dfd2f2ff955b8021c96f58f86b75ef52729ae48 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 17 Dec 2020 11:47:13 +1100 Subject: [PATCH] AP_NavEKF3: use use_EKFGSFYaw to reduce code duplication --- libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp index 4960ae2a19..2392b81ced 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp @@ -1464,12 +1464,8 @@ bool NavEKF3_core::EKFGSF_resetMainFilterYaw() return false; }; - float yawEKFGSF, yawVarianceEKFGSF, velInnovLength; - if (yawEstimator->getYawData(yawEKFGSF, yawVarianceEKFGSF) && - is_positive(yawVarianceEKFGSF) && - yawVarianceEKFGSF < sq(radians(GSF_YAW_ACCURACY_THRESHOLD_DEG)) && - (assume_zero_sideslip() || (yawEstimator->getVelInnovLength(velInnovLength) && velInnovLength < frontend->maxYawEstVelInnov))) { - + float yawEKFGSF, yawVarianceEKFGSF; + if (EKFGSF_getYaw(yawEKFGSF, yawVarianceEKFGSF)) { // keep roll and pitch and reset yaw rotationOrder order; bestRotationOrder(order);