Browse Source

AP_NavEKF3: fix potential time-stamping bug

Use a consistent time reference
mission-4.1.18
priseborough 8 years ago committed by Randy Mackay
parent
commit
a8fd1d8bcd
  1. 2
      libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp
  2. 3
      libraries/AP_NavEKF3/AP_NavEKF3_core.cpp

2
libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp

@ -283,7 +283,7 @@ void NavEKF3_core::readIMUData() @@ -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)) {

3
libraries/AP_NavEKF3/AP_NavEKF3_core.cpp

@ -498,9 +498,6 @@ void NavEKF3_core::UpdateFilter(bool predict) @@ -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…
Cancel
Save