mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_HAL_ChibiOS: make sure bootloader reserves space for storage
Fixes bug introduced by #19769
This commit is contained in:
parent
6ed07bd67e
commit
7fc5a7135a
@ -957,13 +957,18 @@ def write_mcu_config(f):
|
|||||||
f.write('#define CRT1_RAMFUNC_ENABLE FALSE\n')
|
f.write('#define CRT1_RAMFUNC_ENABLE FALSE\n')
|
||||||
|
|
||||||
storage_flash_page = get_storage_flash_page()
|
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 storage_flash_page is not None:
|
||||||
if not args.bootloader:
|
if not args.bootloader:
|
||||||
f.write('#define STORAGE_FLASH_PAGE %u\n' % storage_flash_page)
|
f.write('#define STORAGE_FLASH_PAGE %u\n' % storage_flash_page)
|
||||||
validate_flash_storage_size()
|
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
|
# ensure the flash page leaves room for bootloader
|
||||||
offset = get_flash_page_offset_kb(storage_flash_page)
|
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:
|
if flash_size >= 2048 and not args.bootloader:
|
||||||
# lets pick a flash sector for Crash log
|
# 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))
|
'EXT_FLASH_RESERVE_START_KB', default=0, type=int)*1024))
|
||||||
f.write('#define BOOT_FROM_EXT_FLASH 1\n')
|
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_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('#define APP_START_OFFSET_KB %u\n' % get_config('APP_START_OFFSET_KB', default=0, type=int))
|
||||||
f.write('\n')
|
f.write('\n')
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user