diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/common_mixf.ld b/libraries/AP_HAL_ChibiOS/hwdef/common/common_mixf.ld new file mode 100644 index 0000000000..68895095cc --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/common_mixf.ld @@ -0,0 +1,215 @@ +/* + ChibiOS - Copyright (C) 2006..2015 Giovanni Di Sirio + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/* + this file is included by the board specific ldscript.ld which is + generated from hwdef.dat +*/ + +/* RAM region to be used for Main stack. This stack accommodates the processing + of all exceptions and interrupts*/ +REGION_ALIAS("MAIN_STACK_RAM", ram0); + +/* RAM region to be used for the process stack. This is the stack used by + the main() function.*/ +REGION_ALIAS("PROCESS_STACK_RAM", ram0); + +/* RAM region to be used for data segment.*/ +REGION_ALIAS("DATA_RAM", ram0); + +/* RAM region to be used for BSS segment.*/ +REGION_ALIAS("BSS_RAM", ram0); + +/* RAM region to be used for the default heap.*/ +REGION_ALIAS("HEAP_RAM", ram0); + +__ram0_start__ = ORIGIN(ram0); +__ram0_size__ = LENGTH(ram0); +__ram0_end__ = __ram0_start__ + __ram0_size__; + +ENTRY(Reset_Handler) + +SECTIONS +{ + . = 0; + _text = .; + + startup : ALIGN(16) SUBALIGN(16) + { + KEEP(*(.vectors)) + } > flash + + constructors : ALIGN(4) SUBALIGN(4) + { + __init_array_base__ = .; + KEEP(*(SORT(.init_array.*))) + KEEP(*(.init_array)) + __init_array_end__ = .; + } > flash + + destructors : ALIGN(4) SUBALIGN(4) + { + __fini_array_base__ = .; + KEEP(*(.fini_array)) + KEEP(*(SORT(.fini_array.*))) + __fini_array_end__ = .; + } > flash + + /* External Flash area if defined */ + .extflash : ALIGN(4) SUBALIGN(4) + { + *(.ap_romfs*) + /* moving GCS_MAVLink to ext_flash */ + lib/lib*.a:GCS*.*(.text* .rodata*) + *(.extflash) + } > ext_flash + + .text : ALIGN(4) SUBALIGN(4) + { + /* we want app_descriptor near the start of flash so a false + positive isn't found by the bootloader (eg. ROMFS) */ + KEEP(*(.apsec_data)); + KEEP(*(.app_descriptor)); + *(.text) + *(.text.*) + *(.rodata) + *(.rodata.*) + *(.glue_7t) + *(.glue_7) + *(.gcc*) + } > flash + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > flash + + .ARM.exidx : { + __exidx_start = .; + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + __exidx_end = .; + } > flash + + .eh_frame_hdr : + { + *(.eh_frame_hdr) + } > flash + + .eh_frame : ONLY_IF_RO + { + *(.eh_frame) + } > flash + + .textalign : ONLY_IF_RO + { + . = ALIGN(8); + } > flash + + /* Legacy symbol, not used anywhere.*/ + . = ALIGN(4); + PROVIDE(_etext = .); + + /* Special section for exceptions stack.*/ + .mstack : + { + . = ALIGN(8); + __main_stack_base__ = .; + . += __main_stack_size__; + . = ALIGN(8); + __main_stack_end__ = .; + } > MAIN_STACK_RAM + + /* Special section for process stack.*/ + .pstack : + { + __process_stack_base__ = .; + __main_thread_stack_base__ = .; + . += __process_stack_size__; + . = ALIGN(8); + __process_stack_end__ = .; + __main_thread_stack_end__ = .; + } > PROCESS_STACK_RAM + + .data : ALIGN(4) + { + . = ALIGN(4); + PROVIDE(_textdata = LOADADDR(.data)); + PROVIDE(_data = .); + __textdata_base__ = LOADADDR(.data); + __data_base__ = .; + *(.data) + *(.data.*) + *(.ramtext) + . = ALIGN(4); + PROVIDE(_edata = .); + __data_end__ = .; + } > DATA_RAM AT > flash + + .bss (NOLOAD) : ALIGN(4) + { + . = ALIGN(4); + __bss_base__ = .; + *(.bss) + *(.bss.*) + *(COMMON) + . = ALIGN(4); + __bss_end__ = .; + PROVIDE(end = .); + } > BSS_RAM + + .ram0_init : ALIGN(4) + { + . = ALIGN(4); + __ram0_init_text__ = LOADADDR(.ram0_init); + __ram0_init__ = .; + *(.ram0_init) + *(.ram0_init.*) + . = ALIGN(4); + } > ram0 AT > flash + + .ram0 (NOLOAD) : ALIGN(4) + { + . = ALIGN(4); + __ram0_clear__ = .; + *(.ram0_clear) + *(.ram0_clear.*) + . = ALIGN(4); + __ram0_noinit__ = .; + *(.ram0) + *(.ram0.*) + . = ALIGN(4); + __ram0_free__ = .; + } > ram0 + + /* The default heap uses the (statically) unused part of a RAM section.*/ + .heap (NOLOAD) : + { + . = ALIGN(8); + __heap_base__ = .; + . = ORIGIN(HEAP_RAM) + LENGTH(HEAP_RAM); + __heap_end__ = .; + } > HEAP_RAM + + /* The crash log uses the unused part of a flash section.*/ + .crash_log (NOLOAD) : + { + . = ALIGN(32); + __crash_log_base__ = .; + . = ORIGIN(flash) + LENGTH(flash); + __crash_log_end__ = .; + } > flash + +} diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 77b8569544..86e25a1bc3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -756,7 +756,7 @@ def get_ram_map(): if app_ram_map[0][0] == ram_map[i][0]: env_vars['APP_RAM_START'] = i return ram_map - elif env_vars['EXT_FLASH_SIZE_MB']: + elif env_vars['EXT_FLASH_SIZE_MB'] and not env_vars['INT_FLASH_PRIMARY']: ram_map = get_mcu_config('RAM_MAP_EXTERNAL_FLASH', False) if ram_map is not None: return ram_map @@ -1000,8 +1000,8 @@ def write_mcu_config(f): f.write('#define EXT_FLASH_RESERVE_END_KB %u\n' % get_config('EXT_FLASH_RESERVE_END_KB', default=0, type=int)) env_vars['EXT_FLASH_SIZE_MB'] = get_config('EXT_FLASH_SIZE_MB', default=0, type=int) - - if env_vars['EXT_FLASH_SIZE_MB'] and not args.bootloader: + env_vars['INT_FLASH_PRIMARY'] = get_config('INT_FLASH_PRIMARY', default=False, type=bool) + if env_vars['EXT_FLASH_SIZE_MB'] and not args.bootloader and not env_vars['INT_FLASH_PRIMARY']: f.write('#define CRT0_AREAS_NUMBER 3\n') f.write('#define CRT1_RAMFUNC_ENABLE TRUE\n') # this will enable loading program sections to RAM f.write('#define __FASTRAMFUNC__ __attribute__ ((__section__(".fastramfunc")))\n') @@ -1011,6 +1011,13 @@ def write_mcu_config(f): f.write('#define CRT0_AREAS_NUMBER 1\n') f.write('#define CRT1_RAMFUNC_ENABLE FALSE\n') + if env_vars['INT_FLASH_PRIMARY']: + # this will put methods with low latency requirements into external flash + # and save internal flash space + f.write('#define __EXTFLASHFUNC__ __attribute__ ((__section__(".extflash")))\n') + else: + f.write('#define __EXTFLASHFUNC__\n') + storage_flash_page = get_storage_flash_page() flash_reserve_end = get_config('FLASH_RESERVE_END_KB', default=0, type=int) if storage_flash_page is not None: @@ -1034,7 +1041,7 @@ def write_mcu_config(f): env_vars['ENABLE_CRASHDUMP'] = 0 if args.bootloader: - if env_vars['EXT_FLASH_SIZE_MB']: + if env_vars['EXT_FLASH_SIZE_MB'] and not env_vars['INT_FLASH_PRIMARY']: f.write('\n// location of loaded firmware in external flash\n') f.write('#define APP_START_ADDRESS 0x%08x\n' % (0x90000000 + get_config( 'EXT_FLASH_RESERVE_START_KB', default=0, type=int)*1024)) @@ -1306,6 +1313,7 @@ def write_ldscript(fname): # get external flash if any ext_flash_size = get_config('EXT_FLASH_SIZE_MB', default=0, type=int) + int_flash_primary = get_config('INT_FLASH_PRIMARY', default=False, type=int) if not args.bootloader: flash_length = flash_size - (flash_reserve_start + flash_reserve_end) @@ -1320,6 +1328,9 @@ def write_ldscript(fname): f = open(fname, 'w') ram0_start = ram_map[0][0] ram0_len = ram_map[0][1] * 1024 + if ext_flash_size > 32: + error("We only support 24bit addressing over external flash") + if env_vars['APP_RAM_START'] is None: # default to start of ram for shared ram # possibly reserve some memory for app/bootloader comms @@ -1337,9 +1348,19 @@ MEMORY INCLUDE common.ld ''' % (flash_base, flash_length, ram0_start, ram0_len)) + elif int_flash_primary: + env_vars['HAS_EXTERNAL_FLASH_SECTIONS'] = 1 + f.write('''/* generated ldscript.ld */ +MEMORY +{ + flash : org = 0x%08x, len = %uK + ext_flash : org = 0x%08x, len = %uK + ram0 : org = 0x%08x, len = %u +} + +INCLUDE common_mixf.ld +''' % (flash_base, flash_length, ext_flash_base, ext_flash_length, ram0_start, ram0_len)) else: - if ext_flash_size > 32: - error("We only support 24bit addressing over external flash") env_vars['HAS_EXTERNAL_FLASH_SECTIONS'] = 1 f.write('''/* generated ldscript.ld */ MEMORY @@ -1363,6 +1384,9 @@ def copy_common_linkerscript(outdir): if not get_config('EXT_FLASH_SIZE_MB', default=0, type=int) or args.bootloader: shutil.copy(os.path.join(dirpath, "../common/common.ld"), os.path.join(outdir, "common.ld")) + elif get_config('INT_FLASH_PRIMARY', default=False, type=int): + shutil.copy(os.path.join(dirpath, "../common/common_mixf.ld"), + os.path.join(outdir, "common_mixf.ld")) else: shutil.copy(os.path.join(dirpath, "../common/common_extf.ld"), os.path.join(outdir, "common_extf.ld"))