mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
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:
parent
324d5da811
commit
2c3174b77b
@ -547,7 +547,11 @@ void NavEKF3_core::readGpsData()
|
||||
gpsGoodToAlign = false;
|
||||
lastGpsVelFail_ms = imuSampleTime_ms;
|
||||
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
|
||||
// for GPS alignment checks to pass before using GPS inside the EKF.
|
||||
waitingForGpsChecks = true;
|
||||
|
Loading…
Reference in New Issue
Block a user