mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: support a app->bootloader comms region in SRAM
this allows for UAVCAN update without a 2nd BeginFirmwareUpdate call
This commit is contained in:
parent
1c61ab165c
commit
0a4576728e
|
@ -106,3 +106,6 @@ define BOOTLOADER_BAUDRATE 57600
|
|||
|
||||
# use a small bootloader timeout
|
||||
define HAL_BOOTLOADER_TIMEOUT 1000
|
||||
|
||||
# reserve 256 bytes for comms between app and bootloader
|
||||
RAM_RESERVE_START 256
|
||||
|
|
|
@ -168,3 +168,6 @@ define AP_PERIPH_LED_BRIGHT_DEFAULT 50
|
|||
|
||||
# use the app descriptor needed by MissionPlanner for CAN upload
|
||||
env APP_DESCRIPTOR MissionPlanner
|
||||
|
||||
# reserve 256 bytes for comms between app and bootloader
|
||||
RAM_RESERVE_START 256
|
||||
|
|
|
@ -29,6 +29,9 @@ FLASH_SIZE_KB 256
|
|||
# reserve space for params
|
||||
FLASH_RESERVE_END_KB 2
|
||||
|
||||
# reserve 256 bytes for comms between app and bootloader
|
||||
RAM_RESERVE_START 256
|
||||
|
||||
# USART3 for debug
|
||||
#STDOUT_SERIAL SD3
|
||||
#STDOUT_BAUDRATE 115200
|
||||
|
|
|
@ -12,6 +12,9 @@ define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_ZubaxGNSS"
|
|||
# bootloader starts firmware at 34k
|
||||
FLASH_RESERVE_START_KB 34
|
||||
|
||||
# reserve 256 bytes for comms between app and bootloader
|
||||
RAM_RESERVE_START 256
|
||||
|
||||
# store parameters in last 2 pages
|
||||
define STORAGE_FLASH_PAGE 126
|
||||
define HAL_STORAGE_SIZE 800
|
||||
|
|
|
@ -95,3 +95,6 @@ define HAL_BOOTLOADER_TIMEOUT 1000
|
|||
# and look for it low then we know user has pulled it down and
|
||||
# want to stay in the bootloader
|
||||
PB6 STAY_IN_BOOTLOADER INPUT FLOATING
|
||||
|
||||
# reserve 256 bytes for comms between app and bootloader
|
||||
RAM_RESERVE_START 256
|
||||
|
|
|
@ -142,3 +142,6 @@ define HAL_COMPASS_MAX_SENSORS 1
|
|||
|
||||
# use the app descriptor needed by MissionPlanner for CAN upload
|
||||
env APP_DESCRIPTOR MissionPlanner
|
||||
|
||||
# reserve 256 bytes for comms between app and bootloader
|
||||
RAM_RESERVE_START 256
|
||||
|
|
|
@ -613,6 +613,11 @@ def write_mcu_config(f):
|
|||
f.write('#define HAL_MEMORY_REGIONS %s\n' % ', '.join(regions))
|
||||
f.write('#define HAL_MEMORY_TOTAL_KB %u\n' % total_memory)
|
||||
|
||||
f.write('#define HAL_RAM0_START 0x%08x\n' % ram_map[0][0])
|
||||
ram_reserve_start = get_config('RAM_RESERVE_START', default=0, type=int)
|
||||
if ram_reserve_start > 0:
|
||||
f.write('#define HAL_RAM_RESERVE_START 0x%08x\n' % ram_reserve_start)
|
||||
|
||||
f.write('\n// CPU serial number (12 bytes)\n')
|
||||
f.write('#define UDID_START 0x%08x\n\n' % get_mcu_config('UDID_START', True))
|
||||
|
||||
|
@ -696,15 +701,23 @@ def write_ldscript(fname):
|
|||
|
||||
print("Generating ldscript.ld")
|
||||
f = open(fname, 'w')
|
||||
ram0_start = ram_map[0][0]
|
||||
ram0_len = ram_map[0][1] * 1024
|
||||
|
||||
# possibly reserve some memory for app/bootloader comms
|
||||
ram_reserve_start = get_config('RAM_RESERVE_START', default=0, type=int)
|
||||
ram0_start += ram_reserve_start
|
||||
ram0_len -= ram_reserve_start
|
||||
|
||||
f.write('''/* generated ldscript.ld */
|
||||
MEMORY
|
||||
{
|
||||
flash : org = 0x%08x, len = %uK
|
||||
ram0 : org = 0x%08x, len = %uk
|
||||
ram0 : org = 0x%08x, len = %u
|
||||
}
|
||||
|
||||
INCLUDE common.ld
|
||||
''' % (flash_base, flash_length, ram_map[0][0], ram_map[0][1]))
|
||||
''' % (flash_base, flash_length, ram0_start, ram0_len))
|
||||
|
||||
def copy_common_linkerscript(outdir, hwdef):
|
||||
dirpath = os.path.dirname(hwdef)
|
||||
|
|
Loading…
Reference in New Issue