mirror of https://github.com/ArduPilot/ardupilot
AP_IOMCU: prevent internal error on bootloader flash
when we flash the bootloader on boards with an IOMCU we expect a long delay as the CPU stops during the flash
This commit is contained in:
parent
bb278a1cc7
commit
87528f47c8
|
@ -1016,8 +1016,12 @@ void AP_IOMCU::check_iomcu_reset(void)
|
|||
}
|
||||
uint32_t dt_ms = reg_status.timestamp_ms - last_iocmu_timestamp_ms;
|
||||
uint32_t ts1 = last_iocmu_timestamp_ms;
|
||||
// when we are in an expected delay allow for a larger time
|
||||
// delta. This copes with flash erase, such as bootloader update
|
||||
const uint32_t max_delay = hal.scheduler->in_expected_delay()?5000:500;
|
||||
last_iocmu_timestamp_ms = reg_status.timestamp_ms;
|
||||
if (dt_ms < 500) {
|
||||
|
||||
if (dt_ms < max_delay) {
|
||||
// all OK
|
||||
return;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue