AP_Bootloader: cope with RAM0_START not matching between bl and periph

this allows us to stay in bootloader based solely on RTC_BOOT_CANBL
without the RAM0 area matching between bootloader and periph fw

fixes an issue with current bootloaders where the old bl may not match
current RAM0 value
This commit is contained in:
Andrew Tridgell 2024-02-11 13:36:51 +11:00
parent bb8047c026
commit 7199ccacda
1 changed files with 3 additions and 2 deletions

View File

@ -136,8 +136,9 @@ int main(void)
}
#endif // AP_CHECK_FIRMWARE_ENABLED
#ifndef BOOTLOADER_DEV_LIST
else if (timeout != 0) {
// fast boot for good firmware
else if (timeout == HAL_BOOTLOADER_TIMEOUT) {
// fast boot for good firmware if we haven't been told to stay
// in bootloader
try_boot = true;
timeout = 1000;
}