mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: Prevent bad GPS pre-arming casuing initial position errors
If the vehicle moves significantly or the GPS changes position significantly pre-armed, then the GPS glitch logic was being invoked when the first GPs measurements were fused. This patch resets the position to the GPS when the vehicle arms.
This commit is contained in:
parent
bc5581d634
commit
aa94ff629d
|
@ -4621,6 +4621,8 @@ void NavEKF::performArmingChecks()
|
|||
PV_AidingMode = AID_ABSOLUTE; // we have GPS data and can estimate all vehicle states
|
||||
constPosMode = false;
|
||||
constVelMode = false;
|
||||
// we reset the position in case the initial GPS setting the origin was off or the vehicle has been moved a significant distance
|
||||
ResetPosition();
|
||||
}
|
||||
}
|
||||
// Reset filter positon, height and velocity states on arming or disarming
|
||||
|
|
Loading…
Reference in New Issue