mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL_ChibiOS: tune delay for flashing bootloader
As the function can internally loop for 10 seconds
This commit is contained in:
parent
47c65314fb
commit
464540ab56
@ -230,7 +230,7 @@ bool Util::flash_bootloader()
|
||||
uint32_t fw_size;
|
||||
const char *fw_name = "bootloader.bin";
|
||||
|
||||
hal.scheduler->expect_delay_ms(5000);
|
||||
hal.scheduler->expect_delay_ms(11000);
|
||||
|
||||
uint8_t *fw = AP_ROMFS::find_decompress(fw_name, fw_size);
|
||||
if (!fw) {
|
||||
|
Loading…
Reference in New Issue
Block a user