HAL_ChibiOS: moved to generated loader script

This commit is contained in:
Andrew Tridgell 2018-01-13 12:29:11 +11:00
parent 9482ab1840
commit 6e4ef32628
7 changed files with 55 additions and 1277 deletions

View File

@ -32,15 +32,10 @@
#define MIN_ALIGNMENT 8
#if defined(STM32F427xx) || defined(STM32F405xx)
// 427 and 405 have 64k CCM ram
#define CCM_RAM_ATTRIBUTE __attribute__((section(".ram4")))
#if defined(CCM_RAM_SIZE)
#ifndef CCM_BASE_ADDRESS
#define CCM_BASE_ADDRESS 0x10000000
#endif
#ifdef CCM_RAM_ATTRIBUTE
//CCM RAM Heap
#define CCM_REGION_SIZE 64*1024
CH_HEAP_AREA(ccm_heap_region, CCM_REGION_SIZE) CCM_RAM_ATTRIBUTE;
static memory_heap_t ccm_heap;
static bool ccm_heap_initialised = false;
#endif
@ -48,10 +43,10 @@ static bool ccm_heap_initialised = false;
void *malloc_ccm(size_t size)
{
void *p = NULL;
#ifdef CCM_RAM_ATTRIBUTE
#if defined(CCM_RAM_SIZE)
if (!ccm_heap_initialised) {
ccm_heap_initialised = true;
chHeapObjectInit(&ccm_heap, ccm_heap_region, CCM_REGION_SIZE);
chHeapObjectInit(&ccm_heap, (void *)CCM_BASE_ADDRESS, CCM_RAM_SIZE*1024);
}
p = chHeapAllocAligned(&ccm_heap, size, CH_HEAP_ALIGNMENT);
if (p != NULL) {
@ -100,7 +95,7 @@ size_t mem_available(void)
// we also need to add in memory that is not yet allocated to the heap
totalp += chCoreGetStatusX();
#ifdef CCM_RAM_ATTRIBUTE
#if defined(CCM_RAM_SIZE)
size_t ccm_available = 0;
chHeapStatus(&ccm_heap, &ccm_available, NULL);
totalp += ccm_available;

View File

@ -1,393 +0,0 @@
/*
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.
*/
/*
* ST32F429xI memory setup.
* Note: Use of ram1, ram2 and ram3 is mutually exclusive with use of ram0.
*/
MEMORY
{
flash : org = 0x08004000, len = 2032K
ram0 : org = 0x20000000, len = 192k /* SRAM1 + SRAM2 + SRAM3 */
ram1 : org = 0x20000000, len = 112k /* SRAM1 */
ram2 : org = 0x2001C000, len = 16k /* SRAM2 */
ram3 : org = 0x20020000, len = 64k /* SRAM3 */
ram4 : org = 0x10000000, len = 64k /* CCM SRAM */
ram5 : org = 0x40024000, len = 4k /* BCKP SRAM */
ram6 : org = 0x00000000, len = 0
ram7 : org = 0x00000000, len = 0
}
/* 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__;
__ram1_start__ = ORIGIN(ram1);
__ram1_size__ = LENGTH(ram1);
__ram1_end__ = __ram1_start__ + __ram1_size__;
__ram2_start__ = ORIGIN(ram2);
__ram2_size__ = LENGTH(ram2);
__ram2_end__ = __ram2_start__ + __ram2_size__;
__ram3_start__ = ORIGIN(ram3);
__ram3_size__ = LENGTH(ram3);
__ram3_end__ = __ram3_start__ + __ram3_size__;
__ram4_start__ = ORIGIN(ram4);
__ram4_size__ = LENGTH(ram4);
__ram4_end__ = __ram4_start__ + __ram4_size__;
__ram5_start__ = ORIGIN(ram5);
__ram5_size__ = LENGTH(ram5);
__ram5_end__ = __ram5_start__ + __ram5_size__;
__ram6_start__ = ORIGIN(ram6);
__ram6_size__ = LENGTH(ram6);
__ram6_end__ = __ram6_start__ + __ram6_size__;
__ram7_start__ = ORIGIN(ram7);
__ram7_size__ = LENGTH(ram7);
__ram7_end__ = __ram7_start__ + __ram7_size__;
ENTRY(Reset_Handler)
SECTIONS
{
. = 0;
_text = .;
startup : ALIGN(16) SUBALIGN(16)
{
KEEP(*(.vectors))
} > flash
constructors : ALIGN(4) SUBALIGN(4)
{
__init_array_start = .;
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
__init_array_end = .;
} > flash
destructors : ALIGN(4) SUBALIGN(4)
{
__fini_array_start = .;
KEEP(*(.fini_array))
KEEP(*(SORT(.fini_array.*)))
__fini_array_end = .;
} > flash
.text : ALIGN(16) SUBALIGN(16)
{
*(.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_start = LOADADDR(.data);
_data_start = .;
*(.data)
*(.data.*)
*(.ramtext)
. = ALIGN(4);
PROVIDE(_edata = .);
_data_end = .;
} > DATA_RAM AT > flash
.bss (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
_bss_start = .;
*(.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
.ram1_init : ALIGN(4)
{
. = ALIGN(4);
__ram1_init_text__ = LOADADDR(.ram1_init);
__ram1_init__ = .;
*(.ram1_init)
*(.ram1_init.*)
. = ALIGN(4);
} > ram1 AT > flash
.ram1 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram1_clear__ = .;
*(.ram1_clear)
*(.ram1_clear.*)
. = ALIGN(4);
__ram1_noinit__ = .;
*(.ram1)
*(.ram1.*)
. = ALIGN(4);
__ram1_free__ = .;
} > ram1
.ram2_init : ALIGN(4)
{
. = ALIGN(4);
__ram2_init_text__ = LOADADDR(.ram2_init);
__ram2_init__ = .;
*(.ram2_init)
*(.ram2_init.*)
. = ALIGN(4);
} > ram2 AT > flash
.ram2 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram2_clear__ = .;
*(.ram2_clear)
*(.ram2_clear.*)
. = ALIGN(4);
__ram2_noinit__ = .;
*(.ram2)
*(.ram2.*)
. = ALIGN(4);
__ram2_free__ = .;
} > ram2
.ram3_init : ALIGN(4)
{
. = ALIGN(4);
__ram3_init_text__ = LOADADDR(.ram3_init);
__ram3_init__ = .;
*(.ram3_init)
*(.ram3_init.*)
. = ALIGN(4);
} > ram3 AT > flash
.ram3 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram3_clear__ = .;
*(.ram3_clear)
*(.ram3_clear.*)
. = ALIGN(4);
__ram3_noinit__ = .;
*(.ram3)
*(.ram3.*)
. = ALIGN(4);
__ram3_free__ = .;
} > ram3
.ram4_init : ALIGN(4)
{
. = ALIGN(4);
__ram4_init_text__ = LOADADDR(.ram4_init);
__ram4_init__ = .;
*(.ram4_init)
*(.ram4_init.*)
. = ALIGN(4);
} > ram4 AT > flash
.ram4 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram4_clear__ = .;
*(.ram4_clear)
*(.ram4_clear.*)
. = ALIGN(4);
__ram4_noinit__ = .;
*(.ram4)
*(.ram4.*)
. = ALIGN(4);
__ram4_free__ = .;
} > ram4
.ram5_init : ALIGN(4)
{
. = ALIGN(4);
__ram5_init_text__ = LOADADDR(.ram5_init);
__ram5_init__ = .;
*(.ram5_init)
*(.ram5_init.*)
. = ALIGN(4);
} > ram5 AT > flash
.ram5 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram5_clear__ = .;
*(.ram5_clear)
*(.ram5_clear.*)
. = ALIGN(4);
__ram5_noinit__ = .;
*(.ram5)
*(.ram5.*)
. = ALIGN(4);
__ram5_free__ = .;
} > ram5
.ram6_init : ALIGN(4)
{
. = ALIGN(4);
__ram6_init_text__ = LOADADDR(.ram6_init);
__ram6_init__ = .;
*(.ram6_init)
*(.ram6_init.*)
. = ALIGN(4);
} > ram6 AT > flash
.ram6 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram6_clear__ = .;
*(.ram6_clear)
*(.ram6_clear.*)
. = ALIGN(4);
__ram6_noinit__ = .;
*(.ram6)
*(.ram6.*)
. = ALIGN(4);
__ram6_free__ = .;
} > ram6
.ram7_init : ALIGN(4)
{
. = ALIGN(4);
__ram7_init_text__ = LOADADDR(.ram7_init);
__ram7_init__ = .;
*(.ram7_init)
*(.ram7_init.*)
. = ALIGN(4);
} > ram7 AT > flash
.ram7 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram7_clear__ = .;
*(.ram7_clear)
*(.ram7_clear.*)
. = ALIGN(4);
__ram7_noinit__ = .;
*(.ram7)
*(.ram7.*)
. = ALIGN(4);
__ram7_free__ = .;
} > ram7
/* 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
}

View File

@ -1,393 +0,0 @@
/*
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.
*/
/*
* ST32F429xI memory setup.
* Note: Use of ram1, ram2 and ram3 is mutually exclusive with use of ram0.
*/
MEMORY
{
flash : org = 0x08004000, len = 2032K
ram0 : org = 0x20000000, len = 192k /* SRAM1 + SRAM2 + SRAM3 */
ram1 : org = 0x20000000, len = 112k /* SRAM1 */
ram2 : org = 0x2001C000, len = 16k /* SRAM2 */
ram3 : org = 0x20020000, len = 64k /* SRAM3 */
ram4 : org = 0x10000000, len = 64k /* CCM SRAM */
ram5 : org = 0x40024000, len = 4k /* BCKP SRAM */
ram6 : org = 0x00000000, len = 0
ram7 : org = 0x00000000, len = 0
}
/* 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__;
__ram1_start__ = ORIGIN(ram1);
__ram1_size__ = LENGTH(ram1);
__ram1_end__ = __ram1_start__ + __ram1_size__;
__ram2_start__ = ORIGIN(ram2);
__ram2_size__ = LENGTH(ram2);
__ram2_end__ = __ram2_start__ + __ram2_size__;
__ram3_start__ = ORIGIN(ram3);
__ram3_size__ = LENGTH(ram3);
__ram3_end__ = __ram3_start__ + __ram3_size__;
__ram4_start__ = ORIGIN(ram4);
__ram4_size__ = LENGTH(ram4);
__ram4_end__ = __ram4_start__ + __ram4_size__;
__ram5_start__ = ORIGIN(ram5);
__ram5_size__ = LENGTH(ram5);
__ram5_end__ = __ram5_start__ + __ram5_size__;
__ram6_start__ = ORIGIN(ram6);
__ram6_size__ = LENGTH(ram6);
__ram6_end__ = __ram6_start__ + __ram6_size__;
__ram7_start__ = ORIGIN(ram7);
__ram7_size__ = LENGTH(ram7);
__ram7_end__ = __ram7_start__ + __ram7_size__;
ENTRY(Reset_Handler)
SECTIONS
{
. = 0;
_text = .;
startup : ALIGN(16) SUBALIGN(16)
{
KEEP(*(.vectors))
} > flash
constructors : ALIGN(4) SUBALIGN(4)
{
__init_array_start = .;
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
__init_array_end = .;
} > flash
destructors : ALIGN(4) SUBALIGN(4)
{
__fini_array_start = .;
KEEP(*(.fini_array))
KEEP(*(SORT(.fini_array.*)))
__fini_array_end = .;
} > flash
.text : ALIGN(16) SUBALIGN(16)
{
*(.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_start = LOADADDR(.data);
_data_start = .;
*(.data)
*(.data.*)
*(.ramtext)
. = ALIGN(4);
PROVIDE(_edata = .);
_data_end = .;
} > DATA_RAM AT > flash
.bss (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
_bss_start = .;
*(.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
.ram1_init : ALIGN(4)
{
. = ALIGN(4);
__ram1_init_text__ = LOADADDR(.ram1_init);
__ram1_init__ = .;
*(.ram1_init)
*(.ram1_init.*)
. = ALIGN(4);
} > ram1 AT > flash
.ram1 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram1_clear__ = .;
*(.ram1_clear)
*(.ram1_clear.*)
. = ALIGN(4);
__ram1_noinit__ = .;
*(.ram1)
*(.ram1.*)
. = ALIGN(4);
__ram1_free__ = .;
} > ram1
.ram2_init : ALIGN(4)
{
. = ALIGN(4);
__ram2_init_text__ = LOADADDR(.ram2_init);
__ram2_init__ = .;
*(.ram2_init)
*(.ram2_init.*)
. = ALIGN(4);
} > ram2 AT > flash
.ram2 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram2_clear__ = .;
*(.ram2_clear)
*(.ram2_clear.*)
. = ALIGN(4);
__ram2_noinit__ = .;
*(.ram2)
*(.ram2.*)
. = ALIGN(4);
__ram2_free__ = .;
} > ram2
.ram3_init : ALIGN(4)
{
. = ALIGN(4);
__ram3_init_text__ = LOADADDR(.ram3_init);
__ram3_init__ = .;
*(.ram3_init)
*(.ram3_init.*)
. = ALIGN(4);
} > ram3 AT > flash
.ram3 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram3_clear__ = .;
*(.ram3_clear)
*(.ram3_clear.*)
. = ALIGN(4);
__ram3_noinit__ = .;
*(.ram3)
*(.ram3.*)
. = ALIGN(4);
__ram3_free__ = .;
} > ram3
.ram4_init : ALIGN(4)
{
. = ALIGN(4);
__ram4_init_text__ = LOADADDR(.ram4_init);
__ram4_init__ = .;
*(.ram4_init)
*(.ram4_init.*)
. = ALIGN(4);
} > ram4 AT > flash
.ram4 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram4_clear__ = .;
*(.ram4_clear)
*(.ram4_clear.*)
. = ALIGN(4);
__ram4_noinit__ = .;
*(.ram4)
*(.ram4.*)
. = ALIGN(4);
__ram4_free__ = .;
} > ram4
.ram5_init : ALIGN(4)
{
. = ALIGN(4);
__ram5_init_text__ = LOADADDR(.ram5_init);
__ram5_init__ = .;
*(.ram5_init)
*(.ram5_init.*)
. = ALIGN(4);
} > ram5 AT > flash
.ram5 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram5_clear__ = .;
*(.ram5_clear)
*(.ram5_clear.*)
. = ALIGN(4);
__ram5_noinit__ = .;
*(.ram5)
*(.ram5.*)
. = ALIGN(4);
__ram5_free__ = .;
} > ram5
.ram6_init : ALIGN(4)
{
. = ALIGN(4);
__ram6_init_text__ = LOADADDR(.ram6_init);
__ram6_init__ = .;
*(.ram6_init)
*(.ram6_init.*)
. = ALIGN(4);
} > ram6 AT > flash
.ram6 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram6_clear__ = .;
*(.ram6_clear)
*(.ram6_clear.*)
. = ALIGN(4);
__ram6_noinit__ = .;
*(.ram6)
*(.ram6.*)
. = ALIGN(4);
__ram6_free__ = .;
} > ram6
.ram7_init : ALIGN(4)
{
. = ALIGN(4);
__ram7_init_text__ = LOADADDR(.ram7_init);
__ram7_init__ = .;
*(.ram7_init)
*(.ram7_init.*)
. = ALIGN(4);
} > ram7 AT > flash
.ram7 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram7_clear__ = .;
*(.ram7_clear)
*(.ram7_clear.*)
. = ALIGN(4);
__ram7_noinit__ = .;
*(.ram7)
*(.ram7.*)
. = ALIGN(4);
__ram7_free__ = .;
} > ram7
/* 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
}

View File

@ -21,6 +21,15 @@ STM32_VDD 330U
# flash size
FLASH_SIZE_KB 2048
# space to reserve for bootloader and storage at start of flash
FLASH_RESERVE_START_KB 16
# space to reserve for storage at end of flash
FLASH_RESERVE_END_KB 0
# this board has 64k of CCM memory
CCM_RAM_SIZE_KB 64
# serial port for stdout
STDOUT_SERIAL SD7
STDOUT_BAUDRATE 57600

View File

@ -1,393 +0,0 @@
/*
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.
*/
/*
* ST32F429xI memory setup.
* Note: Use of ram1, ram2 and ram3 is mutually exclusive with use of ram0.
*/
MEMORY
{
flash : org = 0x08004000, len = 2032K
ram0 : org = 0x20000000, len = 192k /* SRAM1 + SRAM2 + SRAM3 */
ram1 : org = 0x20000000, len = 112k /* SRAM1 */
ram2 : org = 0x2001C000, len = 16k /* SRAM2 */
ram3 : org = 0x20020000, len = 64k /* SRAM3 */
ram4 : org = 0x10000000, len = 64k /* CCM SRAM */
ram5 : org = 0x40024000, len = 4k /* BCKP SRAM */
ram6 : org = 0x00000000, len = 0
ram7 : org = 0x00000000, len = 0
}
/* 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__;
__ram1_start__ = ORIGIN(ram1);
__ram1_size__ = LENGTH(ram1);
__ram1_end__ = __ram1_start__ + __ram1_size__;
__ram2_start__ = ORIGIN(ram2);
__ram2_size__ = LENGTH(ram2);
__ram2_end__ = __ram2_start__ + __ram2_size__;
__ram3_start__ = ORIGIN(ram3);
__ram3_size__ = LENGTH(ram3);
__ram3_end__ = __ram3_start__ + __ram3_size__;
__ram4_start__ = ORIGIN(ram4);
__ram4_size__ = LENGTH(ram4);
__ram4_end__ = __ram4_start__ + __ram4_size__;
__ram5_start__ = ORIGIN(ram5);
__ram5_size__ = LENGTH(ram5);
__ram5_end__ = __ram5_start__ + __ram5_size__;
__ram6_start__ = ORIGIN(ram6);
__ram6_size__ = LENGTH(ram6);
__ram6_end__ = __ram6_start__ + __ram6_size__;
__ram7_start__ = ORIGIN(ram7);
__ram7_size__ = LENGTH(ram7);
__ram7_end__ = __ram7_start__ + __ram7_size__;
ENTRY(Reset_Handler)
SECTIONS
{
. = 0;
_text = .;
startup : ALIGN(16) SUBALIGN(16)
{
KEEP(*(.vectors))
} > flash
constructors : ALIGN(4) SUBALIGN(4)
{
__init_array_start = .;
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
__init_array_end = .;
} > flash
destructors : ALIGN(4) SUBALIGN(4)
{
__fini_array_start = .;
KEEP(*(.fini_array))
KEEP(*(SORT(.fini_array.*)))
__fini_array_end = .;
} > flash
.text : ALIGN(16) SUBALIGN(16)
{
*(.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_start = LOADADDR(.data);
_data_start = .;
*(.data)
*(.data.*)
*(.ramtext)
. = ALIGN(4);
PROVIDE(_edata = .);
_data_end = .;
} > DATA_RAM AT > flash
.bss (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
_bss_start = .;
*(.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
.ram1_init : ALIGN(4)
{
. = ALIGN(4);
__ram1_init_text__ = LOADADDR(.ram1_init);
__ram1_init__ = .;
*(.ram1_init)
*(.ram1_init.*)
. = ALIGN(4);
} > ram1 AT > flash
.ram1 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram1_clear__ = .;
*(.ram1_clear)
*(.ram1_clear.*)
. = ALIGN(4);
__ram1_noinit__ = .;
*(.ram1)
*(.ram1.*)
. = ALIGN(4);
__ram1_free__ = .;
} > ram1
.ram2_init : ALIGN(4)
{
. = ALIGN(4);
__ram2_init_text__ = LOADADDR(.ram2_init);
__ram2_init__ = .;
*(.ram2_init)
*(.ram2_init.*)
. = ALIGN(4);
} > ram2 AT > flash
.ram2 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram2_clear__ = .;
*(.ram2_clear)
*(.ram2_clear.*)
. = ALIGN(4);
__ram2_noinit__ = .;
*(.ram2)
*(.ram2.*)
. = ALIGN(4);
__ram2_free__ = .;
} > ram2
.ram3_init : ALIGN(4)
{
. = ALIGN(4);
__ram3_init_text__ = LOADADDR(.ram3_init);
__ram3_init__ = .;
*(.ram3_init)
*(.ram3_init.*)
. = ALIGN(4);
} > ram3 AT > flash
.ram3 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram3_clear__ = .;
*(.ram3_clear)
*(.ram3_clear.*)
. = ALIGN(4);
__ram3_noinit__ = .;
*(.ram3)
*(.ram3.*)
. = ALIGN(4);
__ram3_free__ = .;
} > ram3
.ram4_init : ALIGN(4)
{
. = ALIGN(4);
__ram4_init_text__ = LOADADDR(.ram4_init);
__ram4_init__ = .;
*(.ram4_init)
*(.ram4_init.*)
. = ALIGN(4);
} > ram4 AT > flash
.ram4 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram4_clear__ = .;
*(.ram4_clear)
*(.ram4_clear.*)
. = ALIGN(4);
__ram4_noinit__ = .;
*(.ram4)
*(.ram4.*)
. = ALIGN(4);
__ram4_free__ = .;
} > ram4
.ram5_init : ALIGN(4)
{
. = ALIGN(4);
__ram5_init_text__ = LOADADDR(.ram5_init);
__ram5_init__ = .;
*(.ram5_init)
*(.ram5_init.*)
. = ALIGN(4);
} > ram5 AT > flash
.ram5 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram5_clear__ = .;
*(.ram5_clear)
*(.ram5_clear.*)
. = ALIGN(4);
__ram5_noinit__ = .;
*(.ram5)
*(.ram5.*)
. = ALIGN(4);
__ram5_free__ = .;
} > ram5
.ram6_init : ALIGN(4)
{
. = ALIGN(4);
__ram6_init_text__ = LOADADDR(.ram6_init);
__ram6_init__ = .;
*(.ram6_init)
*(.ram6_init.*)
. = ALIGN(4);
} > ram6 AT > flash
.ram6 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram6_clear__ = .;
*(.ram6_clear)
*(.ram6_clear.*)
. = ALIGN(4);
__ram6_noinit__ = .;
*(.ram6)
*(.ram6.*)
. = ALIGN(4);
__ram6_free__ = .;
} > ram6
.ram7_init : ALIGN(4)
{
. = ALIGN(4);
__ram7_init_text__ = LOADADDR(.ram7_init);
__ram7_init__ = .;
*(.ram7_init)
*(.ram7_init.*)
. = ALIGN(4);
} > ram7 AT > flash
.ram7 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram7_clear__ = .;
*(.ram7_clear)
*(.ram7_clear.*)
. = ALIGN(4);
__ram7_noinit__ = .;
*(.ram7)
*(.ram7.*)
. = ALIGN(4);
__ram7_free__ = .;
} > ram7
/* 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
}

View File

@ -305,10 +305,47 @@ def write_mcu_config(f):
f.write('#define HRT_TIMER GPTD%u\n' % hrt_timer)
f.write('#define STM32_GPT_USE_TIM%u TRUE\n' % hrt_timer)
flash_size = get_config('FLASH_SIZE_KB', need_int=True)
f.write('#define BOARD_FLASH_SIZE %u' % flash_size)
f.write('#define BOARD_FLASH_SIZE %u\n' % flash_size)
f.write('#define CRT1_AREAS_NUMBER 1\n')
if mcu_type in ['STM32F427xx', 'STM32F405xx']:
def_ccm_size = 64
else:
def_ccm_size = None
ccm_size = get_config('CCM_RAM_SIZE_KB', default=def_ccm_size, required=False, need_int=True)
if ccm_size is not None:
f.write('#define CCM_RAM_SIZE %u\n' % ccm_size)
f.write('\n')
def write_ldscript(fname):
'''write ldscript.ld for this board'''
flash_size = get_config('FLASH_SIZE_KB', need_int=True)
# space to reserve for bootloader and storage at start of flash
flash_reserve_start = get_config('FLASH_RESERVE_START_KB', default=16, need_int=True)
# space to reserve for storage at end of flash
flash_reserve_end = get_config('FLASH_RESERVE_END_KB', default=0, need_int=True)
# ram size
ram_size = get_config('RAM_SIZE_KB', default=192)
flash_base = 0x08000000 + flash_reserve_start*1024
flash_length = flash_size - (flash_reserve_start + flash_reserve_end)
print("Generating ldscript.ld")
f = open(fname, 'w')
f.write('''/* generated ldscript.ld */
MEMORY
{
flash : org = 0x%08x, len = %uK
ram0 : org = 0x20000000, len = %uk
}
INCLUDE common.ld
''' % (flash_base, flash_length, ram_size))
def write_USB_config(f):
'''write USB config defines'''
if not 'USB_VENDOR' in config:
@ -680,3 +717,5 @@ periph_list = build_peripheral_list()
# write out hwdef.h
write_hwdef_header(os.path.join(outdir, "hwdef.h"))
# write out ldscript.ld
write_ldscript(os.path.join(outdir, "ldscript.ld"))

View File

@ -1,86 +0,0 @@
/*
ChibiOS - Copyright (C) 2006..2016 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.
*/
/*
* STM32F412xG memory setup.
*/
MEMORY
{
/* leave space for bootloader and two storage sectors */
flash0 : org = 0x0800C000, len = 952k
flash1 : org = 0x00000000, len = 0
flash2 : org = 0x00000000, len = 0
flash3 : org = 0x00000000, len = 0
flash4 : org = 0x00000000, len = 0
flash5 : org = 0x00000000, len = 0
flash6 : org = 0x00000000, len = 0
flash7 : org = 0x00000000, len = 0
ram0 : org = 0x20000000, len = 256k
ram1 : org = 0x00000000, len = 0
ram2 : org = 0x00000000, len = 0
ram3 : org = 0x00000000, len = 0
ram4 : org = 0x00000000, len = 0
ram5 : org = 0x00000000, len = 0
ram6 : org = 0x00000000, len = 0
ram7 : org = 0x00000000, len = 0
}
/* For each data/text section two region are defined, a virtual region
and a load region (_LMA suffix).*/
/* Flash region to be used for exception vectors.*/
REGION_ALIAS("VECTORS_FLASH", flash0);
REGION_ALIAS("VECTORS_FLASH_LMA", flash0);
/* Flash region to be used for constructors and destructors.*/
REGION_ALIAS("XTORS_FLASH", flash0);
REGION_ALIAS("XTORS_FLASH_LMA", flash0);
/* Flash region to be used for code text.*/
REGION_ALIAS("TEXT_FLASH", flash0);
REGION_ALIAS("TEXT_FLASH_LMA", flash0);
/* Flash region to be used for read only data.*/
REGION_ALIAS("RODATA_FLASH", flash0);
REGION_ALIAS("RODATA_FLASH_LMA", flash0);
/* Flash region to be used for various.*/
REGION_ALIAS("VARIOUS_FLASH", flash0);
REGION_ALIAS("VARIOUS_FLASH_LMA", flash0);
/* Flash region to be used for RAM(n) initialization data.*/
REGION_ALIAS("RAM_INIT_FLASH_LMA", flash0);
/* 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);
REGION_ALIAS("DATA_RAM_LMA", flash0);
/* 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);
/* Generic rules inclusion.*/
INCLUDE rules.ld