mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_NavEKF: we can assume get_sample_rate() returns a non-zero number
this fixes a build error with the previous patch
This commit is contained in:
parent
e32e6cfa67
commit
5561efde2b
@ -3824,7 +3824,7 @@ void NavEKF_core::readIMUData()
|
||||
const AP_InertialSensor &ins = _ahrs->get_ins();
|
||||
|
||||
// calculate the average time between IMU updates
|
||||
dtIMUavg = 1.0f/max(ins.get_sample_rate(),1E-5f);
|
||||
dtIMUavg = 1.0f/(float)ins.get_sample_rate();
|
||||
|
||||
// calculate the most recent time between gyro delta angle updates
|
||||
if (ins.get_delta_time() > 0.0f) {
|
||||
|
Loading…
Reference in New Issue
Block a user