mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_NavEKF: Fix bug causing magnetic field state learning to be forgotten
This commit is contained in:
parent
bf89c56e54
commit
73a06cd0c1
@ -708,7 +708,7 @@ void NavEKF::UpdateFilter()
|
|||||||
state.quat = calcQuatAndFieldStates(_ahrs->roll, _ahrs->pitch);
|
state.quat = calcQuatAndFieldStates(_ahrs->roll, _ahrs->pitch);
|
||||||
firstArmPosD = state.position.z;
|
firstArmPosD = state.position.z;
|
||||||
}
|
}
|
||||||
calcQuatAndFieldStates(_ahrs->roll, _ahrs->pitch);
|
// zero stored velocities used to do dead-reckoning
|
||||||
heldVelNE.zero();
|
heldVelNE.zero();
|
||||||
// When entering static mode (dis-arming), clear the GPS inhibit mode
|
// When entering static mode (dis-arming), clear the GPS inhibit mode
|
||||||
// when leaving static mode (arming) set to true if EKF user parameter is set to not use GPS
|
// when leaving static mode (arming) set to true if EKF user parameter is set to not use GPS
|
||||||
|
Loading…
Reference in New Issue
Block a user