Skip to content

Commit

Permalink
AP_HAL_ChibiOS: add config for supporting load from external flash
Browse files Browse the repository at this point in the history
  • Loading branch information
bugobliterator authored and tridge committed Sep 1, 2021
1 parent 75bcc76 commit 4ba2835
Show file tree
Hide file tree
Showing 2 changed files with 229 additions and 5 deletions.
200 changes: 200 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld
Original file line number Diff line number Diff line change
@@ -0,0 +1,200 @@
/*
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))
} > irq_flash

constructors : ALIGN(4) SUBALIGN(4)
{
__init_array_base__ = .;
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
__init_array_end__ = .;
} > irq_flash

destructors : ALIGN(4) SUBALIGN(4)
{
__fini_array_base__ = .;
KEEP(*(.fini_array))
KEEP(*(SORT(.fini_array.*)))
__fini_array_end__ = .;
} > irq_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(*(.app_descriptor));
*(.text)
*(.text.*)
*(.rodata)
*(.rodata.*)
*(.glue_7t)
*(.glue_7)
*(.gcc*)
} > default_flash

.irq : ALIGN(4) SUBALIGN(4)
{
*(.irq)
} > irq_flash

.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > default_flash

.ARM.exidx : {
__exidx_start = .;
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
__exidx_end = .;
} > default_flash

.eh_frame_hdr :
{
*(.eh_frame_hdr)
} > default_flash

.eh_frame : ONLY_IF_RO
{
*(.eh_frame)
} > default_flash

.textalign : ONLY_IF_RO
{
. = ALIGN(8);
} > default_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 > default_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 > default_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
}
34 changes: 29 additions & 5 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
Original file line number Diff line number Diff line change
Expand Up @@ -769,12 +769,14 @@ def write_mcu_config(f):
f.write('\n// location of loaded firmware\n')
f.write('#define FLASH_LOAD_ADDRESS 0x%08x\n' % (0x08000000 + flash_reserve_start*1024))
f.write('#define EXTERNAL_PROG_FLASH_MB %u\n' % get_config('EXTERNAL_PROG_FLASH_MB', default=0, type=int))

env_vars['EXTERNAL_PROG_FLASH_MB'] = get_config('EXTERNAL_PROG_FLASH_MB', default=0, type=int)
if args.bootloader:
f.write('#define FLASH_BOOTLOADER_LOAD_KB %u\n' % get_config('FLASH_BOOTLOADER_LOAD_KB', type=int))
f.write('#define FLASH_RESERVE_END_KB %u\n' % get_config('FLASH_RESERVE_END_KB', default=0, type=int))
f.write('#define APP_START_OFFSET_KB %u\n' % get_config('APP_START_OFFSET_KB', default=0, type=int))

else:
f.write('#define PORT_IRQ_ATTRIBUTES __attribute__((section(".irq")))')
f.write('\n')

ram_map = get_mcu_config('RAM_MAP', True)
Expand Down Expand Up @@ -922,6 +924,7 @@ def write_ldscript(fname):
ram_map = get_mcu_config('RAM_MAP', True)

flash_base = 0x08000000 + flash_reserve_start * 1024
ext_flash_base = 0x90000000

if not args.bootloader:
flash_length = flash_size - (flash_reserve_start + flash_reserve_end)
Expand All @@ -939,8 +942,10 @@ def write_ldscript(fname):
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 */
ext_flash_length = get_config('EXTERNAL_PROG_FLASH_MB', default=0, type=int)
if ext_flash_length == 0 or args.bootloader:
env_vars['HAS_EXTERNAL_FLASH_SECTIONS'] = 0
f.write('''/* generated ldscript.ld */
MEMORY
{
flash : org = 0x%08x, len = %uK
Expand All @@ -949,12 +954,31 @@ def write_ldscript(fname):
INCLUDE common.ld
''' % (flash_base, flash_length, ram0_start, ram0_len))
else:
if ext_flash_length > 32:
error("We only support 24bit addressing over external flash")
env_vars['HAS_EXTERNAL_FLASH_SECTIONS'] = 1
f.write('''/* generated ldscript.ld */
MEMORY
{
default_flash : org = 0x%08x, len = %uM
irq_flash : org = 0x%08x, len = %uK
ram0 : org = 0x%08x, len = %u
}
INCLUDE common_extf.ld
''' % (ext_flash_base, ext_flash_length,
flash_base, flash_length,
ram0_start, ram0_len))

def copy_common_linkerscript(outdir, hwdef):
dirpath = os.path.dirname(hwdef)
shutil.copy(os.path.join(dirpath, "../common/common.ld"),
os.path.join(outdir, "common.ld"))
if not get_config('EXTERNAL_PROG_FLASH_MB', default=0, type=int) or args.bootloader:
shutil.copy(os.path.join(dirpath, "../common/common.ld"),
os.path.join(outdir, "common.ld"))
else:
shutil.copy(os.path.join(dirpath, "../common/common_extf.ld"),
os.path.join(outdir, "common_extf.ld"))

def get_USB_IDs():
'''return tuple of USB VID/PID'''
Expand Down

0 comments on commit 4ba2835

Please sign in to comment.