AP_NavEKF3: Strengthen protection against GPS jamming

These changes prevent the EKF from consuming GPS data too soon when it is recovering from jamming if the EKF is able to navigate using dead reckoning.
This commit is contained in:
Paul Riseborough 2023-03-21 20:03:58 +11:00 committed by Andrew Tridgell
parent 324d5da811
commit 2c3174b77b

View File

@ -547,7 +547,11 @@ void NavEKF3_core::readGpsData()
gpsGoodToAlign = false; gpsGoodToAlign = false;
lastGpsVelFail_ms = imuSampleTime_ms; lastGpsVelFail_ms = imuSampleTime_ms;
lastGpsVelPass_ms = 0; lastGpsVelPass_ms = 0;
if (filterStatus.flags.horiz_pos_rel && !filterStatus.flags.horiz_pos_abs) { const bool doingBodyVelNav = (imuSampleTime_ms - prevBodyVelFuseTime_ms < 1000);
const bool doingFlowNav = (imuSampleTime_ms - prevFlowFuseTime_ms < 1000);;
const bool doingWindRelNav = (!tasTimeout && assume_zero_sideslip());
const bool canDeadReckon = ((doingFlowNav && gndOffsetValid) || doingWindRelNav || doingBodyVelNav);
if (canDeadReckon) {
// If we can do dead reckoning with a data source other than GPS there is time to wait // If we can do dead reckoning with a data source other than GPS there is time to wait
// for GPS alignment checks to pass before using GPS inside the EKF. // for GPS alignment checks to pass before using GPS inside the EKF.
waitingForGpsChecks = true; waitingForGpsChecks = true;