AP_NavEKF2: INS get_sample_rate() renamed to get_loop_rate_hz()

This commit is contained in:
Andy Piper 2020-05-21 19:31:22 +01:00 committed by Andrew Tridgell
parent 5a6be9e0a2
commit e39e24bd18
2 changed files with 2 additions and 2 deletions

View File

@ -665,7 +665,7 @@ bool NavEKF2::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));

View File

@ -72,7 +72,7 @@ bool NavEKF2_core::setup_core(uint8_t _imu_index, uint8_t _core_index)
than 100Hz is downsampled. For 50Hz main loop rate we need a
shorter buffer.
*/
if (AP::ins().get_sample_rate() < 100) {
if (AP::ins().get_loop_rate_hz() < 100) {
imu_buffer_length = 13;
} else {
// maximum 260 msec delay at 100 Hz fusion rate