mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_NavEKF: fix delay detection so that filter properly resets after a delay
This commit is contained in:
parent
3719ea53e4
commit
085faaac6a
@ -3982,9 +3982,7 @@ void NavEKF::readIMUData()
|
||||
const AP_InertialSensor &ins = _ahrs->get_ins();
|
||||
|
||||
dtIMUavg = 1.0f/ins.get_sample_rate();
|
||||
|
||||
// limit IMU delta time to prevent numerical problems elsewhere
|
||||
dtIMUactual = constrain_float(ins.get_delta_time(),0.001f,0.2f);
|
||||
dtIMUactual = max(ins.get_delta_time(),1.0e-3f);
|
||||
|
||||
// the imu sample time is sued as a common time reference throughout the filter
|
||||
imuSampleTime_ms = hal.scheduler->millis();
|
||||
|
Loading…
Reference in New Issue
Block a user