AP_NavEKF3: Don't block no compass planes from running GPS alignment checks

This commit is contained in:
Paul Riseborough 2023-09-27 11:04:35 +10:00 committed by Andrew Tridgell
parent 6baeb1cd9d
commit eb2ff2192d
1 changed files with 1 additions and 1 deletions

View File

@ -12,7 +12,7 @@
*/
void NavEKF3_core::calcGpsGoodToAlign(void)
{
if (inFlight && assume_zero_sideslip() && !use_compass()) {
if (inFlight && !finalInflightYawInit && assume_zero_sideslip() && !use_compass()) {
// this is a special case where a plane has launched without magnetometer
// is now in the air and needs to align yaw to the GPS and start navigating as soon as possible
gpsGoodToAlign = true;