diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 1be49e5647..6a06440fe9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -957,13 +957,18 @@ def write_mcu_config(f): f.write('#define CRT1_RAMFUNC_ENABLE FALSE\n') storage_flash_page = get_storage_flash_page() + flash_reserve_end = get_config('FLASH_RESERVE_END_KB', default=0, type=int) if storage_flash_page is not None: if not args.bootloader: f.write('#define STORAGE_FLASH_PAGE %u\n' % storage_flash_page) validate_flash_storage_size() - else: + elif get_config('FLASH_RESERVE_END_KB', type=int, required = False) is None: # ensure the flash page leaves room for bootloader offset = get_flash_page_offset_kb(storage_flash_page) + bl_offset = get_config('FLASH_BOOTLOADER_LOAD_KB', type=int) + # storage at end of flash - leave room + if offset > bl_offset: + flash_reserve_end = flash_size - offset if flash_size >= 2048 and not args.bootloader: # lets pick a flash sector for Crash log @@ -980,7 +985,7 @@ def write_mcu_config(f): 'EXT_FLASH_RESERVE_START_KB', default=0, type=int)*1024)) f.write('#define BOOT_FROM_EXT_FLASH 1\n') f.write('#define FLASH_BOOTLOADER_LOAD_KB %u\n' % get_config('FLASH_BOOTLOADER_LOAD_KB', type=int)) - f.write('#define FLASH_RESERVE_END_KB %u\n' % get_config('FLASH_RESERVE_END_KB', default=0, type=int)) + f.write('#define FLASH_RESERVE_END_KB %u\n' % flash_reserve_end) f.write('#define APP_START_OFFSET_KB %u\n' % get_config('APP_START_OFFSET_KB', default=0, type=int)) f.write('\n')