diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 05bef6ab2c..cb9f2cfc1f 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -761,12 +761,54 @@ void NavEKF2::UpdateFilter(void) updateLaneSwitchPosResetData(newPrimaryIndex, primary); updateLaneSwitchPosDownResetData(newPrimaryIndex, primary); primary = newPrimaryIndex; + lastLaneSwitch_ms = AP_HAL::millis(); } } check_log_write(); } +/* + check if switching lanes will reduce the normalised + innovations. This is called when the vehicle code is about to + trigger an EKF failsafe, and it would like to avoid that by + using a different EKF lane +*/ +void NavEKF2::checkLaneSwitch(void) +{ + uint32_t now = AP_HAL::millis(); + if (lastLaneSwitch_ms != 0 && now - lastLaneSwitch_ms < 5000) { + // don't switch twice in 5 seconds + return; + } + float primaryErrorScore = core[primary].errorScore(); + float lowestErrorScore = primaryErrorScore; + uint8_t newPrimaryIndex = primary; + for (uint8_t coreIndex=0; coreIndex