AP_NavEKF2: switch to optflow if gps is jammed

This commit is contained in:
chobits 2019-10-03 09:52:40 +08:00 committed by Randy Mackay
parent 455bd86f1a
commit a54f24c8c0

View File

@ -250,6 +250,9 @@ void NavEKF2_core::setAidingMode()
tasTimeout = true;
gpsNotAvailable = true;
} else if (posAidLossCritical) {
if ((frontend->_flowUse == FLOW_USE_NAV) && optFlowDataPresent() && (imuSampleTime_ms - rngValidMeaTime_ms < 500)) {
PV_AidingMode = AID_NONE;
}
// if the loss of position is critical, declare all sources of position aiding as being timed out
posTimeout = true;
velTimeout = true;