From 99f481e0981b7d88637781a433834c7c6c60ee5d Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 30 Mar 2016 18:59:59 -0700 Subject: [PATCH] AP_NavEKF2: always calcGpsGoodForFlight --- libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp index 80b84b9afa..c8ac440438 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp @@ -411,11 +411,11 @@ void NavEKF2_core::readGpsData() if (PV_AidingMode != AID_ABSOLUTE) { // Pre-alignment checks gpsGoodToAlign = calcGpsGoodToAlign(); - } else { - // Post-alignment checks - calcGpsGoodForFlight(); } + // Post-alignment checks + calcGpsGoodForFlight(); + // Read the GPS locaton in WGS-84 lat,long,height coordinates const struct Location &gpsloc = _ahrs->get_gps().location();