diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index 4780afd777..b51efd699e 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -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; }