mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: set filter status dead_reckoning bit
This commit is contained in:
parent
6553b9145a
commit
eafb118b47
|
@ -718,6 +718,7 @@ void NavEKF3_core::updateFilterStatus(void)
|
||||||
(imuSampleTime_ms - lastTasFailTime_ms) < 1000 &&
|
(imuSampleTime_ms - lastTasFailTime_ms) < 1000 &&
|
||||||
(imuSampleTime_ms - lastTasPassTime_ms) > 3000;
|
(imuSampleTime_ms - lastTasPassTime_ms) > 3000;
|
||||||
filterStatus.flags.initalized = filterStatus.flags.initalized || healthy();
|
filterStatus.flags.initalized = filterStatus.flags.initalized || healthy();
|
||||||
|
filterStatus.flags.dead_reckoning = (PV_AidingMode != AID_NONE) && doingWindRelNav && !((doingFlowNav && gndOffsetValid) || doingNormalGpsNav || doingBodyVelNav);
|
||||||
}
|
}
|
||||||
|
|
||||||
void NavEKF3_core::runYawEstimatorPrediction()
|
void NavEKF3_core::runYawEstimatorPrediction()
|
||||||
|
|
Loading…
Reference in New Issue