mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_NavEKF2: Don't run GPS checks when not required
This commit is contained in:
parent
1986af021f
commit
df0eb9d9d7
@ -3751,7 +3751,9 @@ void NavEKF2_core::readGpsData()
|
||||
}
|
||||
|
||||
// Monitor quality of the GPS velocity data for alignment
|
||||
gpsQualGood = calcGpsGoodToAlign();
|
||||
if (PV_AidingMode != AID_ABSOLUTE) {
|
||||
gpsQualGood = calcGpsGoodToAlign();
|
||||
}
|
||||
|
||||
// read latitutde and longitude from GPS and convert to local NE position relative to the stored origin
|
||||
// If we don't have an origin, then set it to the current GPS coordinates
|
||||
|
Loading…
Reference in New Issue
Block a user