mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: use single precision ceilf()
This commit is contained in:
parent
4404c95cc8
commit
553abda91c
|
@ -101,7 +101,7 @@ bool NavEKF3_core::setup_core(NavEKF3 *_frontend, uint8_t _imu_index, uint8_t _c
|
||||||
// set the observation buffer length to handle the minimum time of arrival between observations in combination
|
// set the observation buffer length to handle the minimum time of arrival between observations in combination
|
||||||
// with the worst case delay from current time to ekf fusion time
|
// with the worst case delay from current time to ekf fusion time
|
||||||
// allow for worst case 50% extension of the ekf fusion time horizon delay due to timing jitter
|
// allow for worst case 50% extension of the ekf fusion time horizon delay due to timing jitter
|
||||||
uint16_t ekf_delay_ms = maxTimeDelay_ms + (int)(ceil((float)maxTimeDelay_ms * 0.5f));
|
uint16_t ekf_delay_ms = maxTimeDelay_ms + (int)(ceilf((float)maxTimeDelay_ms * 0.5f));
|
||||||
obs_buffer_length = (ekf_delay_ms / _frontend->sensorIntervalMin_ms) + 1;
|
obs_buffer_length = (ekf_delay_ms / _frontend->sensorIntervalMin_ms) + 1;
|
||||||
|
|
||||||
// limit to be no longer than the IMU buffer (we can't process data faster than the EKF prediction rate)
|
// limit to be no longer than the IMU buffer (we can't process data faster than the EKF prediction rate)
|
||||||
|
|
Loading…
Reference in New Issue