HAL_ChibiOS: fixed flash load address in hwdef.h

This commit is contained in:
Andrew Tridgell 2018-06-07 17:41:28 +10:00
parent 3a7c1b4d42
commit 2df0a71a4b
1 changed files with 1 additions and 1 deletions

View File

@ -413,7 +413,7 @@ def write_mcu_config(f):
flash_reserve_start = get_config(
'FLASH_RESERVE_START_KB', default=16, type=int)
f.write('\n// location of loaded firmware\n')
f.write('#define FLASH_LOAD_ADDRESS 0x%08x\n' % flash_reserve_start)
f.write('#define FLASH_LOAD_ADDRESS 0x%08x\n' % flash_reserve_start*1024)
f.write('\n')
ram_size_kb = get_mcu_config('RAM_SIZE_KB', True)