AP_NavEKF3: fix potential time-stamping bug

Use a consistent time reference
This commit is contained in:
priseborough 2016-12-19 11:29:41 +11:00 committed by Randy Mackay
parent 8d1733cee6
commit a8fd1d8bcd
2 changed files with 1 additions and 4 deletions

View File

@ -283,7 +283,7 @@ void NavEKF3_core::readIMUData()
dtIMUavg = ins.get_loop_delta_t();
// the imu sample time is used as a common time reference throughout the filter
imuSampleTime_ms = AP_HAL::millis();
imuSampleTime_ms = frontend->imuSampleTime_us / 1000;
// use the nominated imu or primary if not available
if (ins.use_accel(imu_index)) {

View File

@ -498,9 +498,6 @@ void NavEKF3_core::UpdateFilter(bool predict)
// TODO - in-flight restart method
//get starting time for update step
imuSampleTime_ms = frontend->imuSampleTime_us / 1000;
// Check arm status and perform required checks and mode changes
controlFilterModes();