AP_NavEKF3: use use_EKFGSFYaw to reduce code duplication

This commit is contained in:
Peter Barker 2020-12-17 11:47:13 +11:00 committed by Randy Mackay
parent a31ea88ff5
commit 6dfd2f2ff9

View File

@ -1464,12 +1464,8 @@ bool NavEKF3_core::EKFGSF_resetMainFilterYaw()
return false; return false;
}; };
float yawEKFGSF, yawVarianceEKFGSF, velInnovLength; float yawEKFGSF, yawVarianceEKFGSF;
if (yawEstimator->getYawData(yawEKFGSF, yawVarianceEKFGSF) && if (EKFGSF_getYaw(yawEKFGSF, yawVarianceEKFGSF)) {
is_positive(yawVarianceEKFGSF) &&
yawVarianceEKFGSF < sq(radians(GSF_YAW_ACCURACY_THRESHOLD_DEG)) &&
(assume_zero_sideslip() || (yawEstimator->getVelInnovLength(velInnovLength) && velInnovLength < frontend->maxYawEstVelInnov))) {
// keep roll and pitch and reset yaw // keep roll and pitch and reset yaw
rotationOrder order; rotationOrder order;
bestRotationOrder(order); bestRotationOrder(order);