mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: ensure bootloader flash is multiple of 32 bytes
This commit is contained in:
parent
e22170628d
commit
4561ebf0e2
|
@ -239,6 +239,9 @@ bool Util::flash_bootloader()
|
|||
return false;
|
||||
}
|
||||
|
||||
// make sure size is multiple of 32
|
||||
fw_size = (fw_size + 31U) & ~31U;
|
||||
|
||||
const uint32_t addr = hal.flash->getpageaddr(0);
|
||||
if (!memcmp(fw, (const void*)addr, fw_size)) {
|
||||
hal.console->printf("Bootloader up-to-date\n");
|
||||
|
|
Loading…
Reference in New Issue