AP_NavEKF2: always calcGpsGoodForFlight

This commit is contained in:
Jonathan Challinger 2016-03-30 18:59:59 -07:00 committed by Andrew Tridgell
parent 3382e09580
commit 99f481e098
1 changed files with 3 additions and 3 deletions

View File

@ -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();