Browse Source

AP_NavEKF2: Don't run GPS checks when not required

master
Paul Riseborough 10 years ago
parent
commit
df0eb9d9d7
  1. 4
      libraries/AP_NavEKF2/AP_NavEKF2_core.cpp

4
libraries/AP_NavEKF2/AP_NavEKF2_core.cpp

@ -3751,7 +3751,9 @@ void NavEKF2_core::readGpsData() @@ -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…
Cancel
Save