mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: allow for delay in bootloader flash
This commit is contained in:
parent
f89aadd2ba
commit
6e80174147
|
@ -189,9 +189,12 @@ bool Util::flash_bootloader()
|
|||
uint32_t fw_size;
|
||||
const char *fw_name = "bootloader.bin";
|
||||
|
||||
hal.scheduler->expect_delay_ms(5000);
|
||||
|
||||
uint8_t *fw = AP_ROMFS::find_decompress(fw_name, fw_size);
|
||||
if (!fw) {
|
||||
hal.console->printf("failed to find %s\n", fw_name);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -199,6 +202,7 @@ bool Util::flash_bootloader()
|
|||
if (!memcmp(fw, (const void*)addr, fw_size)) {
|
||||
hal.console->printf("Bootloader up-to-date\n");
|
||||
free(fw);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -206,6 +210,7 @@ bool Util::flash_bootloader()
|
|||
if (!stm32_flash_erasepage(0)) {
|
||||
hal.console->printf("Erase failed\n");
|
||||
free(fw);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
return false;
|
||||
}
|
||||
hal.console->printf("Flashing %s @%08x\n", fw_name, (unsigned int)addr);
|
||||
|
@ -223,11 +228,13 @@ bool Util::flash_bootloader()
|
|||
}
|
||||
hal.console->printf("Flash OK\n");
|
||||
free(fw);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
return true;
|
||||
}
|
||||
|
||||
hal.console->printf("Flash failed after %u attempts\n", max_attempts);
|
||||
free(fw);
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue