diff --git a/docs/boards.md b/docs/boards.md index cf5defb51..d56e39bd0 100644 --- a/docs/boards.md +++ b/docs/boards.md @@ -13,14 +13,18 @@ This code base already had supported for a handful of following boards (sorted a - [Adafruit Circuit Playground Express](https://www.adafruit.com/product/3333) - [Adafruit Feather M0 Express](https://www.adafruit.com/product/3403) -- [Adafruit Metro M0 Express](https://www.adafruit.com/product/3505) - [Adafruit Feather M4 Express](https://www.adafruit.com/product/3857) +- [Adafruit ItsyBitsy M0 Express](https://www.adafruit.com/product/3727) +- [Adafruit ItsyBitsy M4 Express](https://www.adafruit.com/product/3800) +- [Adafruit Metro M0 Express](https://www.adafruit.com/product/3505) - [Adafruit Metro M4 Express](https://www.adafruit.com/product/3382) ### Nordic nRF5x -- [Adafruit Feather nRF52840 Express](https://www.adafruit.com/product/4062) - [Adafruit Circuit Playground Bluefruit](https://www.adafruit.com/product/4333) +- [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) - [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) @@ -32,6 +36,7 @@ This code base already had supported for a handful of following boards (sorted a - [NuTiny NUC121S](https://direct.nuvoton.com/en/nutiny-nuc121s) - [NuTiny NUC125S](https://direct.nuvoton.com/en/nutiny-nuc125s) - [NuTiny NUC126V](https://direct.nuvoton.com/en/nutiny-nuc126v) +- [NuTiny SDK NUC505Y](https://direct.nuvoton.com/en/nutiny-nuc505y) ### NXP iMX RT diff --git a/hw/bsp/adafruit_clue/adafruit_clue.c b/hw/bsp/adafruit_clue/adafruit_clue.c new file mode 100644 index 000000000..67b5ffda4 --- /dev/null +++ b/hw/bsp/adafruit_clue/adafruit_clue.c @@ -0,0 +1,192 @@ +/* + * 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" + +#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(1, 1) +#define LED_STATE_ON 1 + +#define BUTTON_PIN _PINNUM(1, 02) + +// 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) +{ + // 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); + +#if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock/1000); +#endif + +#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; +} + +int board_uart_write(void const * buf, int len) +{ + (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 + +#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/adafruit_clue/board.mk b/hw/bsp/adafruit_clue/board.mk new file mode 100644 index 000000000..3b2137d74 --- /dev/null +++ b/hw/bsp/adafruit_clue/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)/nrf52840_s140_v6.ld + +LDFLAGS += -L$(TOP)/hw/mcu/nordic/nrfx/mdk + +SRC_C += \ + hw/mcu/nordic/nrfx/drivers/src/nrfx_power.c \ + hw/mcu/nordic/nrfx/mdk/system_nrf52840.c \ + +INC += \ + $(TOP)/hw/mcu/nordic/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 + +# For uf2 conversion +UF2_FAMILY = 0xADA52840 + +$(BUILD)/$(BOARD)-firmware.zip: $(BUILD)/$(BOARD)-firmware.hex + adafruit-nrfutil dfu genpkg --dev-type 0x0052 --sd-req 0xFFFE --application $^ $@ + +# flash using adafruit-nrfutil dfu +flash: $(BUILD)/$(BOARD)-firmware.zip + @:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0) + adafruit-nrfutil --verbose dfu serial --package $^ -p $(SERIAL) -b 115200 --singlebank --touch 1200 diff --git a/hw/bsp/adafruit_clue/nrf52840_s140_v6.ld b/hw/bsp/adafruit_clue/nrf52840_s140_v6.ld new file mode 100755 index 000000000..5314a4e93 --- /dev/null +++ b/hw/bsp/adafruit_clue/nrf52840_s140_v6.ld @@ -0,0 +1,38 @@ +/* Linker script to configure memory regions. */ + +SEARCH_DIR(.) +GROUP(-lgcc -lc -lnosys) + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x26000, LENGTH = 0xED000 - 0x26000 + + /* SRAM required by S132 depend on + * - Attribute Table Size + * - Vendor UUID count + * - Max ATT MTU + * - Concurrent connection peripheral + central + secure links + * - Event Len, HVN queue, Write CMD queue + */ + RAM (rwx) : ORIGIN = 0x20003400, LENGTH = 0x20040000 - 0x20003400 +} + +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/circuitplayground_bluefruit/board.mk b/hw/bsp/circuitplayground_bluefruit/board.mk index bfeaa2355..3b2137d74 100644 --- a/hw/bsp/circuitplayground_bluefruit/board.mk +++ b/hw/bsp/circuitplayground_bluefruit/board.mk @@ -19,7 +19,7 @@ CFLAGS += -Wno-error=cast-function-type endif # All source paths should be relative to the top level. -LD_FILE = hw/bsp/circuitplayground_bluefruit/nrf52840_s140_v6.ld +LD_FILE = hw/bsp/$(BOARD)/nrf52840_s140_v6.ld LDFLAGS += -L$(TOP)/hw/mcu/nordic/nrfx/mdk diff --git a/hw/bsp/circuitplayground_express/board.mk b/hw/bsp/circuitplayground_express/board.mk index 7ea90e8e1..32b440715 100644 --- a/hw/bsp/circuitplayground_express/board.mk +++ b/hw/bsp/circuitplayground_express/board.mk @@ -8,7 +8,7 @@ CFLAGS += \ -DCFG_TUSB_MCU=OPT_MCU_SAMD21 # All source paths should be relative to the top level. -LD_FILE = hw/bsp/circuitplayground_express/samd21g18a_flash.ld +LD_FILE = hw/bsp/$(BOARD)/samd21g18a_flash.ld SRC_C += \ hw/mcu/microchip/samd/asf4/samd21/gcc/gcc/startup_samd21.c \ diff --git a/hw/bsp/ea4088qs/board.mk b/hw/bsp/ea4088qs/board.mk index a88976d3a..950aa484c 100644 --- a/hw/bsp/ea4088qs/board.mk +++ b/hw/bsp/ea4088qs/board.mk @@ -15,7 +15,7 @@ CFLAGS += -Wno-error=strict-prototypes -Wno-error=unused-parameter MCU_DIR = hw/mcu/nxp/lpcopen/lpc40xx/lpc_chip_40xx # All source paths should be relative to the top level. -LD_FILE = hw/bsp/ea4088qs/lpc4088.ld +LD_FILE = hw/bsp/$(BOARD)/lpc4088.ld SRC_C += \ $(MCU_DIR)/../gcc/cr_startup_lpc40xx.c \ diff --git a/hw/bsp/ea4357/board.mk b/hw/bsp/ea4357/board.mk index 098fb4c90..ff7b7a151 100644 --- a/hw/bsp/ea4357/board.mk +++ b/hw/bsp/ea4357/board.mk @@ -14,7 +14,7 @@ CFLAGS += -Wno-error=unused-parameter -Wno-error=strict-prototypes MCU_DIR = hw/mcu/nxp/lpcopen/lpc43xx/lpc_chip_43xx # All source paths should be relative to the top level. -LD_FILE = hw/bsp/ea4357/lpc4357.ld +LD_FILE = hw/bsp/$(BOARD)/lpc4357.ld SRC_C += \ $(MCU_DIR)/../gcc/cr_startup_lpc43xx.c \ diff --git a/hw/bsp/feather_m0_express/board.mk b/hw/bsp/feather_m0_express/board.mk index a147cf82d..d762c4eca 100644 --- a/hw/bsp/feather_m0_express/board.mk +++ b/hw/bsp/feather_m0_express/board.mk @@ -9,7 +9,7 @@ CFLAGS += \ -DCFG_TUSB_MCU=OPT_MCU_SAMD21 # All source paths should be relative to the top level. -LD_FILE = hw/bsp/feather_m0_express/samd21g18a_flash.ld +LD_FILE = hw/bsp/$(BOARD)/samd21g18a_flash.ld SRC_C += \ hw/mcu/microchip/samd/asf4/samd21/gcc/gcc/startup_samd21.c \ diff --git a/hw/bsp/feather_m4_express/board.mk b/hw/bsp/feather_m4_express/board.mk index f42aa7703..49c2d7f2f 100644 --- a/hw/bsp/feather_m4_express/board.mk +++ b/hw/bsp/feather_m4_express/board.mk @@ -12,7 +12,7 @@ CFLAGS += \ CFLAGS += -Wno-error=undef # All source paths should be relative to the top level. -LD_FILE = hw/bsp/metro_m4_express/samd51g19a_flash.ld +LD_FILE = hw/bsp/$(BOARD)/samd51g19a_flash.ld SRC_C += \ hw/mcu/microchip/samd/asf4/samd51/gcc/gcc/startup_samd51.c \ diff --git a/hw/bsp/feather_nrf52840_express/board.mk b/hw/bsp/feather_nrf52840_express/board.mk index b4d6fbe9f..3b2137d74 100644 --- a/hw/bsp/feather_nrf52840_express/board.mk +++ b/hw/bsp/feather_nrf52840_express/board.mk @@ -19,7 +19,7 @@ CFLAGS += -Wno-error=cast-function-type endif # All source paths should be relative to the top level. -LD_FILE = hw/bsp/feather_nrf52840_express/nrf52840_s140_v6.ld +LD_FILE = hw/bsp/$(BOARD)/nrf52840_s140_v6.ld LDFLAGS += -L$(TOP)/hw/mcu/nordic/nrfx/mdk diff --git a/hw/bsp/feather_nrf52840_sense/board.mk b/hw/bsp/feather_nrf52840_sense/board.mk new file mode 100644 index 000000000..3b2137d74 --- /dev/null +++ b/hw/bsp/feather_nrf52840_sense/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)/nrf52840_s140_v6.ld + +LDFLAGS += -L$(TOP)/hw/mcu/nordic/nrfx/mdk + +SRC_C += \ + hw/mcu/nordic/nrfx/drivers/src/nrfx_power.c \ + hw/mcu/nordic/nrfx/mdk/system_nrf52840.c \ + +INC += \ + $(TOP)/hw/mcu/nordic/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 + +# For uf2 conversion +UF2_FAMILY = 0xADA52840 + +$(BUILD)/$(BOARD)-firmware.zip: $(BUILD)/$(BOARD)-firmware.hex + adafruit-nrfutil dfu genpkg --dev-type 0x0052 --sd-req 0xFFFE --application $^ $@ + +# flash using adafruit-nrfutil dfu +flash: $(BUILD)/$(BOARD)-firmware.zip + @:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0) + adafruit-nrfutil --verbose dfu serial --package $^ -p $(SERIAL) -b 115200 --singlebank --touch 1200 diff --git a/hw/bsp/feather_nrf52840_sense/feather_nrf52840_sense.c b/hw/bsp/feather_nrf52840_sense/feather_nrf52840_sense.c new file mode 100644 index 000000000..468f96c5e --- /dev/null +++ b/hw/bsp/feather_nrf52840_sense/feather_nrf52840_sense.c @@ -0,0 +1,192 @@ +/* + * 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" + +#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(1, 9) +#define LED_STATE_ON 1 + +#define BUTTON_PIN _PINNUM(1, 02) + +// 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) +{ + // 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); + +#if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock/1000); +#endif + +#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; +} + +int board_uart_write(void const * buf, int len) +{ + (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 + +#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/feather_nrf52840_sense/nrf52840_s140_v6.ld b/hw/bsp/feather_nrf52840_sense/nrf52840_s140_v6.ld new file mode 100644 index 000000000..5314a4e93 --- /dev/null +++ b/hw/bsp/feather_nrf52840_sense/nrf52840_s140_v6.ld @@ -0,0 +1,38 @@ +/* Linker script to configure memory regions. */ + +SEARCH_DIR(.) +GROUP(-lgcc -lc -lnosys) + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x26000, LENGTH = 0xED000 - 0x26000 + + /* SRAM required by S132 depend on + * - Attribute Table Size + * - Vendor UUID count + * - Max ATT MTU + * - Concurrent connection peripheral + central + secure links + * - Event Len, HVN queue, Write CMD queue + */ + RAM (rwx) : ORIGIN = 0x20003400, LENGTH = 0x20040000 - 0x20003400 +} + +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/feather_stm32f405/board.mk b/hw/bsp/feather_stm32f405/board.mk index 5a007cad0..2d1f8bb8d 100644 --- a/hw/bsp/feather_stm32f405/board.mk +++ b/hw/bsp/feather_stm32f405/board.mk @@ -13,7 +13,7 @@ ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32F4xx_HAL_Driver ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32F4xx # All source paths should be relative to the top level. -LD_FILE = hw/bsp/pyboardv11/STM32F405RGTx_FLASH.ld +LD_FILE = hw/bsp/$(BOARD)/STM32F405RGTx_FLASH.ld SRC_C += \ $(ST_CMSIS)/Source/Templates/system_stm32f4xx.c \ diff --git a/hw/bsp/fomu/board.mk b/hw/bsp/fomu/board.mk index 4e8101b7f..8687cf41a 100644 --- a/hw/bsp/fomu/board.mk +++ b/hw/bsp/fomu/board.mk @@ -9,7 +9,7 @@ MCU_DIR = hw/mcu/fomu BSP_DIR = hw/bsp/fomu # All source paths should be relative to the top level. -LD_FILE = hw/bsp/fomu/fomu.ld +LD_FILE = hw/bsp/$(BOARD)/fomu.ld # TODO remove later SRC_C += src/portable/$(VENDOR)/$(CHIP_FAMILY)/hal_$(CHIP_FAMILY).c diff --git a/hw/bsp/itsybitsy_m0/board.mk b/hw/bsp/itsybitsy_m0/board.mk new file mode 100644 index 000000000..d762c4eca --- /dev/null +++ b/hw/bsp/itsybitsy_m0/board.mk @@ -0,0 +1,45 @@ +CFLAGS += \ + -flto \ + -mthumb \ + -mabi=aapcs-linux \ + -mcpu=cortex-m0plus \ + -nostdlib -nostartfiles \ + -D__SAMD21G18A__ \ + -DCONF_DFLL_OVERWRITE_CALIBRATION=0 \ + -DCFG_TUSB_MCU=OPT_MCU_SAMD21 + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/samd21g18a_flash.ld + +SRC_C += \ + hw/mcu/microchip/samd/asf4/samd21/gcc/gcc/startup_samd21.c \ + hw/mcu/microchip/samd/asf4/samd21/gcc/system_samd21.c \ + hw/mcu/microchip/samd/asf4/samd21/hpl/gclk/hpl_gclk.c \ + hw/mcu/microchip/samd/asf4/samd21/hpl/pm/hpl_pm.c \ + hw/mcu/microchip/samd/asf4/samd21/hpl/sysctrl/hpl_sysctrl.c \ + hw/mcu/microchip/samd/asf4/samd21/hal/src/hal_atomic.c + +INC += \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd21/ \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd21/config \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd21/include \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd21/hal/include \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd21/hal/utils/include \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd21/hpl/pm/ \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd21/hpl/port \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd21/hri \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd21/CMSIS/Include + +# For TinyUSB port source +VENDOR = microchip +CHIP_FAMILY = samd + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM0 + +# For flash-jlink target +JLINK_DEVICE = ATSAMD21G18 +JLINK_IF = swd + +# flash using jlink +flash: flash-jlink diff --git a/hw/bsp/itsybitsy_m0/itsybitsy_m0.c b/hw/bsp/itsybitsy_m0/itsybitsy_m0.c new file mode 100644 index 000000000..39fe3f354 --- /dev/null +++ b/hw/bsp/itsybitsy_m0/itsybitsy_m0.c @@ -0,0 +1,142 @@ +/* + * 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 "sam.h" +#include "bsp/board.h" + +#include "hal/include/hal_gpio.h" +#include "hal/include/hal_init.h" +#include "hri/hri_nvmctrl_d21.h" + +#include "hpl/gclk/hpl_gclk_base.h" +#include "hpl_pm_config.h" +#include "hpl/pm/hpl_pm_base.h" + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM DECLARATION +//--------------------------------------------------------------------+ +#define LED_PIN 17 +#define BUTTON_PIN 21 // pin D7 + +/* Referenced GCLKs, should be initialized firstly */ +#define _GCLK_INIT_1ST (1 << 0 | 1 << 1) + +/* Not referenced GCLKs, initialized last */ +#define _GCLK_INIT_LAST (~_GCLK_INIT_1ST) + +void board_init(void) +{ + // Clock init ( follow hpl_init.c ) + hri_nvmctrl_set_CTRLB_RWS_bf(NVMCTRL, 2); + + _pm_init(); + _sysctrl_init_sources(); +#if _GCLK_INIT_1ST + _gclk_init_generators_by_fref(_GCLK_INIT_1ST); +#endif + _sysctrl_init_referenced_generators(); + _gclk_init_generators_by_fref(_GCLK_INIT_LAST); + + // Led init + gpio_set_pin_direction(LED_PIN, GPIO_DIRECTION_OUT); + gpio_set_pin_level(LED_PIN, 0); + + // Button init + gpio_set_pin_direction(BUTTON_PIN, GPIO_DIRECTION_IN); + gpio_set_pin_pull_mode(BUTTON_PIN, GPIO_PULL_UP); + +#if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer (samd SystemCoreClock may not correct) + SysTick_Config(CONF_CPU_FREQUENCY / 1000); +#endif + + /* USB Clock init + * The USB module requires a GCLK_USB of 48 MHz ~ 0.25% clock + * for low speed and full speed operation. */ + _pm_enable_bus_clock(PM_BUS_APBB, USB); + _pm_enable_bus_clock(PM_BUS_AHB, USB); + _gclk_enable_channel(USB_GCLK_ID, GCLK_CLKCTRL_GEN_GCLK0_Val); + + // USB Pin Init + gpio_set_pin_direction(PIN_PA24, GPIO_DIRECTION_OUT); + gpio_set_pin_level(PIN_PA24, false); + gpio_set_pin_pull_mode(PIN_PA24, GPIO_PULL_OFF); + gpio_set_pin_direction(PIN_PA25, GPIO_DIRECTION_OUT); + gpio_set_pin_level(PIN_PA25, false); + gpio_set_pin_pull_mode(PIN_PA25, GPIO_PULL_OFF); + + gpio_set_pin_function(PIN_PA24, PINMUX_PA24G_USB_DM); + gpio_set_pin_function(PIN_PA25, PINMUX_PA25G_USB_DP); + + // Output 500hz PWM on D12 (PA19 - TCC0 WO[3]) so we can validate the GCLK0 clock speed with a Saleae. + _pm_enable_bus_clock(PM_BUS_APBC, TCC0); + TCC0->PER.bit.PER = 48000000 / 1000; + TCC0->CC[3].bit.CC = 48000000 / 2000; + TCC0->CTRLA.bit.ENABLE = true; + + gpio_set_pin_function(PIN_PA19, PINMUX_PA19F_TCC0_WO3); + _gclk_enable_channel(TCC0_GCLK_ID, GCLK_CLKCTRL_GEN_GCLK0_Val); +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + gpio_set_pin_level(LED_PIN, state); +} + +uint32_t board_button_read(void) +{ + // button is active low + return gpio_get_pin_level(BUTTON_PIN) ? 0 : 1; +} + +int board_uart_read(uint8_t* buf, int len) +{ + (void) buf; (void) len; + return 0; +} + +int board_uart_write(void const * buf, int len) +{ + (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/itsybitsy_m0/samd21g18a_flash.ld b/hw/bsp/itsybitsy_m0/samd21g18a_flash.ld new file mode 100644 index 000000000..7fc42171b --- /dev/null +++ b/hw/bsp/itsybitsy_m0/samd21g18a_flash.ld @@ -0,0 +1,144 @@ +/** + * \file + * + * \brief Linker script for running in internal FLASH on the SAMD21G18A + * + * Copyright (c) 2017 Microchip Technology Inc. + * + * \asf_license_start + * + * \page License + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 Licence 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. + * + * \asf_license_stop + * + */ + + +OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm") +OUTPUT_ARCH(arm) +SEARCH_DIR(.) + +/* Memory Spaces Definitions */ +MEMORY +{ + rom (rx) : ORIGIN = 0x00000000 + 8K, LENGTH = 0x00040000 - 8K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00008000 +} + +/* 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; + +/* Section Definitions */ +SECTIONS +{ + .text : + { + . = ALIGN(4); + _sfixed = .; + KEEP(*(.vectors .vectors.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + *(.ARM.extab* .gnu.linkonce.armextab.*) + + /* Support C constructors, and C destructors in both user code + and the C library. This also provides support for C++ code. */ + . = ALIGN(4); + KEEP(*(.init)) + . = ALIGN(4); + __preinit_array_start = .; + KEEP (*(.preinit_array)) + __preinit_array_end = .; + + . = ALIGN(4); + __init_array_start = .; + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + __init_array_end = .; + + . = ALIGN(4); + KEEP (*crtbegin.o(.ctors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*crtend.o(.ctors)) + + . = ALIGN(4); + KEEP(*(.fini)) + + . = ALIGN(4); + __fini_array_start = .; + KEEP (*(.fini_array)) + KEEP (*(SORT(.fini_array.*))) + __fini_array_end = .; + + KEEP (*crtbegin.o(.dtors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*crtend.o(.dtors)) + + . = ALIGN(4); + _efixed = .; /* End of text section */ + } > rom + + /* .ARM.exidx is sorted, so has to go in its own output section. */ + PROVIDE_HIDDEN (__exidx_start = .); + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > rom + PROVIDE_HIDDEN (__exidx_end = .); + + . = ALIGN(4); + _etext = .; + + .relocate : AT (_etext) + { + . = ALIGN(4); + _srelocate = .; + *(.ramfunc .ramfunc.*); + *(.data .data.*); + . = ALIGN(4); + _erelocate = .; + } > ram + + /* .bss section which is used for uninitialized data */ + .bss (NOLOAD) : + { + . = ALIGN(4); + _sbss = . ; + _szero = .; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + _ezero = .; + end = .; + } > ram + + /* stack section */ + .stack (NOLOAD): + { + . = ALIGN(8); + _sstack = .; + . = . + STACK_SIZE; + . = ALIGN(8); + _estack = .; + } > ram + + . = ALIGN(4); + _end = . ; +} diff --git a/hw/bsp/itsybitsy_m4/board.mk b/hw/bsp/itsybitsy_m4/board.mk new file mode 100644 index 000000000..49c2d7f2f --- /dev/null +++ b/hw/bsp/itsybitsy_m4/board.mk @@ -0,0 +1,48 @@ +CFLAGS += \ + -flto \ + -mthumb \ + -mabi=aapcs-linux \ + -mcpu=cortex-m4 \ + -mfloat-abi=hard \ + -mfpu=fpv4-sp-d16 \ + -nostdlib -nostartfiles \ + -D__SAMD51J19A__ \ + -DCFG_TUSB_MCU=OPT_MCU_SAMD51 + +CFLAGS += -Wno-error=undef + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/samd51g19a_flash.ld + +SRC_C += \ + hw/mcu/microchip/samd/asf4/samd51/gcc/gcc/startup_samd51.c \ + hw/mcu/microchip/samd/asf4/samd51/gcc/system_samd51.c \ + hw/mcu/microchip/samd/asf4/samd51/hpl/gclk/hpl_gclk.c \ + hw/mcu/microchip/samd/asf4/samd51/hpl/mclk/hpl_mclk.c \ + hw/mcu/microchip/samd/asf4/samd51/hpl/osc32kctrl/hpl_osc32kctrl.c \ + hw/mcu/microchip/samd/asf4/samd51/hpl/oscctrl/hpl_oscctrl.c \ + hw/mcu/microchip/samd/asf4/samd51/hal/src/hal_atomic.c + +INC += \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd51/ \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd51/config \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd51/include \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd51/hal/include \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd51/hal/utils/include \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd51/hpl/port \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd51/hri \ + $(TOP)/hw/mcu/microchip/samd/asf4/samd51/CMSIS/Include + +# For TinyUSB port source +VENDOR = microchip +CHIP_FAMILY = samd + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM4F + +# For flash-jlink target +JLINK_DEVICE = ATSAMD51J19 +JLINK_IF = swd + +# flash using jlink +flash: flash-jlink diff --git a/hw/bsp/itsybitsy_m4/itsybitsy_m4.c b/hw/bsp/itsybitsy_m4/itsybitsy_m4.c new file mode 100644 index 000000000..3afe93134 --- /dev/null +++ b/hw/bsp/itsybitsy_m4/itsybitsy_m4.c @@ -0,0 +1,132 @@ +/* + * 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 "sam.h" +#include "bsp/board.h" + +#include "hal/include/hal_gpio.h" +#include "hal/include/hal_init.h" +#include "hpl/gclk/hpl_gclk_base.h" +#include "hpl_mclk_config.h" + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM DECLARATION +//--------------------------------------------------------------------+ +#define LED_PIN 22 +#define BUTTON_PIN 18 // pin D5 + +/* Referenced GCLKs, should be initialized firstly */ +#define _GCLK_INIT_1ST 0xFFFFFFFF + +/* Not referenced GCLKs, initialized last */ +#define _GCLK_INIT_LAST (~_GCLK_INIT_1ST) + +void board_init(void) +{ + // Clock init ( follow hpl_init.c ) + hri_nvmctrl_set_CTRLA_RWS_bf(NVMCTRL, 0); + + _osc32kctrl_init_sources(); + _oscctrl_init_sources(); + _mclk_init(); +#if _GCLK_INIT_1ST + _gclk_init_generators_by_fref(_GCLK_INIT_1ST); +#endif + _oscctrl_init_referenced_generators(); + _gclk_init_generators_by_fref(_GCLK_INIT_LAST); + + // Led init + gpio_set_pin_direction(LED_PIN, GPIO_DIRECTION_OUT); + gpio_set_pin_level(LED_PIN, 0); + + // Button init + gpio_set_pin_direction(BUTTON_PIN, GPIO_DIRECTION_IN); + gpio_set_pin_pull_mode(BUTTON_PIN, GPIO_PULL_UP); + +#if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer (samd SystemCoreClock may not correct) + SysTick_Config(CONF_CPU_FREQUENCY / 1000); +#endif + + /* USB Clock init + * The USB module requires a GCLK_USB of 48 MHz ~ 0.25% clock + * for low speed and full speed operation. */ + hri_gclk_write_PCHCTRL_reg(GCLK, USB_GCLK_ID, GCLK_PCHCTRL_GEN_GCLK1_Val | GCLK_PCHCTRL_CHEN); + hri_mclk_set_AHBMASK_USB_bit(MCLK); + hri_mclk_set_APBBMASK_USB_bit(MCLK); + + // USB Pin Init + gpio_set_pin_direction(PIN_PA24, GPIO_DIRECTION_OUT); + gpio_set_pin_level(PIN_PA24, false); + gpio_set_pin_pull_mode(PIN_PA24, GPIO_PULL_OFF); + gpio_set_pin_direction(PIN_PA25, GPIO_DIRECTION_OUT); + gpio_set_pin_level(PIN_PA25, false); + gpio_set_pin_pull_mode(PIN_PA25, GPIO_PULL_OFF); + + gpio_set_pin_function(PIN_PA24, PINMUX_PA24H_USB_DM); + gpio_set_pin_function(PIN_PA25, PINMUX_PA25H_USB_DP); +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + gpio_set_pin_level(LED_PIN, state); +} + +uint32_t board_button_read(void) +{ + // button is active low + return gpio_get_pin_level(BUTTON_PIN) ? 0 : 1; +} + +int board_uart_read(uint8_t* buf, int len) +{ + (void) buf; (void) len; + return 0; +} + +int board_uart_write(void const * buf, int len) +{ + (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/itsybitsy_m4/samd51g19a_flash.ld b/hw/bsp/itsybitsy_m4/samd51g19a_flash.ld new file mode 100644 index 000000000..cf5db3800 --- /dev/null +++ b/hw/bsp/itsybitsy_m4/samd51g19a_flash.ld @@ -0,0 +1,164 @@ +/** + * \file + * + * \brief Linker script for running in internal FLASH on the SAMD51G19A + * + * Copyright (c) 2017 Microchip Technology Inc. + * + * \asf_license_start + * + * \page License + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 Licence 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. + * + * \asf_license_stop + * + */ + + +OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm") +OUTPUT_ARCH(arm) +SEARCH_DIR(.) + +/* Memory Spaces Definitions */ +MEMORY +{ + rom (rx) : ORIGIN = 0x00000000 + 16K, LENGTH = 0x00080000 - 16K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00030000 + bkupram (rwx) : ORIGIN = 0x47000000, LENGTH = 0x00002000 + qspi (rwx) : ORIGIN = 0x04000000, LENGTH = 0x01000000 +} + +/* 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; + +/* Section Definitions */ +SECTIONS +{ + .text : + { + . = ALIGN(4); + _sfixed = .; + KEEP(*(.vectors .vectors.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + *(.ARM.extab* .gnu.linkonce.armextab.*) + + /* Support C constructors, and C destructors in both user code + and the C library. This also provides support for C++ code. */ + . = ALIGN(4); + KEEP(*(.init)) + . = ALIGN(4); + __preinit_array_start = .; + KEEP (*(.preinit_array)) + __preinit_array_end = .; + + . = ALIGN(4); + __init_array_start = .; + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + __init_array_end = .; + + . = ALIGN(4); + KEEP (*crtbegin.o(.ctors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*crtend.o(.ctors)) + + . = ALIGN(4); + KEEP(*(.fini)) + + . = ALIGN(4); + __fini_array_start = .; + KEEP (*(.fini_array)) + KEEP (*(SORT(.fini_array.*))) + __fini_array_end = .; + + KEEP (*crtbegin.o(.dtors)) + KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*crtend.o(.dtors)) + + . = ALIGN(4); + _efixed = .; /* End of text section */ + } > rom + + /* .ARM.exidx is sorted, so has to go in its own output section. */ + PROVIDE_HIDDEN (__exidx_start = .); + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > rom + PROVIDE_HIDDEN (__exidx_end = .); + + . = ALIGN(4); + _etext = .; + + .relocate : AT (_etext) + { + . = ALIGN(4); + _srelocate = .; + *(.ramfunc .ramfunc.*); + *(.data .data.*); + . = ALIGN(4); + _erelocate = .; + } > ram + + .bkupram (NOLOAD): + { + . = ALIGN(8); + _sbkupram = .; + *(.bkupram .bkupram.*); + . = ALIGN(8); + _ebkupram = .; + } > bkupram + + .qspi (NOLOAD): + { + . = ALIGN(8); + _sqspi = .; + *(.qspi .qspi.*); + . = ALIGN(8); + _eqspi = .; + } > qspi + + /* .bss section which is used for uninitialized data */ + .bss (NOLOAD) : + { + . = ALIGN(4); + _sbss = . ; + _szero = .; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + _ezero = .; + end = .; + } > ram + + /* stack section */ + .stack (NOLOAD): + { + . = ALIGN(8); + _sstack = .; + . = . + STACK_SIZE; + . = ALIGN(8); + _estack = .; + } > ram + + . = ALIGN(4); + _end = . ; +} diff --git a/hw/bsp/lpcxpresso11u37/board.mk b/hw/bsp/lpcxpresso11u37/board.mk index d3121ab95..790516c7d 100644 --- a/hw/bsp/lpcxpresso11u37/board.mk +++ b/hw/bsp/lpcxpresso11u37/board.mk @@ -17,7 +17,7 @@ CFLAGS += -Wno-error=nested-externs -Wno-error=strict-prototypes -Wno-error=unus MCU_DIR = hw/mcu/nxp/lpcopen/lpc11uxx/lpc_chip_11uxx # All source paths should be relative to the top level. -LD_FILE = hw/bsp/lpcxpresso11u37/lpc11u37.ld +LD_FILE = hw/bsp/$(BOARD)/lpc11u37.ld SRC_C += \ $(MCU_DIR)/../gcc/cr_startup_lpc11xx.c \ diff --git a/hw/bsp/lpcxpresso11u68/board.mk b/hw/bsp/lpcxpresso11u68/board.mk index ba84b7d95..d9017ae1a 100644 --- a/hw/bsp/lpcxpresso11u68/board.mk +++ b/hw/bsp/lpcxpresso11u68/board.mk @@ -14,7 +14,7 @@ CFLAGS += \ MCU_DIR = hw/mcu/nxp/lpcopen/lpc11u6x/lpc_chip_11u6x # All source paths should be relative to the top level. -LD_FILE = hw/bsp/lpcxpresso11u68/lpc11u68.ld +LD_FILE = hw/bsp/$(BOARD)/lpc11u68.ld SRC_C += \ $(MCU_DIR)/../gcc/cr_startup_lpc11u6x.c \ diff --git a/hw/bsp/lpcxpresso1347/board.mk b/hw/bsp/lpcxpresso1347/board.mk index 54a83a3b6..6a72a7987 100644 --- a/hw/bsp/lpcxpresso1347/board.mk +++ b/hw/bsp/lpcxpresso1347/board.mk @@ -17,7 +17,7 @@ CFLAGS += -Wno-error=nested-externs -Wno-error=strict-prototypes MCU_DIR = hw/mcu/nxp/lpcopen/lpc13xx/lpc_chip_13xx # All source paths should be relative to the top level. -LD_FILE = hw/bsp/lpcxpresso1347/lpc1347.ld +LD_FILE = hw/bsp/$(BOARD)/lpc1347.ld SRC_C += \ $(MCU_DIR)/../gcc/cr_startup_lpc13xx.c \ diff --git a/hw/bsp/lpcxpresso1769/board.mk b/hw/bsp/lpcxpresso1769/board.mk index b87d6afc9..a345e5a27 100644 --- a/hw/bsp/lpcxpresso1769/board.mk +++ b/hw/bsp/lpcxpresso1769/board.mk @@ -15,7 +15,7 @@ CFLAGS += -Wno-error=strict-prototypes MCU_DIR = hw/mcu/nxp/lpcopen/lpc175x_6x/lpc_chip_175x_6x # All source paths should be relative to the top level. -LD_FILE = hw/bsp/lpcxpresso1769/lpc1769.ld +LD_FILE = hw/bsp/$(BOARD)/lpc1769.ld SRC_C += \ $(MCU_DIR)/../gcc/cr_startup_lpc175x_6x.c \ diff --git a/hw/bsp/mbed1768/board.mk b/hw/bsp/mbed1768/board.mk index 60428bcb4..60beb5e39 100644 --- a/hw/bsp/mbed1768/board.mk +++ b/hw/bsp/mbed1768/board.mk @@ -15,7 +15,7 @@ CFLAGS += -Wno-error=nested-externs -Wno-error=strict-prototypes MCU_DIR = hw/mcu/nxp/lpcopen/lpc175x_6x/lpc_chip_175x_6x # All source paths should be relative to the top level. -LD_FILE = hw/bsp/mbed1768/lpc1768.ld +LD_FILE = hw/bsp/$(BOARD)/lpc1768.ld SRC_C += \ $(MCU_DIR)/../gcc/cr_startup_lpc175x_6x.c \ diff --git a/hw/bsp/mcb1800/board.mk b/hw/bsp/mcb1800/board.mk index b05d4d71a..7806bff46 100644 --- a/hw/bsp/mcb1800/board.mk +++ b/hw/bsp/mcb1800/board.mk @@ -14,7 +14,7 @@ CFLAGS += -Wno-error=unused-parameter -Wno-error=strict-prototypes MCU_DIR = hw/mcu/nxp/lpcopen/lpc18xx/lpc_chip_18xx # All source paths should be relative to the top level. -LD_FILE = hw/bsp/mcb1800/lpc1857.ld +LD_FILE = hw/bsp/$(BOARD)/lpc1857.ld SRC_C += \ $(MCU_DIR)/../gcc/cr_startup_lpc18xx.c \ diff --git a/hw/bsp/metro_m0_express/board.mk b/hw/bsp/metro_m0_express/board.mk index 4d6dedcf8..d762c4eca 100644 --- a/hw/bsp/metro_m0_express/board.mk +++ b/hw/bsp/metro_m0_express/board.mk @@ -9,7 +9,7 @@ CFLAGS += \ -DCFG_TUSB_MCU=OPT_MCU_SAMD21 # All source paths should be relative to the top level. -LD_FILE = hw/bsp/metro_m0_express/samd21g18a_flash.ld +LD_FILE = hw/bsp/$(BOARD)/samd21g18a_flash.ld SRC_C += \ hw/mcu/microchip/samd/asf4/samd21/gcc/gcc/startup_samd21.c \ diff --git a/hw/bsp/metro_m4_express/board.mk b/hw/bsp/metro_m4_express/board.mk index f42aa7703..49c2d7f2f 100644 --- a/hw/bsp/metro_m4_express/board.mk +++ b/hw/bsp/metro_m4_express/board.mk @@ -12,7 +12,7 @@ CFLAGS += \ CFLAGS += -Wno-error=undef # All source paths should be relative to the top level. -LD_FILE = hw/bsp/metro_m4_express/samd51g19a_flash.ld +LD_FILE = hw/bsp/$(BOARD)/samd51g19a_flash.ld SRC_C += \ hw/mcu/microchip/samd/asf4/samd51/gcc/gcc/startup_samd51.c \ diff --git a/hw/bsp/nutiny_nuc121s/board.mk b/hw/bsp/nutiny_nuc121s/board.mk index 893c8500a..e89877820 100644 --- a/hw/bsp/nutiny_nuc121s/board.mk +++ b/hw/bsp/nutiny_nuc121s/board.mk @@ -9,7 +9,7 @@ CFLAGS += \ -DCFG_TUSB_MCU=OPT_MCU_NUC121 # All source paths should be relative to the top level. -LD_FILE = hw/bsp/nutiny_nuc121s/nuc121_flash.ld +LD_FILE = hw/bsp/$(BOARD)/nuc121_flash.ld SRC_C += \ hw/mcu/nuvoton/nuc121_125/Device/Nuvoton/NUC121/Source/system_NUC121.c \ diff --git a/hw/bsp/nutiny_nuc125s/board.mk b/hw/bsp/nutiny_nuc125s/board.mk index e2eecff12..5bba8dee3 100644 --- a/hw/bsp/nutiny_nuc125s/board.mk +++ b/hw/bsp/nutiny_nuc125s/board.mk @@ -9,7 +9,7 @@ CFLAGS += \ -DCFG_TUSB_MCU=OPT_MCU_NUC121 # All source paths should be relative to the top level. -LD_FILE = hw/bsp/nutiny_nuc125s/nuc125_flash.ld +LD_FILE = hw/bsp/$(BOARD)/nuc125_flash.ld SRC_C += \ hw/mcu/nuvoton/nuc121_125/Device/Nuvoton/NUC121/Source/system_NUC121.c \ diff --git a/hw/bsp/nutiny_nuc126v/board.mk b/hw/bsp/nutiny_nuc126v/board.mk index cc88b5529..21f2c9c53 100644 --- a/hw/bsp/nutiny_nuc126v/board.mk +++ b/hw/bsp/nutiny_nuc126v/board.mk @@ -9,7 +9,7 @@ CFLAGS += \ -DCFG_TUSB_MCU=OPT_MCU_NUC126 # All source paths should be relative to the top level. -LD_FILE = hw/bsp/nutiny_nuc126v/nuc126_flash.ld +LD_FILE = hw/bsp/$(BOARD)/nuc126_flash.ld SRC_C += \ hw/mcu/nuvoton/nuc126/Device/Nuvoton/NUC126/Source/system_NUC126.c \ diff --git a/hw/bsp/nutiny_sdk_nuc505/board.mk b/hw/bsp/nutiny_sdk_nuc505/board.mk index 259d11082..68dea63a9 100644 --- a/hw/bsp/nutiny_sdk_nuc505/board.mk +++ b/hw/bsp/nutiny_sdk_nuc505/board.mk @@ -6,7 +6,7 @@ CFLAGS += \ -DCFG_TUSB_MCU=OPT_MCU_NUC505 # All source paths should be relative to the top level. -LD_FILE = hw/bsp/nutiny_sdk_nuc505/nuc505_flashtoram.ld +LD_FILE = hw/bsp/$(BOARD)/nuc505_flashtoram.ld SRC_C += \ hw/mcu/nuvoton/nuc505/Device/Nuvoton/NUC505Series/Source/system_NUC505Series.c \ diff --git a/hw/bsp/pyboardv11/board.mk b/hw/bsp/pyboardv11/board.mk index a0b07f265..9da0541ec 100644 --- a/hw/bsp/pyboardv11/board.mk +++ b/hw/bsp/pyboardv11/board.mk @@ -13,7 +13,7 @@ ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32F4xx_HAL_Driver ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32F4xx # All source paths should be relative to the top level. -LD_FILE = hw/bsp/pyboardv11/STM32F405RGTx_FLASH.ld +LD_FILE = hw/bsp/$(BOARD)/STM32F405RGTx_FLASH.ld SRC_C += \ $(ST_CMSIS)/Source/Templates/system_stm32f4xx.c \