mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_NavEKF2: use ekf_low_time_remaining for core scheduling
This commit is contained in:
parent
47c3fadc17
commit
90a8c5cb1a
@ -763,7 +763,7 @@ void NavEKF2::UpdateFilter(void)
|
||||
// loop then suppress the prediction step. This allows
|
||||
// multiple EKF instances to cooperate on scheduling
|
||||
if (core[i].getFramesSincePredict() < (_framesPerPrediction+3) &&
|
||||
(AP::dal().micros64() - imuSampleTime_us) > _frameTimeUsec/3) {
|
||||
AP::dal().ekf_low_time_remaining(AP_DAL::EKFType::EKF2, i)) {
|
||||
statePredictEnabled[i] = false;
|
||||
} else {
|
||||
statePredictEnabled[i] = true;
|
||||
|
Loading…
Reference in New Issue
Block a user