mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_NavEKF2: fixed init order for scheduler
this can impact replay of EKF2
This commit is contained in:
parent
913d1b81b2
commit
b36bfe4206
@ -634,7 +634,11 @@ bool NavEKF2::InitialiseFilter(void)
|
||||
imuSampleTime_us = AP::dal().micros64();
|
||||
|
||||
// remember expected frame time
|
||||
_frameTimeUsec = 1e6 / ins.get_loop_rate_hz();
|
||||
const float loop_rate = ins.get_loop_rate_hz();
|
||||
if (!is_positive(loop_rate)) {
|
||||
return false;
|
||||
}
|
||||
_frameTimeUsec = 1e6 / loop_rate;
|
||||
|
||||
// expected number of IMU frames per prediction
|
||||
_framesPerPrediction = uint8_t((EKF_TARGET_DT / (_frameTimeUsec * 1.0e-6) + 0.5));
|
||||
|
Loading…
Reference in New Issue
Block a user