mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_NavEKF3: use ekf_low_time_remaining for core scheduling
This commit is contained in:
parent
90a8c5cb1a
commit
31091d6307
@ -818,8 +818,7 @@ void NavEKF3::UpdateFilter(void)
|
|||||||
// loop then suppress the prediction step. This allows
|
// loop then suppress the prediction step. This allows
|
||||||
// multiple EKF instances to cooperate on scheduling
|
// multiple EKF instances to cooperate on scheduling
|
||||||
if (core[i].getFramesSincePredict() < (_framesPerPrediction+3) &&
|
if (core[i].getFramesSincePredict() < (_framesPerPrediction+3) &&
|
||||||
// need sub-frame micros for this test
|
AP::dal().ekf_low_time_remaining(AP_DAL::EKFType::EKF3, i)) {
|
||||||
(AP::dal().micros64() - imuSampleTime_us) > _frameTimeUsec/3) {
|
|
||||||
statePredictEnabled[i] = false;
|
statePredictEnabled[i] = false;
|
||||||
} else {
|
} else {
|
||||||
statePredictEnabled[i] = true;
|
statePredictEnabled[i] = true;
|
||||||
|
Loading…
Reference in New Issue
Block a user