From 83d4facb0efa8c8c05014f0d34cadaefa262477d Mon Sep 17 00:00:00 2001 From: Andreas Rebert Date: Thu, 31 Oct 2013 13:25:58 +0100 Subject: [PATCH 1/2] Added support for GCC_ARM --- workspace_tools/export/gccarm.py | 2 +- workspace_tools/targets.py | 2 +- workspace_tools/toolchains/gcc.py | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/workspace_tools/export/gccarm.py b/workspace_tools/export/gccarm.py index 8718e3a45c9..daca507a8c9 100644 --- a/workspace_tools/export/gccarm.py +++ b/workspace_tools/export/gccarm.py @@ -21,7 +21,7 @@ class GccArm(Exporter): NAME = 'GccArm' TOOLCHAIN = 'GCC_ARM' - TARGETS = ['LPC1768'] + TARGETS = ['LPC1768', 'LPC4088'] DOT_IN_RELATIVE_PATH = True def generate(self): diff --git a/workspace_tools/targets.py b/workspace_tools/targets.py index 6e2f33d78eb..33669de5136 100644 --- a/workspace_tools/targets.py +++ b/workspace_tools/targets.py @@ -167,7 +167,7 @@ def __init__(self): self.extra_labels = ['NXP', 'LPC408X'] - self.supported_toolchains = ["ARM", "GCC_CR"] + self.supported_toolchains = ["ARM", "GCC_CR", "GCC_ARM"] # Use this target to generate the custom binary image for LPC4088 EA boards class LPC4088_EA(LPC4088): diff --git a/workspace_tools/toolchains/gcc.py b/workspace_tools/toolchains/gcc.py index b74c1bd6384..96446480391 100644 --- a/workspace_tools/toolchains/gcc.py +++ b/workspace_tools/toolchains/gcc.py @@ -167,7 +167,7 @@ def __init__(self, target, options=None, notify=None, macros=None): # Use latest gcc nanolib self.ld.append("--specs=nano.specs") - if target.name in ["LPC1768"]: + if target.name in ["LPC1768", "LPC4088"]: self.ld.extend(["-u", "_printf_float", "-u", "_scanf_float"]) self.sys_libs.append("nosys") From 09cf4ef12886d26cb761e40108bdf8d278e841ff Mon Sep 17 00:00:00 2001 From: Andreas Rebert Date: Thu, 31 Oct 2013 13:28:05 +0100 Subject: [PATCH 2/2] Support for exporting to GCC_ARM --- .../TOOLCHAIN_GCC_ARM/LPC4088.ld | 172 +++++++++++++ .../TOOLCHAIN_GCC_ARM/startup_LPC408x.s | 231 ++++++++++++++++++ workspace_tools/export/gcc_arm_lpc4088.tmpl | 46 ++++ 3 files changed, 449 insertions(+) create mode 100644 libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_ARM/LPC4088.ld create mode 100644 libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_ARM/startup_LPC408x.s create mode 100644 workspace_tools/export/gcc_arm_lpc4088.tmpl diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_ARM/LPC4088.ld b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_ARM/LPC4088.ld new file mode 100644 index 00000000000..364154d143a --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_ARM/LPC4088.ld @@ -0,0 +1,172 @@ +/* Linker script for mbed LPC1768 */ + +/* Linker script to configure memory regions. */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 512K + RAM (rwx) : ORIGIN = 0x100000E8, LENGTH = (32K - 0xE8) + + USB_RAM(rwx) : ORIGIN = 0x20000000, LENGTH = 16K + ETH_RAM(rwx) : ORIGIN = 0x20004000, LENGTH = 16K +} + +/* Linker script to place sections and symbol values. Should be used together + * with other linker script that defines memory regions FLASH and RAM. + * It references following symbols, which must be defined in code: + * Reset_Handler : Entry of reset handler + * + * It defines following symbols, which code can use without definition: + * __exidx_start + * __exidx_end + * __etext + * __data_start__ + * __preinit_array_start + * __preinit_array_end + * __init_array_start + * __init_array_end + * __fini_array_start + * __fini_array_end + * __data_end__ + * __bss_start__ + * __bss_end__ + * __end__ + * end + * __HeapLimit + * __StackLimit + * __StackTop + * __stack + */ +ENTRY(Reset_Handler) + +SECTIONS +{ + .text : + { + KEEP(*(.isr_vector)) + *(.text*) + + KEEP(*(.init)) + KEEP(*(.fini)) + + /* .ctors */ + *crtbegin.o(.ctors) + *crtbegin?.o(.ctors) + *(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors) + *(SORT(.ctors.*)) + *(.ctors) + + /* .dtors */ + *crtbegin.o(.dtors) + *crtbegin?.o(.dtors) + *(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors) + *(SORT(.dtors.*)) + *(.dtors) + + *(.rodata*) + + KEEP(*(.eh_frame*)) + } > FLASH + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > FLASH + + __exidx_start = .; + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > FLASH + __exidx_end = .; + + __etext = .; + + .data : AT (__etext) + { + __data_start__ = .; + Image$$RW_IRAM1$$Base = .; + *(vtable) + *(.data*) + + . = ALIGN(4); + /* preinit data */ + PROVIDE (__preinit_array_start = .); + KEEP(*(.preinit_array)) + PROVIDE (__preinit_array_end = .); + + . = ALIGN(4); + /* init data */ + PROVIDE (__init_array_start = .); + KEEP(*(SORT(.init_array.*))) + KEEP(*(.init_array)) + PROVIDE (__init_array_end = .); + + + . = ALIGN(4); + /* finit data */ + PROVIDE (__fini_array_start = .); + KEEP(*(SORT(.fini_array.*))) + KEEP(*(.fini_array)) + PROVIDE (__fini_array_end = .); + + . = ALIGN(4); + /* All data end */ + __data_end__ = .; + + } > RAM + + + .bss : + { + __bss_start__ = .; + *(.bss*) + *(COMMON) + __bss_end__ = .; + Image$$RW_IRAM1$$ZI$$Limit = . ; + } > RAM + + + .heap : + { + __end__ = .; + end = __end__; + *(.heap*) + __HeapLimit = .; + } > RAM + + /* .stack_dummy section doesn't contains any symbols. It is only + * used for linker to calculate size of stack sections, and assign + * values to stack symbols later */ + .stack_dummy : + { + *(.stack) + } > RAM + + /* Set stack top to end of RAM, and stack limit move down by + * size of stack_dummy section */ + __StackTop = ORIGIN(RAM) + LENGTH(RAM); + __StackLimit = __StackTop - SIZEOF(.stack_dummy); + PROVIDE(__stack = __StackTop); + + /* Check if data + heap + stack exceeds RAM limit */ + ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack") + + + /* Code can explicitly ask for data to be + placed in these higher RAM banks where + they will be left uninitialized. + */ + .AHBSRAM0 (NOLOAD): + { + Image$$RW_IRAM2$$Base = . ; + *(AHBSRAM0) + Image$$RW_IRAM2$$ZI$$Limit = .; + } > USB_RAM + + .AHBSRAM1 (NOLOAD): + { + Image$$RW_IRAM3$$Base = . ; + *(AHBSRAM1) + Image$$RW_IRAM3$$ZI$$Limit = .; + } > ETH_RAM +} diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_ARM/startup_LPC408x.s b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_ARM/startup_LPC408x.s new file mode 100644 index 00000000000..83a7583570f --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_ARM/startup_LPC408x.s @@ -0,0 +1,231 @@ +/* File: startup_ARMCM3.s + * Purpose: startup file for Cortex-M3/M4 devices. Should use with + * GNU Tools for ARM Embedded Processors + * Version: V1.1 + * Date: 17 June 2011 + * + * Copyright (C) 2011 ARM Limited. All rights reserved. + * ARM Limited (ARM) is supplying this software for use with Cortex-M3/M4 + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + */ + .syntax unified + .arch armv7-m + +/* Memory Model + The HEAP starts at the end of the DATA section and grows upward. + + The STACK starts at the end of the RAM and grows downward. + + The HEAP and stack STACK are only checked at compile time: + (DATA_SIZE + HEAP_SIZE + STACK_SIZE) < RAM_SIZE + + This is just a check for the bare minimum for the Heap+Stack area before + aborting compilation, it is not the run time limit: + Heap_Size + Stack_Size = 0x80 + 0x80 = 0x100 + */ + .section .stack + .align 3 +#ifdef __STACK_SIZE + .equ Stack_Size, __STACK_SIZE +#else + .equ Stack_Size, 0xc00 +#endif + .globl __StackTop + .globl __StackLimit +__StackLimit: + .space Stack_Size + .size __StackLimit, . - __StackLimit +__StackTop: + .size __StackTop, . - __StackTop + + .section .heap + .align 3 +#ifdef __HEAP_SIZE + .equ Heap_Size, __HEAP_SIZE +#else + .equ Heap_Size, 0x800 +#endif + .globl __HeapBase + .globl __HeapLimit +__HeapBase: + .space Heap_Size + .size __HeapBase, . - __HeapBase +__HeapLimit: + .size __HeapLimit, . - __HeapLimit + + .section .isr_vector + .align 2 + .globl __isr_vector +__isr_vector: + .long __StackTop /* Top of Stack */ + .long Reset_Handler /* Reset Handler */ + .long NMI_Handler /* NMI Handler */ + .long HardFault_Handler /* Hard Fault Handler */ + .long MemManage_Handler /* MPU Fault Handler */ + .long BusFault_Handler /* Bus Fault Handler */ + .long UsageFault_Handler /* Usage Fault Handler */ + .long 0 /* Reserved */ + .long 0 /* Reserved */ + .long 0 /* Reserved */ + .long 0 /* Reserved */ + .long SVC_Handler /* SVCall Handler */ + .long DebugMon_Handler /* Debug Monitor Handler */ + .long 0 /* Reserved */ + .long PendSV_Handler /* PendSV Handler */ + .long SysTick_Handler /* SysTick Handler */ + + /* External interrupts */ + .long WDT_IRQHandler /* 16: Watchdog Timer */ + .long TIMER0_IRQHandler /* 17: Timer0 */ + .long TIMER1_IRQHandler /* 18: Timer1 */ + .long TIMER2_IRQHandler /* 19: Timer2 */ + .long TIMER3_IRQHandler /* 20: Timer3 */ + .long UART0_IRQHandler /* 21: UART0 */ + .long UART1_IRQHandler /* 22: UART1 */ + .long UART2_IRQHandler /* 23: UART2 */ + .long UART3_IRQHandler /* 24: UART3 */ + .long PWM1_IRQHandler /* 25: PWM1 */ + .long I2C0_IRQHandler /* 26: I2C0 */ + .long I2C1_IRQHandler /* 27: I2C1 */ + .long I2C2_IRQHandler /* 28: I2C2 */ + .long 0 /* 29: Reserved */ + .long SSP0_IRQHandler /* 30: SSP0 */ + .long SSP1_IRQHandler /* 31: SSP1 */ + .long PLL0_IRQHandler /* 32: PLL0 Lock (Main PLL) */ + .long RTC_IRQHandler /* 33: Real Time Clock */ + .long EINT0_IRQHandler /* 34: External Interrupt 0 */ + .long EINT1_IRQHandler /* 35: External Interrupt 1 */ + .long EINT2_IRQHandler /* 36: External Interrupt 2 */ + .long EINT3_IRQHandler /* 37: External Interrupt 3 */ + .long ADC_IRQHandler /* 38: A/D Converter */ + .long BOD_IRQHandler /* 39: Brown-Out Detect */ + .long USB_IRQHandler /* 40: USB */ + .long CAN_IRQHandler /* 41: CAN */ + .long DMA_IRQHandler /* 42: General Purpose DMA */ + .long I2S_IRQHandler /* 43: I2S */ + .long ENET_IRQHandler /* 44: Ethernet */ + .long MCI_IRQHandler /* 45: SD/MMC carf I/F */ + .long MCPWM_IRQHandler /* 46: Motor Control PWM */ + .long QEI_IRQHandler /* 47: Quadrature Encoder Interface */ + .long PLL1_IRQHandler /* 48: PLL1 Lock (USB PLL) */ + .long USBActivity_IRQHandler /* 49: USB Activity */ + .long CANActivity_IRQHandler /* 50: CAN Activity */ + .long UART4_IRQHandler /* 51: UART4 */ + .long SSP2_IRQHandler /* 52: SSP2 */ + .long LCD_IRQHandler /* 53: LCD */ + .long GPIO_IRQHandler /* 54: GPIO */ + .long PWM0_IRQHandler /* 55: PWM0 */ + .long EEPROM_IRQHandler /* 56: EEPROM */ + + .size __isr_vector, . - __isr_vector + + .text + .thumb + .thumb_func + .align 2 + .globl Reset_Handler + .type Reset_Handler, %function +Reset_Handler: +/* Loop to copy data from read only memory to RAM. The ranges + * of copy from/to are specified by following symbols evaluated in + * linker script. + * _etext: End of code section, i.e., begin of data sections to copy from. + * __data_start__/__data_end__: RAM address range that data should be + * copied to. Both must be aligned to 4 bytes boundary. */ + + ldr r1, =__etext + ldr r2, =__data_start__ + ldr r3, =__data_end__ + +.flash_to_ram_loop: + cmp r2, r3 + ittt lt + ldrlt r0, [r1], #4 + strlt r0, [r2], #4 + blt .flash_to_ram_loop + + ldr r0, =SystemInit + blx r0 + ldr r0, =_start + bx r0 + .pool + .size Reset_Handler, . - Reset_Handler + +/* Macro to define default handlers. Default handler + * will be weak symbol and just dead loops. They can be + * overwritten by other handlers */ + .macro def_default_handler handler_name + .align 1 + .thumb_func + .weak \handler_name + .type \handler_name, %function +\handler_name : + b . + .size \handler_name, . - \handler_name + .endm + + def_default_handler NMI_Handler + def_default_handler HardFault_Handler + def_default_handler MemManage_Handler + def_default_handler BusFault_Handler + def_default_handler UsageFault_Handler + def_default_handler SVC_Handler + def_default_handler DebugMon_Handler + def_default_handler PendSV_Handler + def_default_handler SysTick_Handler + def_default_handler Default_Handler + + def_default_handler WDT_IRQHandler + def_default_handler TIMER0_IRQHandler + def_default_handler TIMER1_IRQHandler + def_default_handler TIMER2_IRQHandler + def_default_handler TIMER3_IRQHandler + def_default_handler UART0_IRQHandler + def_default_handler UART1_IRQHandler + def_default_handler UART2_IRQHandler + def_default_handler UART3_IRQHandler + def_default_handler PWM1_IRQHandler + def_default_handler I2C0_IRQHandler + def_default_handler I2C1_IRQHandler + def_default_handler I2C2_IRQHandler +/* def_default_handler SPI_IRQHandler */ + def_default_handler SSP0_IRQHandler + def_default_handler SSP1_IRQHandler + def_default_handler PLL0_IRQHandler + def_default_handler RTC_IRQHandler + def_default_handler EINT0_IRQHandler + def_default_handler EINT1_IRQHandler + def_default_handler EINT2_IRQHandler + def_default_handler EINT3_IRQHandler + def_default_handler ADC_IRQHandler + def_default_handler BOD_IRQHandler + def_default_handler USB_IRQHandler + def_default_handler CAN_IRQHandler + def_default_handler DMA_IRQHandler + def_default_handler I2S_IRQHandler + def_default_handler ENET_IRQHandler + def_default_handler MCI_IRQHandler + def_default_handler MCPWM_IRQHandler + def_default_handler QEI_IRQHandler + def_default_handler PLL1_IRQHandler + def_default_handler USBActivity_IRQHandler + def_default_handler CANActivity_IRQHandler + def_default_handler UART4_IRQHandler + def_default_handler SSP2_IRQHandler + def_default_handler LCD_IRQHandler + def_default_handler GPIO_IRQHandler + def_default_handler PWM0_IRQHandler + def_default_handler EEPROM_IRQHandler + + .weak DEF_IRQHandler + .set DEF_IRQHandler, Default_Handler + + .end + diff --git a/workspace_tools/export/gcc_arm_lpc4088.tmpl b/workspace_tools/export/gcc_arm_lpc4088.tmpl new file mode 100644 index 00000000000..4f40755f517 --- /dev/null +++ b/workspace_tools/export/gcc_arm_lpc4088.tmpl @@ -0,0 +1,46 @@ +# This file was automagically generated by mbed.org. For more information, +# see http://mbed.org/handbook/Exporting-to-GCC-ARM-Embedded + +GCC_BIN = +PROJECT = {{name}} +OBJECTS = {% for f in to_be_compiled %}{{f}} {% endfor %} +SYS_OBJECTS = {% for f in object_files %}{{f}} {% endfor %} +INCLUDE_PATHS = {% for p in include_paths %}-I{{p}} {% endfor %} +LIBRARY_PATHS = {% for p in library_paths %}-L{{p}} {% endfor %} +LIBRARIES = {% for lib in libraries %}-l{{lib}} {% endfor %} +LINKER_SCRIPT = {{linker_script}} + +############################################################################### +AS = $(GCC_BIN)arm-none-eabi-as +CC = $(GCC_BIN)arm-none-eabi-gcc +CPP = $(GCC_BIN)arm-none-eabi-g++ +LD = $(GCC_BIN)arm-none-eabi-gcc +OBJCOPY = $(GCC_BIN)arm-none-eabi-objcopy + +CPU = -mcpu=cortex-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=softfp +CC_FLAGS = $(CPU) -c -Os -fno-common -fmessage-length=0 -Wall -fno-exceptions -ffunction-sections -fdata-sections +CC_SYMBOLS = {% for s in symbols %}-D{{s}} {% endfor %} + +LD_FLAGS = -mcpu=cortex-m4 -mthumb -Wl,--gc-sections --specs=nano.specs -u _printf_float -u _scanf_float +LD_SYS_LIBS = -lstdc++ -lsupc++ -lm -lc -lgcc -lnosys + +all: $(PROJECT).bin + +clean: + rm -f $(PROJECT).bin $(PROJECT).elf $(OBJECTS) + +.s.o: + $(AS) $(CPU) -o $@ $< + +.c.o: + $(CC) $(CC_FLAGS) $(CC_SYMBOLS) -std=gnu99 $(INCLUDE_PATHS) -o $@ $< + +.cpp.o: + $(CPP) $(CC_FLAGS) $(CC_SYMBOLS) -std=gnu++98 $(INCLUDE_PATHS) -o $@ $< + + +$(PROJECT).elf: $(OBJECTS) $(SYS_OBJECTS) + $(LD) $(LD_FLAGS) -T$(LINKER_SCRIPT) $(LIBRARY_PATHS) -o $@ $^ $(LIBRARIES) $(LD_SYS_LIBS) $(LIBRARIES) $(LD_SYS_LIBS) + +$(PROJECT).bin: $(PROJECT).elf + $(OBJCOPY) -O binary $< $@