diff --git a/hw/bsp/ngx4330/board.mk b/hw/bsp/ngx4330/board.mk new file mode 100644 index 00000000..a54675a7 --- /dev/null +++ b/hw/bsp/ngx4330/board.mk @@ -0,0 +1,47 @@ +CFLAGS += \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m4 \ + -nostdlib \ + -DCORE_M4 \ + -DCFG_TUSB_MCU=OPT_MCU_LPC43XX \ + -D__USE_LPCOPEN + +# lpc_types.h cause following errors +CFLAGS += -Wno-error=strict-prototypes + +MCU_DIR = hw/mcu/nxp/lpc_driver/lpc43xx/lpc_chip_43xx + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/ngx4330.ld + +# TODO remove later +SRC_C += src/portable/$(VENDOR)/$(CHIP_FAMILY)/hal_$(CHIP_FAMILY).c + +SRC_C += \ + $(MCU_DIR)/../gcc/cr_startup_lpc43xx.c \ + $(MCU_DIR)/src/chip_18xx_43xx.c \ + $(MCU_DIR)/src/clock_18xx_43xx.c \ + $(MCU_DIR)/src/gpio_18xx_43xx.c \ + $(MCU_DIR)/src/sysinit_18xx_43xx.c \ + $(MCU_DIR)/src/i2c_18xx_43xx.c \ + $(MCU_DIR)/src/i2cm_18xx_43xx.c \ + $(MCU_DIR)/src/uart_18xx_43xx.c + +INC += \ + $(TOP)/$(MCU_DIR)/inc \ + $(TOP)/$(MCU_DIR)/inc/config_43xx + +# For TinyUSB port source +VENDOR = nxp +CHIP_FAMILY = lpc18_43 + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM4 + +# For flash-jlink target +JLINK_DEVICE = LPC4330 +JLINK_IF = swd + +# flash using jlink +flash: flash-jlink diff --git a/hw/bsp/ngx4330/ngx4330.c b/hw/bsp/ngx4330/ngx4330.c new file mode 100644 index 00000000..12640ee7 --- /dev/null +++ b/hw/bsp/ngx4330/ngx4330.c @@ -0,0 +1,271 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 Ha Thach (tinyusb.org) + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * This file is part of the TinyUSB stack. + */ + +#include "chip.h" +#include "../board.h" + +#define LED_PORT 1 +#define LED_PIN 12 +#define LED_STATE_ON 0 + +#define BUTTON_PORT 0 +#define BUTTON_PIN 7 +#define BUTTON_STATE_ACTIVE 0 + +#define BOARD_UART_PORT LPC_USART0 +#define BOARD_UART_PIN_PORT 0x0f +#define BOARD_UART_PIN_TX 10 // PF.10 : UART0_TXD +#define BOARD_UART_PIN_RX 11 // PF.11 : UART0_RXD + +/*------------------------------------------------------------------*/ +/* BOARD API + *------------------------------------------------------------------*/ + +/* System configuration variables used by chip driver */ +const uint32_t OscRateIn = 12000000; +const uint32_t ExtRateIn = 0; + +static const PINMUX_GRP_T pinmuxing[] = +{ + // LED P2.12 as GPIO 1.12 + {2, 11, (SCU_MODE_INBUFF_EN | SCU_MODE_PULLDOWN | SCU_MODE_FUNC0)}, + + // Button P2.7 as GPIO 0.7 + {2, 7, (SCU_MODE_PULLUP | SCU_MODE_INBUFF_EN | SCU_MODE_ZIF_DIS | SCU_MODE_FUNC0)}, + + // USB + + // SPIFI + {3, 3, (SCU_PINIO_FAST | SCU_MODE_FUNC3)}, /* SPIFI CLK */ + {3, 4, (SCU_PINIO_FAST | SCU_MODE_FUNC3)}, /* SPIFI D3 */ + {3, 5, (SCU_PINIO_FAST | SCU_MODE_FUNC3)}, /* SPIFI D2 */ + {3, 6, (SCU_PINIO_FAST | SCU_MODE_FUNC3)}, /* SPIFI D1 */ + {3, 7, (SCU_PINIO_FAST | SCU_MODE_FUNC3)}, /* SPIFI D0 */ + {3, 8, (SCU_PINIO_FAST | SCU_MODE_FUNC3)} /* SPIFI CS/SSEL */ +}; + +// Invoked by startup code +extern void (* const g_pfnVectors[])(void); +void SystemInit(void) +{ + // Remap isr vector + *((uint32_t *) 0xE000ED08) = (uint32_t) &g_pfnVectors; + + // Set up pinmux + Chip_SCU_SetPinMuxing(pinmuxing, sizeof(pinmuxing) / sizeof(PINMUX_GRP_T)); + + //------------- Set up clock -------------// + Chip_Clock_SetBaseClock(CLK_BASE_SPIFI, CLKIN_IRC, true, false); // change SPIFI to IRC during clock programming + LPC_SPIFI->CTRL |= SPIFI_CTRL_FBCLK(1); // and set FBCLK in SPIFI controller + + Chip_SetupCoreClock(CLKIN_CRYSTAL, MAX_CLOCK_FREQ, true); + + /* Reset and enable 32Khz oscillator */ + LPC_CREG->CREG0 &= ~((1 << 3) | (1 << 2)); + LPC_CREG->CREG0 |= (1 << 1) | (1 << 0); + + /* Setup a divider E for main PLL clock switch SPIFI clock to that divider. + Divide rate is based on CPU speed and speed of SPI FLASH part. */ +#if (MAX_CLOCK_FREQ > 180000000) + Chip_Clock_SetDivider(CLK_IDIV_E, CLKIN_MAINPLL, 5); +#else + Chip_Clock_SetDivider(CLK_IDIV_E, CLKIN_MAINPLL, 4); +#endif + Chip_Clock_SetBaseClock(CLK_BASE_SPIFI, CLKIN_IDIVE, true, false); + + /* Setup system base clocks and initial states. This won't enable and + disable individual clocks, but sets up the base clock sources for + each individual peripheral clock. */ + Chip_Clock_SetBaseClock(CLK_BASE_USB1, CLKIN_IDIVD, true, true); +} + +void board_init(void) +{ + SystemCoreClockUpdate(); + +#if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); +#elif CFG_TUSB_OS == OPT_OS_FREERTOS + // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) + //NVIC_SetPriority(USB0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY ); +#endif + + Chip_GPIO_Init(LPC_GPIO_PORT); + + // LED + Chip_GPIO_SetPinDIROutput(LPC_GPIO_PORT, LED_PORT, LED_PIN); + + // Button + Chip_GPIO_SetPinDIRInput(LPC_GPIO_PORT, BUTTON_PORT, BUTTON_PIN); + +#if 0 +#if 0 + //------------- UART -------------// + scu_pinmux(BOARD_UART_PIN_PORT, BOARD_UART_PIN_TX, MD_PDN, FUNC1); + scu_pinmux(BOARD_UART_PIN_PORT, BOARD_UART_PIN_RX, MD_PLN | MD_EZI | MD_ZI, FUNC1); + + UART_CFG_Type UARTConfigStruct; + UART_ConfigStructInit(&UARTConfigStruct); + UARTConfigStruct.Baud_rate = CFG_UART_BAUDRATE; + UARTConfigStruct.Clock_Speed = 0; + + UART_Init(BOARD_UART_PORT, &UARTConfigStruct); + UART_TxCmd(BOARD_UART_PORT, ENABLE); // Enable UART Transmit +#endif + + //------------- USB -------------// + enum { + USBMODE_DEVICE = 2, + USBMODE_HOST = 3 + }; + + enum { + USBMODE_VBUS_LOW = 0, + USBMODE_VBUS_HIGH = 1 + }; + + /* USB0 + * For USB Device operation; insert jumpers in position 1-2 in JP17/JP18/JP19. GPIO28 controls USB + * connect functionality and LED32 lights when the USB Device is connected. SJ4 has pads 1-2 shorted + * by default. LED33 is controlled by GPIO27 and signals USB-up state. GPIO54 is used for VBUS + * sensing. + * For USB Host operation; insert jumpers in position 2-3 in JP17/JP18/JP19. USB Host power is + * controlled via distribution switch U20 (found in schematic page 11). Signal GPIO26 is active low and + * enables +5V on VBUS2. LED35 light whenever +5V is present on VBUS2. GPIO55 is connected to + * status feedback from the distribution switch. GPIO54 is used for VBUS sensing. 15Kohm pull-down + * resistors are always active + */ +#if CFG_TUSB_RHPORT0_MODE + Chip_USB0_Init(); + + // Reset controller + LPC_USB0->USBCMD_D |= 0x02; + while( LPC_USB0->USBCMD_D & 0x02 ) {} + + // Set mode + #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST + LPC_USB0->USBMODE_H = USBMODE_HOST | (USBMODE_VBUS_HIGH << 5); + + LPC_USB0->PORTSC1_D |= (1<<24); // FIXME force full speed for debugging + #else // TODO OTG + LPC_USB0->USBMODE_D = USBMODE_DEVICE; + LPC_USB0->OTGSC = (1<<3) | (1<<0) /*| (1<<16)| (1<<24)| (1<<25)| (1<<26)| (1<<27)| (1<<28)| (1<<29)| (1<<30)*/; + #endif +#endif + + /* USB1 + * When USB channel #1 is used as USB Host, 15Kohm pull-down resistors are needed on the USB data + * signals. These are activated inside the USB OTG chip (U31), and this has to be done via the I2C + * interface of GPIO52/GPIO53. + * J20 is the connector to use when USB Host is used. In order to provide +5V to the external USB + * device connected to this connector (J20), channel A of U20 must be enabled. It is enabled by default + * since SJ5 is normally connected between pin 1-2. LED34 lights green when +5V is available on J20. + * JP15 shall not be inserted. JP16 has no effect + * + * When USB channel #1 is used as USB Device, a 1.5Kohm pull-up resistor is needed on the USB DP + * data signal. There are two methods to create this. JP15 is inserted and the pull-up resistor is always + * enabled. Alternatively, the pull-up resistor is activated inside the USB OTG chip (U31), and this has to + * be done via the I2C interface of GPIO52/GPIO53. In the latter case, JP15 shall not be inserted. + * J19 is the connector to use when USB Device is used. Normally it should be a USB-B connector for + * creating a USB Device interface, but the mini-AB connector can also be used in this case. The status + * of VBUS can be read via U31. + * JP16 shall not be inserted. + */ +#if CFG_TUSB_RHPORT1_MODE + Chip_USB1_Init(); + + // Reset controller + LPC_USB1->USBCMD_D |= 0x02; + while( LPC_USB1->USBCMD_D & 0x02 ) {} + + // Set mode + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST + LPC_USB1->USBMODE_H = USBMODE_HOST | (USBMODE_VBUS_HIGH << 5); + #else // TODO OTG + LPC_USB1->USBMODE_D = USBMODE_DEVICE; + #endif + + // USB1 as fullspeed + LPC_USB1->PORTSC1_D |= (1<<24); +#endif + + // USB0 Vbus Power: P2_3 on EA4357 channel B U20 GPIO26 active low (base board) + Chip_SCU_PinMuxSet(2, 3, SCU_MODE_PULLUP | SCU_MODE_INBUFF_EN | SCU_MODE_FUNC7); + + #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE + // P9_5 (GPIO5[18]) (GPIO28 on oem base) as USB connect, active low. + Chip_SCU_PinMuxSet(9, 5, SCU_MODE_PULLDOWN | SCU_MODE_FUNC4); + Chip_GPIO_SetPinDIROutput(LPC_GPIO_PORT, 5, 18); + #endif + + // USB1 Power: EA4357 channel A U20 is enabled by SJ5 connected to pad 1-2, no more action required + // TODO Remove R170, R171, solder a pair of 15K to USB1 D+/D- to test with USB1 Host +#endif +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + Chip_GPIO_SetPinState(LPC_GPIO_PORT, LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); +} + +uint32_t board_button_read(void) +{ + return BUTTON_STATE_ACTIVE == Chip_GPIO_GetPinState(LPC_GPIO_PORT, BUTTON_PORT, BUTTON_PIN); +} + +int board_uart_read(uint8_t* buf, int len) +{ + //return UART_ReceiveByte(BOARD_UART_PORT); + (void) buf; + (void) len; + return 0; +} + +int board_uart_write(void const * buf, int len) +{ + //UART_Send(BOARD_UART_PORT, &c, 1, BLOCKING); + (void) buf; + (void) len; + return 0; +} + +#if CFG_TUSB_OS == OPT_OS_NONE +volatile uint32_t system_ticks = 0; +void SysTick_Handler (void) +{ + system_ticks++; +} + +uint32_t board_millis(void) +{ + return system_ticks; +} +#endif diff --git a/hw/bsp/ngx4330/ngx4330.ld b/hw/bsp/ngx4330/ngx4330.ld new file mode 100644 index 00000000..7bd363f0 --- /dev/null +++ b/hw/bsp/ngx4330/ngx4330.ld @@ -0,0 +1,343 @@ +/* + * GENERATED FILE - DO NOT EDIT + * Copyright (c) 2008-2013 Code Red Technologies Ltd, + * Copyright 2015, 2018-2019 NXP + * (c) NXP Semiconductors 2013-2019 + * Generated linker script file for LPC4330 + * Created from linkscript.ldt by FMCreateLinkLibraries + * Using Freemarker v2.3.23 + * MCUXpresso IDE v11.0.0 [Build 2516] [2019-06-05] on Sep 9, 2019 12:09:49 PM + */ + +MEMORY +{ + /* Define each memory region */ + RamLoc128 (rwx) : ORIGIN = 0x10000000, LENGTH = 0x20000 /* 128K bytes (alias RAM) */ + RamLoc72 (rwx) : ORIGIN = 0x10080000, LENGTH = 0x12000 /* 72K bytes (alias RAM2) */ + RamAHB32 (rwx) : ORIGIN = 0x20000000, LENGTH = 0x8000 /* 32K bytes (alias RAM3) */ + RamAHB16 (rwx) : ORIGIN = 0x20008000, LENGTH = 0x4000 /* 16K bytes (alias RAM4) */ + RamAHB_ETB16 (rwx) : ORIGIN = 0x2000c000, LENGTH = 0x4000 /* 16K bytes (alias RAM5) */ + SPIFI (rx) : ORIGIN = 0x14000000, LENGTH = 0x400000 /* 4M bytes (alias Flash) */ +} + + /* Define a symbol for the top of each memory region */ + __base_RamLoc128 = 0x10000000 ; /* RamLoc128 */ + __base_RAM = 0x10000000 ; /* RAM */ + __top_RamLoc128 = 0x10000000 + 0x20000 ; /* 128K bytes */ + __top_RAM = 0x10000000 + 0x20000 ; /* 128K bytes */ + __base_RamLoc72 = 0x10080000 ; /* RamLoc72 */ + __base_RAM2 = 0x10080000 ; /* RAM2 */ + __top_RamLoc72 = 0x10080000 + 0x12000 ; /* 72K bytes */ + __top_RAM2 = 0x10080000 + 0x12000 ; /* 72K bytes */ + __base_RamAHB32 = 0x20000000 ; /* RamAHB32 */ + __base_RAM3 = 0x20000000 ; /* RAM3 */ + __top_RamAHB32 = 0x20000000 + 0x8000 ; /* 32K bytes */ + __top_RAM3 = 0x20000000 + 0x8000 ; /* 32K bytes */ + __base_RamAHB16 = 0x20008000 ; /* RamAHB16 */ + __base_RAM4 = 0x20008000 ; /* RAM4 */ + __top_RamAHB16 = 0x20008000 + 0x4000 ; /* 16K bytes */ + __top_RAM4 = 0x20008000 + 0x4000 ; /* 16K bytes */ + __base_RamAHB_ETB16 = 0x2000c000 ; /* RamAHB_ETB16 */ + __base_RAM5 = 0x2000c000 ; /* RAM5 */ + __top_RamAHB_ETB16 = 0x2000c000 + 0x4000 ; /* 16K bytes */ + __top_RAM5 = 0x2000c000 + 0x4000 ; /* 16K bytes */ + __base_SPIFI = 0x14000000 ; /* SPIFI */ + __base_Flash = 0x14000000 ; /* Flash */ + __top_SPIFI = 0x14000000 + 0x400000 ; /* 4M bytes */ + __top_Flash = 0x14000000 + 0x400000 ; /* 4M bytes */ + +ENTRY(ResetISR) + +SECTIONS +{ + /* MAIN TEXT SECTION */ + .text : ALIGN(4) + { + FILL(0xff) + __vectors_start__ = ABSOLUTE(.) ; + KEEP(*(.isr_vector)) + /* Global Section Table */ + . = ALIGN(4) ; + __section_table_start = .; + __data_section_table = .; + LONG(LOADADDR(.data)); + LONG( ADDR(.data)); + LONG( SIZEOF(.data)); + LONG(LOADADDR(.data_RAM2)); + LONG( ADDR(.data_RAM2)); + LONG( SIZEOF(.data_RAM2)); + LONG(LOADADDR(.data_RAM3)); + LONG( ADDR(.data_RAM3)); + LONG( SIZEOF(.data_RAM3)); + LONG(LOADADDR(.data_RAM4)); + LONG( ADDR(.data_RAM4)); + LONG( SIZEOF(.data_RAM4)); + LONG(LOADADDR(.data_RAM5)); + LONG( ADDR(.data_RAM5)); + LONG( SIZEOF(.data_RAM5)); + __data_section_table_end = .; + __bss_section_table = .; + LONG( ADDR(.bss)); + LONG( SIZEOF(.bss)); + LONG( ADDR(.bss_RAM2)); + LONG( SIZEOF(.bss_RAM2)); + LONG( ADDR(.bss_RAM3)); + LONG( SIZEOF(.bss_RAM3)); + LONG( ADDR(.bss_RAM4)); + LONG( SIZEOF(.bss_RAM4)); + LONG( ADDR(.bss_RAM5)); + LONG( SIZEOF(.bss_RAM5)); + __bss_section_table_end = .; + __section_table_end = . ; + /* End of Global Section Table */ + + *(.after_vectors*) + + } > SPIFI + + .text : ALIGN(4) + { + *(.text*) + *(.rodata .rodata.* .constdata .constdata.*) + . = ALIGN(4); + } > SPIFI + /* + * for exception handling/unwind - some Newlib functions (in common + * with C++ and STDC++) use this. + */ + .ARM.extab : ALIGN(4) + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > SPIFI + + __exidx_start = .; + + .ARM.exidx : ALIGN(4) + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > SPIFI + __exidx_end = .; + + _etext = .; + + /* DATA section for RamLoc72 */ + + .data_RAM2 : ALIGN(4) + { + FILL(0xff) + PROVIDE(__start_data_RAM2 = .) ; + *(.ramfunc.$RAM2) + *(.ramfunc.$RamLoc72) + *(.data.$RAM2) + *(.data.$RamLoc72) + *(.data.$RAM2.*) + *(.data.$RamLoc72.*) + . = ALIGN(4) ; + PROVIDE(__end_data_RAM2 = .) ; + } > RamLoc72 AT>SPIFI + /* DATA section for RamAHB32 */ + + .data_RAM3 : ALIGN(4) + { + FILL(0xff) + PROVIDE(__start_data_RAM3 = .) ; + *(.ramfunc.$RAM3) + *(.ramfunc.$RamAHB32) + *(.data.$RAM3) + *(.data.$RamAHB32) + *(.data.$RAM3.*) + *(.data.$RamAHB32.*) + . = ALIGN(4) ; + PROVIDE(__end_data_RAM3 = .) ; + } > RamAHB32 AT>SPIFI + /* DATA section for RamAHB16 */ + + .data_RAM4 : ALIGN(4) + { + FILL(0xff) + PROVIDE(__start_data_RAM4 = .) ; + *(.ramfunc.$RAM4) + *(.ramfunc.$RamAHB16) + *(.data.$RAM4) + *(.data.$RamAHB16) + *(.data.$RAM4.*) + *(.data.$RamAHB16.*) + . = ALIGN(4) ; + PROVIDE(__end_data_RAM4 = .) ; + } > RamAHB16 AT>SPIFI + /* DATA section for RamAHB_ETB16 */ + + .data_RAM5 : ALIGN(4) + { + FILL(0xff) + PROVIDE(__start_data_RAM5 = .) ; + *(.ramfunc.$RAM5) + *(.ramfunc.$RamAHB_ETB16) + *(.data.$RAM5) + *(.data.$RamAHB_ETB16) + *(.data.$RAM5.*) + *(.data.$RamAHB_ETB16.*) + . = ALIGN(4) ; + PROVIDE(__end_data_RAM5 = .) ; + } > RamAHB_ETB16 AT>SPIFI + /* MAIN DATA SECTION */ + .uninit_RESERVED (NOLOAD) : + { + . = ALIGN(4) ; + KEEP(*(.bss.$RESERVED*)) + . = ALIGN(4) ; + _end_uninit_RESERVED = .; + } > RamLoc128 + + /* Main DATA section (RamLoc128) */ + .data : ALIGN(4) + { + FILL(0xff) + _data = . ; + *(vtable) + *(.ramfunc*) + *(.data*) + . = ALIGN(4) ; + _edata = . ; + } > RamLoc128 AT>SPIFI + + /* BSS section for RamLoc72 */ + .bss_RAM2 : + { + . = ALIGN(4) ; + PROVIDE(__start_bss_RAM2 = .) ; + *(.bss.$RAM2) + *(.bss.$RamLoc72) + *(.bss.$RAM2.*) + *(.bss.$RamLoc72.*) + . = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */ + PROVIDE(__end_bss_RAM2 = .) ; + } > RamLoc72 + + /* BSS section for RamAHB32 */ + .bss_RAM3 : + { + . = ALIGN(4) ; + PROVIDE(__start_bss_RAM3 = .) ; + *(.bss.$RAM3) + *(.bss.$RamAHB32) + *(.bss.$RAM3.*) + *(.bss.$RamAHB32.*) + . = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */ + PROVIDE(__end_bss_RAM3 = .) ; + } > RamAHB32 + + /* BSS section for RamAHB16 */ + .bss_RAM4 : + { + . = ALIGN(4) ; + PROVIDE(__start_bss_RAM4 = .) ; + *(.bss.$RAM4) + *(.bss.$RamAHB16) + *(.bss.$RAM4.*) + *(.bss.$RamAHB16.*) + . = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */ + PROVIDE(__end_bss_RAM4 = .) ; + } > RamAHB16 + + /* BSS section for RamAHB_ETB16 */ + .bss_RAM5 : + { + . = ALIGN(4) ; + PROVIDE(__start_bss_RAM5 = .) ; + *(.bss.$RAM5) + *(.bss.$RamAHB_ETB16) + *(.bss.$RAM5.*) + *(.bss.$RamAHB_ETB16.*) + . = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */ + PROVIDE(__end_bss_RAM5 = .) ; + } > RamAHB_ETB16 + + /* MAIN BSS SECTION */ + .bss : + { + . = ALIGN(4) ; + _bss = .; + *(.bss*) + *(COMMON) + . = ALIGN(4) ; + _ebss = .; + PROVIDE(end = .); + } > RamLoc128 + + /* NOINIT section for RamLoc72 */ + .noinit_RAM2 (NOLOAD) : + { + . = ALIGN(4) ; + *(.noinit.$RAM2) + *(.noinit.$RamLoc72) + *(.noinit.$RAM2.*) + *(.noinit.$RamLoc72.*) + . = ALIGN(4) ; + } > RamLoc72 + + /* NOINIT section for RamAHB32 */ + .noinit_RAM3 (NOLOAD) : + { + . = ALIGN(4) ; + *(.noinit.$RAM3) + *(.noinit.$RamAHB32) + *(.noinit.$RAM3.*) + *(.noinit.$RamAHB32.*) + . = ALIGN(4) ; + } > RamAHB32 + + /* NOINIT section for RamAHB16 */ + .noinit_RAM4 (NOLOAD) : + { + . = ALIGN(4) ; + *(.noinit.$RAM4) + *(.noinit.$RamAHB16) + *(.noinit.$RAM4.*) + *(.noinit.$RamAHB16.*) + . = ALIGN(4) ; + } > RamAHB16 + + /* NOINIT section for RamAHB_ETB16 */ + .noinit_RAM5 (NOLOAD) : + { + . = ALIGN(4) ; + *(.noinit.$RAM5) + *(.noinit.$RamAHB_ETB16) + *(.noinit.$RAM5.*) + *(.noinit.$RamAHB_ETB16.*) + . = ALIGN(4) ; + } > RamAHB_ETB16 + + /* DEFAULT NOINIT SECTION */ + .noinit (NOLOAD): + { + . = ALIGN(4) ; + _noinit = .; + *(.noinit*) + . = ALIGN(4) ; + _end_noinit = .; + } > RamLoc128 + PROVIDE(_pvHeapStart = DEFINED(__user_heap_base) ? __user_heap_base : .); + PROVIDE(_vStackTop = DEFINED(__user_stack_top) ? __user_stack_top : __top_RamLoc128 - 0); + + /* ## Create checksum value (used in startup) ## */ + PROVIDE(__valid_user_code_checksum = 0 - + (_vStackTop + + (ResetISR + 1) + + (NMI_Handler + 1) + + (HardFault_Handler + 1) + + (( DEFINED(MemManage_Handler) ? MemManage_Handler : 0 ) + 1) /* MemManage_Handler may not be defined */ + + (( DEFINED(BusFault_Handler) ? BusFault_Handler : 0 ) + 1) /* BusFault_Handler may not be defined */ + + (( DEFINED(UsageFault_Handler) ? UsageFault_Handler : 0 ) + 1) /* UsageFault_Handler may not be defined */ + ) ); + + /* Provide basic symbols giving location and size of main text + * block, including initial values of RW data sections. Note that + * these will need extending to give a complete picture with + * complex images (e.g multiple Flash banks). + */ + _image_start = LOADADDR(.text); + _image_end = LOADADDR(.data) + SIZEOF(.data); + _image_size = _image_end - _image_start; +} \ No newline at end of file