mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed timer reset
This commit is contained in:
parent
fa4f497dab
commit
ed3194d095
|
@ -359,6 +359,7 @@ void Scheduler::_io_thread(void* arg)
|
|||
// thread when disarmed
|
||||
uint32_t now = AP_HAL::millis();
|
||||
if (now - last_sd_start_ms > 3000) {
|
||||
last_sd_start_ms = now;
|
||||
sdcard_retry();
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue