From d74a92bf4596d229a3176fab2f91c45eabff6d3a Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 25 Mar 2020 14:06:51 +0700 Subject: [PATCH 1/4] makefile clean up allow board to define CROSS_COMPILE (default to arm gcc) --- examples/make.mk | 69 +++++++++++++------------------ hw/bsp/fomu/board.mk | 3 ++ hw/bsp/msp_exp430f5529lp/board.mk | 3 ++ tools/build_all.py | 2 +- 4 files changed, 36 insertions(+), 41 deletions(-) diff --git a/examples/make.mk b/examples/make.mk index 25b618896..5fc596f63 100644 --- a/examples/make.mk +++ b/examples/make.mk @@ -1,15 +1,34 @@ -# +# --------------------------------------- # Common make definition for all examples -# +# --------------------------------------- -# Compiler -ifeq ($(BOARD), msp_exp430f5529lp) - CROSS_COMPILE = msp430-elf- -else ifeq ($(BOARD), fomu) - CROSS_COMPILE = riscv-none-embed- -else - CROSS_COMPILE = arm-none-eabi- +#-------------- Select the board to build for. ------------ +BOARD_LIST = $(sort $(subst /.,,$(subst $(TOP)/hw/bsp/,,$(wildcard $(TOP)/hw/bsp/*/.)))) + +ifeq ($(filter $(BOARD),$(BOARD_LIST)),) + $(info You must provide a BOARD parameter with 'BOARD=', supported boards are:) + $(foreach b,$(BOARD_LIST),$(info - $(b))) + $(error Invalid BOARD specified) endif + +# Handy check parameter function +check_defined = \ + $(strip $(foreach 1,$1, \ + $(call __check_defined,$1,$(strip $(value 2))))) +__check_defined = \ + $(if $(value $1),, \ + $(error Undefined make flag: $1$(if $2, ($2)))) + +# Build directory +BUILD = _build/build-$(BOARD) + +# Board specific define +include $(TOP)/hw/bsp/$(BOARD)/board.mk + +#-------------- Cross Compiler ------------ +# Can be set by board, default to ARM GCC +CROSS_COMPILE ?= arm-none-eabi- + CC = $(CROSS_COMPILE)gcc CXX = $(CROSS_COMPILE)g++ OBJCOPY = $(CROSS_COMPILE)objcopy @@ -18,38 +37,8 @@ MKDIR = mkdir SED = sed CP = cp RM = rm -PYTHON ?= python -check_defined = \ - $(strip $(foreach 1,$1, \ - $(call __check_defined,$1,$(strip $(value 2))))) -__check_defined = \ - $(if $(value $1),, \ - $(error Undefined make flag: $1$(if $2, ($2)))) - - -define newline - - -endef - -# Select the board to build for. -ifeq ($(BOARD),) - $(info You must provide a BOARD parameter with 'BOARD=') - $(info Supported boards are:) - $(info $(sort $(subst /.,,$(subst $(TOP)/hw/bsp/, $(newline)-,$(wildcard $(TOP)/hw/bsp/*/.))))) - $(error BOARD not defined) -else - ifeq ($(wildcard $(TOP)/hw/bsp/$(BOARD)/.),) - $(error Invalid BOARD specified) - endif -endif - -# Build directory -BUILD = _build/build-$(BOARD) - -# Board specific -include $(TOP)/hw/bsp/$(BOARD)/board.mk +#-------------- Source files and compiler flags -------------- # Include all source C in board folder SRC_C += hw/bsp/board.c diff --git a/hw/bsp/fomu/board.mk b/hw/bsp/fomu/board.mk index b824b6979..403a7fb95 100644 --- a/hw/bsp/fomu/board.mk +++ b/hw/bsp/fomu/board.mk @@ -5,6 +5,9 @@ CFLAGS += \ -nostdlib \ -DCFG_TUSB_MCU=OPT_MCU_VALENTYUSB_EPTRI +# Cross Compiler for RISC-V +CROSS_COMPILE = riscv-none-embed- + MCU_DIR = hw/mcu/fomu BSP_DIR = hw/bsp/fomu diff --git a/hw/bsp/msp_exp430f5529lp/board.mk b/hw/bsp/msp_exp430f5529lp/board.mk index 13e3b7217..8e857eb66 100644 --- a/hw/bsp/msp_exp430f5529lp/board.mk +++ b/hw/bsp/msp_exp430f5529lp/board.mk @@ -6,6 +6,9 @@ CFLAGS += \ #-mmcu=msp430f5529 +# Cross Compiler for MSP430 +CROSS_COMPILE = msp430-elf- + # All source paths should be relative to the top level. LD_FILE = hw/mcu/ti/msp430/msp430-gcc-support-files/include/msp430f5529.ld LDINC += $(TOP)/hw/mcu/ti/msp430/msp430-gcc-support-files/include diff --git a/tools/build_all.py b/tools/build_all.py index 08964bb76..0437bcaac 100644 --- a/tools/build_all.py +++ b/tools/build_all.py @@ -88,7 +88,7 @@ for example in all_examples: fail_count += 1 build_duration = time.monotonic() - start_time - print(build_format.format(example, board, success, "{:.2f}".format(build_duration), flash_size, sram_size)) + print(build_format.format(example, board, success, "{:.2f}s".format(build_duration), flash_size, sram_size)) if build_result.returncode != 0: print(build_result.stdout.decode("utf-8")) From 09262d7f7e7bc462e2badac6caeb03cc57bf6761 Mon Sep 17 00:00:00 2001 From: hathach Date: Thu, 26 Mar 2020 22:04:24 +0700 Subject: [PATCH 2/4] house keeping --- examples/make.mk | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/examples/make.mk b/examples/make.mk index 5fc596f63..f2a8b979e 100644 --- a/examples/make.mk +++ b/examples/make.mk @@ -46,26 +46,24 @@ SRC_C += $(subst $(TOP)/,,$(wildcard $(TOP)/hw/bsp/$(BOARD)/*.c)) # Compiler Flags CFLAGS += \ + -fdata-sections \ + -ffunction-sections \ -fsingle-precision-constant \ -fno-strict-aliasing \ -Wdouble-promotion \ - -Wno-endif-labels \ -Wstrict-prototypes \ -Wall \ -Wextra \ -Werror \ - -Werror-implicit-function-declaration \ -Wfatal-errors \ + -Werror-implicit-function-declaration \ -Wfloat-equal \ -Wundef \ -Wshadow \ -Wwrite-strings \ -Wsign-compare \ -Wmissing-format-attribute \ - -Wno-deprecated-declarations \ - -Wunreachable-code \ - -ffunction-sections \ - -fdata-sections + -Wunreachable-code # This causes lots of warning with nrf5x build due to nrfx code # CFLAGS += -Wcast-align From 1712b61ab64b8ae64cbe20a2b44d5e01d35d5666 Mon Sep 17 00:00:00 2001 From: hathach Date: Sat, 28 Mar 2020 21:34:42 +0700 Subject: [PATCH 3/4] added Arduino Nano 33 BLE with/without Sense --- docs/boards.md | 2 + .../arduino_nano33_ble/arduino_nano33_ble.c | 216 ++++++++++++++++++ .../arduino_nano33_ble/arduino_nano33_ble.ld | 32 +++ hw/bsp/arduino_nano33_ble/board.mk | 63 +++++ 4 files changed, 313 insertions(+) create mode 100644 hw/bsp/arduino_nano33_ble/arduino_nano33_ble.c create mode 100755 hw/bsp/arduino_nano33_ble/arduino_nano33_ble.ld create mode 100644 hw/bsp/arduino_nano33_ble/board.mk diff --git a/docs/boards.md b/docs/boards.md index 3d2f39c5c..8955674c8 100644 --- a/docs/boards.md +++ b/docs/boards.md @@ -26,6 +26,8 @@ This code base already had supported for a handful of following boards (sorted a - [Adafruit CLUE](https://www.adafruit.com/product/4500) - [Adafruit Feather nRF52840 Express](https://www.adafruit.com/product/4062) - [Adafruit Feather nRF52840 Sense](https://www.adafruit.com/product/4516) +- [Arduino Nano 33 BLE](https://store.arduino.cc/usa/nano-33-ble) +- [Arduino Nano 33 BLE Sense](https://store.arduino.cc/usa/nano-33-ble-sense) - [Maker Diary nRF52840 MDK Dongle](https://wiki.makerdiary.com/nrf52840-mdk-usb-dongle) - [Nordic nRF52840 Development Kit (aka pca10056)](https://www.nordicsemi.com/Software-and-Tools/Development-Kits/nRF52840-DK) - [Nordic nRF52840 Dongle (aka pca10059)](https://www.nordicsemi.com/Software-and-Tools/Development-Kits/nRF52840-Dongle) diff --git a/hw/bsp/arduino_nano33_ble/arduino_nano33_ble.c b/hw/bsp/arduino_nano33_ble/arduino_nano33_ble.c new file mode 100644 index 000000000..941716c2f --- /dev/null +++ b/hw/bsp/arduino_nano33_ble/arduino_nano33_ble.c @@ -0,0 +1,216 @@ +/* + * 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 "bsp/board.h" + +#include "nrfx.h" +#include "nrfx/hal/nrf_gpio.h" +#include "nrfx/drivers/include/nrfx_power.h" +#include "nrfx/drivers/include/nrfx_uarte.h" + +#ifdef SOFTDEVICE_PRESENT +#include "nrf_sdm.h" +#include "nrf_soc.h" +#endif + +/*------------------------------------------------------------------*/ +/* MACRO TYPEDEF CONSTANT ENUM + *------------------------------------------------------------------*/ +#define _PINNUM(port, pin) ((port)*32 + (pin)) + +#define LED_PIN _PINNUM(0, 24) +#define LED_STATE_ON 0 + +#define BUTTON_PIN _PINNUM(1, 11) // D2 + +#define UART_RX_PIN _PINNUM(1, 10) +#define UART_TX_PIN _PINNUM(1, 3) + +static nrfx_uarte_t _uart_id = NRFX_UARTE_INSTANCE(0); + +// tinyusb function that handles power event (detected, ready, removed) +// We must call it within SD's SOC event handler, or set it as power event handler if SD is not enabled. +extern void tusb_hal_nrf_power_event(uint32_t event); + +void board_init(void) +{ + // stop LF clock just in case we jump from application without reset + NRF_CLOCK->TASKS_LFCLKSTOP = 1UL; + + // Config clock source: XTAL or RC in sdk_config.h + NRF_CLOCK->LFCLKSRC = (uint32_t)((CLOCK_LFCLKSRC_SRC_Xtal << CLOCK_LFCLKSRC_SRC_Pos) & CLOCK_LFCLKSRC_SRC_Msk); + NRF_CLOCK->TASKS_LFCLKSTART = 1UL; + + // LED + nrf_gpio_cfg_output(LED_PIN); + board_led_write(false); + + // Button + nrf_gpio_cfg_input(BUTTON_PIN, NRF_GPIO_PIN_PULLUP); + + // 1ms tick timer + SysTick_Config(SystemCoreClock/1000); + + // UART + nrfx_uarte_config_t uart_cfg = + { + .pseltxd = UART_TX_PIN, + .pselrxd = UART_RX_PIN, + .pselcts = NRF_UARTE_PSEL_DISCONNECTED, + .pselrts = NRF_UARTE_PSEL_DISCONNECTED, + .p_context = NULL, + .baudrate = NRF_UARTE_BAUDRATE_115200, // CFG_BOARD_UART_BAUDRATE + .interrupt_priority = 7, + .hal_cfg = { + .hwfc = NRF_UARTE_HWFC_DISABLED, + .parity = NRF_UARTE_PARITY_EXCLUDED, + } + }; + + nrfx_uarte_init(&_uart_id, &uart_cfg, NULL); //uart_handler); + +#if TUSB_OPT_DEVICE_ENABLED + // Priorities 0, 1, 4 (nRF52) are reserved for SoftDevice + // 2 is highest for application + NVIC_SetPriority(USBD_IRQn, 2); + + // USB power may already be ready at this time -> no event generated + // We need to invoke the handler based on the status initially + uint32_t usb_reg; + +#ifdef SOFTDEVICE_PRESENT + uint8_t sd_en = false; + sd_softdevice_is_enabled(&sd_en); + + if ( sd_en ) { + sd_power_usbdetected_enable(true); + sd_power_usbpwrrdy_enable(true); + sd_power_usbremoved_enable(true); + + sd_power_usbregstatus_get(&usb_reg); + }else +#endif + { + // Power module init + const nrfx_power_config_t pwr_cfg = { 0 }; + nrfx_power_init(&pwr_cfg); + + // Register tusb function as USB power handler + const nrfx_power_usbevt_config_t config = { .handler = (nrfx_power_usb_event_handler_t) tusb_hal_nrf_power_event }; + nrfx_power_usbevt_init(&config); + + nrfx_power_usbevt_enable(); + + usb_reg = NRF_POWER->USBREGSTATUS; + } + + if ( usb_reg & POWER_USBREGSTATUS_VBUSDETECT_Msk ) tusb_hal_nrf_power_event(NRFX_POWER_USB_EVT_DETECTED); + if ( usb_reg & POWER_USBREGSTATUS_OUTPUTRDY_Msk ) tusb_hal_nrf_power_event(NRFX_POWER_USB_EVT_READY); +#endif +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + nrf_gpio_pin_write(LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); +} + +uint32_t board_button_read(void) +{ + // button is active LOW + return (nrf_gpio_pin_read(BUTTON_PIN) ? 0 : 1); +} + +int board_uart_read(uint8_t* buf, int len) +{ + (void) buf; (void) len; + return 0; +// return NRFX_SUCCESS == nrfx_uart_rx(&_uart_id, buf, (size_t) len) ? len : 0; +} + +int board_uart_write(void const * buf, int len) +{ + return (NRFX_SUCCESS == nrfx_uarte_tx(&_uart_id, (uint8_t const*) buf, (size_t) len)) ? len : 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 + +#ifdef SOFTDEVICE_PRESENT +// process SOC event from SD +uint32_t proc_soc(void) +{ + uint32_t soc_evt; + uint32_t err = sd_evt_get(&soc_evt); + + if (NRF_SUCCESS == err) + { + /*------------- usb power event handler -------------*/ + int32_t usbevt = (soc_evt == NRF_EVT_POWER_USB_DETECTED ) ? NRFX_POWER_USB_EVT_DETECTED: + (soc_evt == NRF_EVT_POWER_USB_POWER_READY) ? NRFX_POWER_USB_EVT_READY : + (soc_evt == NRF_EVT_POWER_USB_REMOVED ) ? NRFX_POWER_USB_EVT_REMOVED : -1; + + if ( usbevt >= 0) tusb_hal_nrf_power_event(usbevt); + } + + return err; +} + +uint32_t proc_ble(void) +{ + // do nothing with ble + return NRF_ERROR_NOT_FOUND; +} + +void SD_EVT_IRQHandler(void) +{ + // process BLE and SOC until there is no more events + while( (NRF_ERROR_NOT_FOUND != proc_ble()) || (NRF_ERROR_NOT_FOUND != proc_soc()) ) + { + + } +} + +void nrf_error_cb(uint32_t id, uint32_t pc, uint32_t info) +{ + (void) id; + (void) pc; + (void) info; +} +#endif diff --git a/hw/bsp/arduino_nano33_ble/arduino_nano33_ble.ld b/hw/bsp/arduino_nano33_ble/arduino_nano33_ble.ld new file mode 100755 index 000000000..f570740b6 --- /dev/null +++ b/hw/bsp/arduino_nano33_ble/arduino_nano33_ble.ld @@ -0,0 +1,32 @@ +/* Linker script to configure memory regions. */ + +SEARCH_DIR(.) +GROUP(-lgcc -lc -lnosys) + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x10000, LENGTH = 0xf0000 + RAM_NVIC (rwx) : ORIGIN = 0x20000000, LENGTH = 0x100 + RAM_CRASH_DATA (rwx) : ORIGIN = (0x20000000 + 0x100), LENGTH = 0x100 + RAM (rwx) : ORIGIN = ((0x20000000 + 0x100) + 0x100), LENGTH = (0x40000 - (0x100 + 0x100)) +} + +SECTIONS +{ + . = ALIGN(4); + .svc_data : + { + PROVIDE(__start_svc_data = .); + KEEP(*(.svc_data)) + PROVIDE(__stop_svc_data = .); + } > RAM + + .fs_data : + { + PROVIDE(__start_fs_data = .); + KEEP(*(.fs_data)) + PROVIDE(__stop_fs_data = .); + } > RAM +} INSERT AFTER .data; + +INCLUDE "nrf52_common.ld" diff --git a/hw/bsp/arduino_nano33_ble/board.mk b/hw/bsp/arduino_nano33_ble/board.mk new file mode 100644 index 000000000..d217d37c0 --- /dev/null +++ b/hw/bsp/arduino_nano33_ble/board.mk @@ -0,0 +1,63 @@ +CFLAGS += \ + -flto \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m4 \ + -mfloat-abi=hard \ + -mfpu=fpv4-sp-d16 \ + -DCFG_TUSB_MCU=OPT_MCU_NRF5X \ + -DNRF52840_XXAA \ + -DCONFIG_GPIO_AS_PINRESET + +# nrfx issue undef _ARMCC_VERSION usage https://github.com/NordicSemiconductor/nrfx/issues/49 +CFLAGS += -Wno-error=undef -Wno-error=unused-parameter + +# due to tusb_hal_nrf_power_event +GCCVERSION = $(firstword $(subst ., ,$(shell arm-none-eabi-gcc -dumpversion))) +ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) +CFLAGS += -Wno-error=cast-function-type +endif + +# All source paths should be relative to the top level. +#LD_FILE = hw/bsp/$(BOARD)/linker_script.ld +LD_FILE = hw/bsp/$(BOARD)/arduino_nano33_ble.ld + +LDFLAGS += -L$(TOP)/hw/mcu/nordic/nrfx/mdk + +SRC_C += \ + hw/mcu/nordic/nrfx/drivers/src/nrfx_power.c \ + hw/mcu/nordic/nrfx/drivers/src/nrfx_uarte.c \ + hw/mcu/nordic/nrfx/mdk/system_nrf52840.c + +INC += \ + $(TOP)/lib/CMSIS_4/CMSIS/Include \ + $(TOP)/hw/mcu/nordic \ + $(TOP)/hw/mcu/nordic/nrfx \ + $(TOP)/hw/mcu/nordic/nrfx/mdk \ + $(TOP)/hw/mcu/nordic/nrfx/hal \ + $(TOP)/hw/mcu/nordic/nrfx/drivers/include \ + $(TOP)/hw/mcu/nordic/nrfx/drivers/src \ + +SRC_S += hw/mcu/nordic/nrfx/mdk/gcc_startup_nrf52840.S + +ASFLAGS += -D__HEAP_SIZE=0 + +# For TinyUSB port source +VENDOR = nordic +CHIP_FAMILY = nrf5x + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM4F + +# For flash-jlink target +JLINK_DEVICE = nRF52840_xxAA +JLINK_IF = swd + +# flash using bossac (as part of Nano33 BSP tools) +# can be found in arduino15/packages/arduino/tools/bossac/ +# Add it to your PATH or change BOSSAC variable to match your installation +BOSSAC = bossac + +flash: $(BUILD)/$(BOARD)-firmware.bin + @:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0) + $(BOSSAC) --port=$(SERIAL) -U -i -e -w $^ -R From ad2824df8bb947c420b0bd4722378eed46981934 Mon Sep 17 00:00:00 2001 From: hathach Date: Sat, 28 Mar 2020 22:25:07 +0700 Subject: [PATCH 4/4] add ENTRY(Reset_Handler) to linker of samd21 and samd51 board fix #303 --- hw/bsp/circuitplayground_express/samd21g18a_flash.ld | 2 ++ hw/bsp/feather_m0_express/samd21g18a_flash.ld | 2 ++ hw/bsp/feather_m4_express/samd51g19a_flash.ld | 2 ++ hw/bsp/itsybitsy_m0/samd21g18a_flash.ld | 2 ++ hw/bsp/itsybitsy_m4/samd51g19a_flash.ld | 2 ++ hw/bsp/metro_m0_express/samd21g18a_flash.ld | 2 ++ hw/bsp/metro_m4_express/samd51g19a_flash.ld | 2 ++ hw/bsp/seeeduino_xiao/samd21g18a_flash.ld | 3 +-- 8 files changed, 15 insertions(+), 2 deletions(-) diff --git a/hw/bsp/circuitplayground_express/samd21g18a_flash.ld b/hw/bsp/circuitplayground_express/samd21g18a_flash.ld index 7fc42171b..f0c93340c 100644 --- a/hw/bsp/circuitplayground_express/samd21g18a_flash.ld +++ b/hw/bsp/circuitplayground_express/samd21g18a_flash.ld @@ -42,6 +42,8 @@ MEMORY /* The stack size used by the application. NOTE: you need to adjust according to your application. */ STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : DEFINED(__stack_size__) ? __stack_size__ : 0x2000; +ENTRY(Reset_Handler) + /* Section Definitions */ SECTIONS { diff --git a/hw/bsp/feather_m0_express/samd21g18a_flash.ld b/hw/bsp/feather_m0_express/samd21g18a_flash.ld index 7fc42171b..f0c93340c 100644 --- a/hw/bsp/feather_m0_express/samd21g18a_flash.ld +++ b/hw/bsp/feather_m0_express/samd21g18a_flash.ld @@ -42,6 +42,8 @@ MEMORY /* The stack size used by the application. NOTE: you need to adjust according to your application. */ STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : DEFINED(__stack_size__) ? __stack_size__ : 0x2000; +ENTRY(Reset_Handler) + /* Section Definitions */ SECTIONS { diff --git a/hw/bsp/feather_m4_express/samd51g19a_flash.ld b/hw/bsp/feather_m4_express/samd51g19a_flash.ld index cf5db3800..f1a021d75 100644 --- a/hw/bsp/feather_m4_express/samd51g19a_flash.ld +++ b/hw/bsp/feather_m4_express/samd51g19a_flash.ld @@ -44,6 +44,8 @@ MEMORY /* The stack size used by the application. NOTE: you need to adjust according to your application. */ STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : DEFINED(__stack_size__) ? __stack_size__ : 0xC000; +ENTRY(Reset_Handler) + /* Section Definitions */ SECTIONS { diff --git a/hw/bsp/itsybitsy_m0/samd21g18a_flash.ld b/hw/bsp/itsybitsy_m0/samd21g18a_flash.ld index 7fc42171b..f0c93340c 100644 --- a/hw/bsp/itsybitsy_m0/samd21g18a_flash.ld +++ b/hw/bsp/itsybitsy_m0/samd21g18a_flash.ld @@ -42,6 +42,8 @@ MEMORY /* The stack size used by the application. NOTE: you need to adjust according to your application. */ STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : DEFINED(__stack_size__) ? __stack_size__ : 0x2000; +ENTRY(Reset_Handler) + /* Section Definitions */ SECTIONS { diff --git a/hw/bsp/itsybitsy_m4/samd51g19a_flash.ld b/hw/bsp/itsybitsy_m4/samd51g19a_flash.ld index cf5db3800..f1a021d75 100644 --- a/hw/bsp/itsybitsy_m4/samd51g19a_flash.ld +++ b/hw/bsp/itsybitsy_m4/samd51g19a_flash.ld @@ -44,6 +44,8 @@ MEMORY /* The stack size used by the application. NOTE: you need to adjust according to your application. */ STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : DEFINED(__stack_size__) ? __stack_size__ : 0xC000; +ENTRY(Reset_Handler) + /* Section Definitions */ SECTIONS { diff --git a/hw/bsp/metro_m0_express/samd21g18a_flash.ld b/hw/bsp/metro_m0_express/samd21g18a_flash.ld index 7fc42171b..f0c93340c 100644 --- a/hw/bsp/metro_m0_express/samd21g18a_flash.ld +++ b/hw/bsp/metro_m0_express/samd21g18a_flash.ld @@ -42,6 +42,8 @@ MEMORY /* The stack size used by the application. NOTE: you need to adjust according to your application. */ STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : DEFINED(__stack_size__) ? __stack_size__ : 0x2000; +ENTRY(Reset_Handler) + /* Section Definitions */ SECTIONS { diff --git a/hw/bsp/metro_m4_express/samd51g19a_flash.ld b/hw/bsp/metro_m4_express/samd51g19a_flash.ld index cf5db3800..f1a021d75 100644 --- a/hw/bsp/metro_m4_express/samd51g19a_flash.ld +++ b/hw/bsp/metro_m4_express/samd51g19a_flash.ld @@ -44,6 +44,8 @@ MEMORY /* The stack size used by the application. NOTE: you need to adjust according to your application. */ STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : DEFINED(__stack_size__) ? __stack_size__ : 0xC000; +ENTRY(Reset_Handler) + /* Section Definitions */ SECTIONS { diff --git a/hw/bsp/seeeduino_xiao/samd21g18a_flash.ld b/hw/bsp/seeeduino_xiao/samd21g18a_flash.ld index bae38a881..cf11c4c35 100644 --- a/hw/bsp/seeeduino_xiao/samd21g18a_flash.ld +++ b/hw/bsp/seeeduino_xiao/samd21g18a_flash.ld @@ -52,8 +52,7 @@ SECTIONS . = ALIGN(4); _sfixed = .; KEEP(*(.vectors .vectors.*)) - *(.text*) - *(.gnu.linkonce.t.*) + *(.text .text.* .gnu.linkonce.t.*) *(.glue_7t) *(.glue_7) *(.rodata .rodata* .gnu.linkonce.r.*) *(.ARM.extab* .gnu.linkonce.armextab.*)