Browse Source

AP_InertialSensor_Invensense: set reset count to 1 if 10s has passed since last reset

c415-sdk
nkruzan 4 years ago committed by Andrew Tridgell
parent
commit
f4c18e0f9c
  1. 5
      libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp

5
libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp

@ -168,6 +168,11 @@ void AP_InertialSensor_Invensense::_fifo_reset(bool log_error) @@ -168,6 +168,11 @@ void AP_InertialSensor_Invensense::_fifo_reset(bool log_error)
INTERNAL_ERROR(AP_InternalError::error_t::imu_reset);
reset_count = 0;
}
} else if (log_error &&
!hal.scheduler->in_expected_delay() &&
now - last_reset_ms > 10000) {
//if last reset was more than 10s ago consider this the first reset
reset_count = 1;
}
last_reset_ms = now;

Loading…
Cancel
Save