mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: always calcGpsGoodForFlight
This commit is contained in:
parent
3382e09580
commit
99f481e098
|
@ -411,10 +411,10 @@ void NavEKF2_core::readGpsData()
|
|||
if (PV_AidingMode != AID_ABSOLUTE) {
|
||||
// Pre-alignment checks
|
||||
gpsGoodToAlign = calcGpsGoodToAlign();
|
||||
} else {
|
||||
}
|
||||
|
||||
// Post-alignment checks
|
||||
calcGpsGoodForFlight();
|
||||
}
|
||||
|
||||
// Read the GPS locaton in WGS-84 lat,long,height coordinates
|
||||
const struct Location &gpsloc = _ahrs->get_gps().location();
|
||||
|
|
Loading…
Reference in New Issue