mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_NavEKF3: fix potential time-stamping bug
Use a consistent time reference
This commit is contained in:
parent
8d1733cee6
commit
a8fd1d8bcd
@ -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)) {
|
||||
|
@ -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();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user