mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AP_HAL_ChibiOS: enable heap allocation if flash space for bootloader is > 128K
This commit is contained in:
parent
fd80d331cb
commit
ceea189fa3
@ -1260,7 +1260,12 @@ class ChibiOSHWDef(object):
|
|||||||
#endif
|
#endif
|
||||||
#define STM32_FLASH_DISABLE_ISR 0
|
#define STM32_FLASH_DISABLE_ISR 0
|
||||||
''')
|
''')
|
||||||
if not self.env_vars['EXT_FLASH_SIZE_MB'] and not args.signed_fw:
|
# get bootloader flash space, if larger than 128k we can enable Heap
|
||||||
|
flash_size = self.get_config('FLASH_USE_MAX_KB', type=int, default=0)
|
||||||
|
if flash_size == 0:
|
||||||
|
flash_size = self.get_config('FLASH_SIZE_KB', type=int)
|
||||||
|
flash_length = min(flash_size, self.get_config('FLASH_BOOTLOADER_LOAD_KB', type=int))
|
||||||
|
if not self.env_vars['EXT_FLASH_SIZE_MB'] and not args.signed_fw and flash_length < 128:
|
||||||
f.write('''
|
f.write('''
|
||||||
#ifndef CH_CFG_USE_MEMCORE
|
#ifndef CH_CFG_USE_MEMCORE
|
||||||
#define CH_CFG_USE_MEMCORE FALSE
|
#define CH_CFG_USE_MEMCORE FALSE
|
||||||
|
Loading…
Reference in New Issue
Block a user