mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_NavEKF3: Don't allow yaw alignment until tilt alignment completed
This commit is contained in:
parent
a07427fd30
commit
073e273732
@ -41,7 +41,7 @@ void NavEKF3_core::controlMagYawReset()
|
||||
// check if the spin rate is OK - high spin rates can cause angular alignment errors
|
||||
bool angRateOK = deltaRotVecTemp.length() < 0.1745f;
|
||||
|
||||
initialResetAllowed = angRateOK;
|
||||
initialResetAllowed = angRateOK && tiltAlignComplete;
|
||||
flightResetAllowed = angRateOK && !onGround;
|
||||
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user