mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
HAL_ChibiOS: fixed flash load address in hwdef.h
This commit is contained in:
parent
3a7c1b4d42
commit
2df0a71a4b
@ -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)
|
||||
|
Loading…
Reference in New Issue
Block a user