mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_NavEKF2: final mag reset at 2.5m
This commit is contained in:
parent
c1264cf60a
commit
7e7f78d4b5
@ -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;
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user