mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: final mag reset at 2.5m
This commit is contained in:
parent
7e7f78d4b5
commit
d64b2fcbf0
|
@ -56,7 +56,7 @@ void NavEKF3_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) < -EKF3_MAG_FINAL_RESET_ALT;
|
||||
|
||||
// check for increasing height
|
||||
bool hgtIncreasing = (posDownAtLastMagReset-stateStruct.position.z) > 0.5f;
|
||||
|
|
|
@ -61,6 +61,9 @@
|
|||
#define EKF_TARGET_DT_MS 12
|
||||
#define EKF_TARGET_DT 0.012f
|
||||
|
||||
// mag fusion final reset altitude (using NED frame so altitude is negative)
|
||||
#define EKF3_MAG_FINAL_RESET_ALT 2.5f
|
||||
|
||||
class AP_AHRS;
|
||||
|
||||
class NavEKF3_core
|
||||
|
|
Loading…
Reference in New Issue