AP_NavEKF2: final mag reset at 2.5m

This commit is contained in:
Randy Mackay 2017-07-07 17:04:45 +09:00
parent c1264cf60a
commit 7e7f78d4b5
2 changed files with 4 additions and 1 deletions

View File

@ -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;

View File

@ -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