AP_NavEKF3: INS get_sample_rate() renamed to get_loop_rate_hz()
This commit is contained in:
parent
e39e24bd18
commit
e35458cedf
@ -686,7 +686,7 @@ bool NavEKF3::InitialiseFilter(void)
|
||||
imuSampleTime_us = AP_HAL::micros64();
|
||||
|
||||
// remember expected frame time
|
||||
_frameTimeUsec = 1e6 / ins.get_sample_rate();
|
||||
_frameTimeUsec = 1e6 / ins.get_loop_rate_hz();
|
||||
|
||||
// expected number of IMU frames per prediction
|
||||
_framesPerPrediction = uint8_t((EKF_TARGET_DT / (_frameTimeUsec * 1.0e-6) + 0.5));
|
||||
|
@ -51,8 +51,8 @@ bool NavEKF3_core::setup_core(uint8_t _imu_index, uint8_t _core_index)
|
||||
*/
|
||||
|
||||
// Calculate the expected EKF time step
|
||||
if (AP::ins().get_sample_rate() > 0) {
|
||||
dtEkfAvg = 1.0f / AP::ins().get_sample_rate();
|
||||
if (AP::ins().get_loop_rate_hz() > 0) {
|
||||
dtEkfAvg = 1.0f / AP::ins().get_loop_rate_hz();
|
||||
dtEkfAvg = MAX(dtEkfAvg,EKF_TARGET_DT);
|
||||
} else {
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user