mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: added option to limit size of bootloader
this will ensure our F4 bootloaders stay under 16k
This commit is contained in:
parent
4cafcc4eae
commit
1c807e0078
|
@ -13,6 +13,9 @@ STM32_PLLM_VALUE 8
|
|||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# don't allow bootloader to use more than 16k
|
||||
FLASH_USE_MAX_KB 16
|
||||
|
||||
USB_STRING_PRODUCT "ArduPilot-revo-BL"
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
|
|
|
@ -447,6 +447,8 @@ def write_mcu_config(f):
|
|||
|
||||
def write_ldscript(fname):
|
||||
'''write ldscript.ld for this board'''
|
||||
flash_size = get_config('FLASH_USE_MAX_KB', type=int, default=0)
|
||||
if flash_size == 0:
|
||||
flash_size = get_config('FLASH_SIZE_KB', type=int)
|
||||
|
||||
# space to reserve for bootloader and storage at start of flash
|
||||
|
|
Loading…
Reference in New Issue