mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
HAL_ChibiOS: ensure bootloader flash is multiple of 32 bytes
This commit is contained in:
parent
9c2caf5b12
commit
af04f1eb93
@ -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
Block a user