diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp index 1d1e79ae9b..25df5b9268 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp @@ -58,7 +58,7 @@ void NavEKF2_core::controlMagYawReset() if (flightResetAllowed && !assume_zero_sideslip()) { // check that we have reached a height where ground magnetic interference effects are insignificant // and can perform a final reset of the yaw and field states - finalResetRequest = (stateStruct.position.z - posDownAtTakeoff) < -5.0f; + finalResetRequest = (stateStruct.position.z - posDownAtTakeoff) < -EKF2_MAG_FINAL_RESET_ALT; // check for increasing height bool hgtIncreasing = (posDownAtLastMagReset-stateStruct.position.z) > 0.5f; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index 65fbdf598b..9ba42c6e2f 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -50,6 +50,9 @@ // target EKF update time step #define EKF_TARGET_DT 0.01f +// mag fusion final reset altitude +#define EKF2_MAG_FINAL_RESET_ALT 2.5f + class AP_AHRS; class NavEKF2_core