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