diff --git a/examples/device/board_test/CMakeLists.txt b/examples/device/board_test/CMakeLists.txt index f0437dd04..c09ffe215 100644 --- a/examples/device/board_test/CMakeLists.txt +++ b/examples/device/board_test/CMakeLists.txt @@ -7,7 +7,7 @@ set(TOP "../../..") get_filename_component(TOP "${TOP}" REALPATH) # Add example src and bsp directories -set(EXTRA_COMPONENT_DIRS "src" "${TOP}/hw/bsp/${BOARD}") +set(EXTRA_COMPONENT_DIRS "src" "${TOP}/hw/bsp/esp32s2/boards" "${TOP}/hw/bsp/esp32s2/components") include($ENV{IDF_PATH}/tools/cmake/project.cmake) set(SUPPORTED_TARGETS esp32s2) diff --git a/examples/device/cdc_msc_freertos/CMakeLists.txt b/examples/device/cdc_msc_freertos/CMakeLists.txt index 339f43a09..146b49cb0 100644 --- a/examples/device/cdc_msc_freertos/CMakeLists.txt +++ b/examples/device/cdc_msc_freertos/CMakeLists.txt @@ -7,7 +7,7 @@ set(TOP "../../..") get_filename_component(TOP "${TOP}" REALPATH) # Add example src and bsp directories -set(EXTRA_COMPONENT_DIRS "src" "${TOP}/hw/bsp/${BOARD}") +set(EXTRA_COMPONENT_DIRS "src" "${TOP}/hw/bsp/esp32s2/boards" "${TOP}/hw/bsp/esp32s2/components") include($ENV{IDF_PATH}/tools/cmake/project.cmake) set(SUPPORTED_TARGETS esp32s2) diff --git a/examples/device/hid_composite_freertos/CMakeLists.txt b/examples/device/hid_composite_freertos/CMakeLists.txt index a429a1336..3c48e4e70 100644 --- a/examples/device/hid_composite_freertos/CMakeLists.txt +++ b/examples/device/hid_composite_freertos/CMakeLists.txt @@ -7,7 +7,7 @@ set(TOP "../../..") get_filename_component(TOP "${TOP}" REALPATH) # Add example src and bsp directories -set(EXTRA_COMPONENT_DIRS "src" "${TOP}/hw/bsp/${BOARD}") +set(EXTRA_COMPONENT_DIRS "src" "${TOP}/hw/bsp/esp32s2/boards" "${TOP}/hw/bsp/esp32s2/components") include($ENV{IDF_PATH}/tools/cmake/project.cmake) set(SUPPORTED_TARGETS esp32s2) diff --git a/examples/make.mk b/examples/make.mk index 992a4e60e..bf3b36a62 100644 --- a/examples/make.mk +++ b/examples/make.mk @@ -2,14 +2,8 @@ # Common make definition for all examples # --------------------------------------- -#-------------- 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 +# Build directory +BUILD = _build/build-$(BOARD) # Handy check parameter function check_defined = \ @@ -19,11 +13,37 @@ __check_defined = \ $(if $(value $1),, \ $(error Undefined make flag: $1$(if $2, ($2)))) -# Build directory -BUILD = _build/build-$(BOARD) +#-------------- 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 -# Board specific define -include $(TOP)/hw/bsp/$(BOARD)/board.mk +# Board without family +BOARD_PATH := $(subst $(TOP)/,,$(wildcard $(TOP)/hw/bsp/$(BOARD))) +FAMILY := + +# Board within family +ifeq ($(BOARD_PATH),) + BOARD_PATH := $(subst $(TOP)/,,$(wildcard $(TOP)/hw/bsp/*/boards/$(BOARD))) + FAMILY := $(word 3, $(subst /, ,$(BOARD_PATH))) + FAMILY_PATH = hw/bsp/$(FAMILY) +endif + +ifeq ($(BOARD_PATH),) + $(error Invalid BOARD specified) +endif + +ifeq ($(FAMILY),) + include $(TOP)/hw/bsp/$(BOARD)/board.mk +else + # Include Family and Board specific defs + include $(TOP)/$(FAMILY_PATH)/family.mk + + SRC_C += $(subst $(TOP)/,,$(wildcard $(TOP)/$(FAMILY_PATH)/*.c)) +endif #-------------- Cross Compiler ------------ # Can be set by board, default to ARM GCC @@ -45,9 +65,9 @@ endif #-------------- Source files and compiler flags -------------- -# Include all source C in board folder +# Include all source C in family & board folder SRC_C += hw/bsp/board.c -SRC_C += $(subst $(TOP)/,,$(wildcard $(TOP)/hw/bsp/$(BOARD)/*.c)) +SRC_C += $(subst $(TOP)/,,$(wildcard $(TOP)/$(BOARD_PATH)/*.c)) # Compiler Flags CFLAGS += \ diff --git a/examples/rules.mk b/examples/rules.mk index 2274d1cd2..fb1fe76c2 100644 --- a/examples/rules.mk +++ b/examples/rules.mk @@ -11,12 +11,26 @@ ifeq ($(CROSS_COMPILE),xtensa-esp32s2-elf-) all: idf.py -B$(BUILD) -DBOARD=$(BOARD) build +build: all + clean: idf.py -B$(BUILD) -DBOARD=$(BOARD) clean flash: idf.py -B$(BUILD) -DBOARD=$(BOARD) flash +bootloader-flash: + idf.py -B$(BUILD) -DBOARD=$(BOARD) bootloader-flash + +app-flash: + idf.py -B$(BUILD) -DBOARD=$(BOARD) app-flash + +erase: + idf.py -B$(BUILD) -DBOARD=$(BOARD) erase_flash + +monitor: + idf.py -B$(BUILD) -DBOARD=$(BOARD) monitor + else # GNU Make build system diff --git a/hw/bsp/adafruit_clue/adafruit_clue.c b/hw/bsp/adafruit_clue/adafruit_clue.c deleted file mode 100644 index cb5c2f223..000000000 --- a/hw/bsp/adafruit_clue/adafruit_clue.c +++ /dev/null @@ -1,200 +0,0 @@ -/* - * 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 - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USBD_IRQHandler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// 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 deleted file mode 100644 index 3db045ac0..000000000 --- a/hw/bsp/adafruit_clue/board.mk +++ /dev/null @@ -1,68 +0,0 @@ -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 - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=undef -Wno-error=unused-parameter -Wno-error=cast-align - -# due to tusb_hal_nrf_power_event -GCCVERSION = $(firstword $(subst ., ,$(shell arm-none-eabi-gcc -dumpversion))) -ifeq ($(CMDEXE),1) -ifeq ($(shell if $(GCCVERSION) geq 8 echo 1), 1) -CFLAGS += -Wno-error=cast-function-type -endif -else -ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) -CFLAGS += -Wno-error=cast-function-type -endif -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)/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 - -# 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/arduino_nano33_ble/arduino_nano33_ble.c b/hw/bsp/arduino_nano33_ble/arduino_nano33_ble.c deleted file mode 100644 index d2d126311..000000000 --- a/hw/bsp/arduino_nano33_ble/arduino_nano33_ble.c +++ /dev/null @@ -1,224 +0,0 @@ -/* - * 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 - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USBD_IRQHandler(void) -{ - tud_int_handler(0); -} - -/*------------------------------------------------------------------*/ -/* 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/board.mk b/hw/bsp/arduino_nano33_ble/board.mk deleted file mode 100644 index 1ee8867e6..000000000 --- a/hw/bsp/arduino_nano33_ble/board.mk +++ /dev/null @@ -1,68 +0,0 @@ -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 - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=undef -Wno-error=unused-parameter -Wno-error=cast-align - -# due to tusb_hal_nrf_power_event -GCCVERSION = $(firstword $(subst ., ,$(shell arm-none-eabi-gcc -dumpversion))) -ifeq ($(CMDEXE),1) -ifeq ($(shell if $(GCCVERSION) geq 8 echo 1), 1) -CFLAGS += -Wno-error=cast-function-type -endif -else -ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) -CFLAGS += -Wno-error=cast-function-type -endif -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 - -# 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 diff --git a/hw/bsp/atsamd21_xpro/atsamd21_xpro.c b/hw/bsp/atsamd21_xpro/atsamd21_xpro.c deleted file mode 100644 index 26d3e93bd..000000000 --- a/hw/bsp/atsamd21_xpro/atsamd21_xpro.c +++ /dev/null @@ -1,140 +0,0 @@ -/* - * 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 "sam.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 (32+30) // pin PB30 -#define BUTTON_PIN (0+15) // pin PA15 - -/* 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, 1); - - // 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); -} - -//--------------------------------------------------------------------+ -// 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 - -//void asf_assert(const bool condition, const char *const file, const int line) {} - -void USB_Handler(void) -{ - tud_int_handler(0); -} diff --git a/hw/bsp/atsamd21_xpro/board.mk b/hw/bsp/atsamd21_xpro/board.mk deleted file mode 100644 index 733457f6a..000000000 --- a/hw/bsp/atsamd21_xpro/board.mk +++ /dev/null @@ -1,45 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs-linux \ - -mcpu=cortex-m0plus \ - -nostdlib -nostartfiles \ - -D__SAMD21J18A__ \ - -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/atsamd21_xpro/samd21j18a_flash.ld - -SRC_C += \ - hw/mcu/microchip/asf4/samd21/gcc/gcc/startup_samd21.c \ - hw/mcu/microchip/asf4/samd21/gcc/system_samd21.c \ - hw/mcu/microchip/asf4/samd21/hpl/gclk/hpl_gclk.c \ - hw/mcu/microchip/asf4/samd21/hpl/pm/hpl_pm.c \ - hw/mcu/microchip/asf4/samd21/hpl/sysctrl/hpl_sysctrl.c \ - hw/mcu/microchip/asf4/samd21/hal/src/hal_atomic.c - -INC += \ - $(TOP)/hw/mcu/microchip/asf4/samd21/ \ - $(TOP)/hw/mcu/microchip/asf4/samd21/config \ - $(TOP)/hw/mcu/microchip/asf4/samd21/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hal/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hal/utils/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hpl/pm/ \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hpl/port \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hri \ - $(TOP)/hw/mcu/microchip/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 = ATSAMD21J18 -JLINK_IF = swd - -# flash using jlink -flash: flash-jlink diff --git a/hw/bsp/circuitplayground_bluefruit/board.mk b/hw/bsp/circuitplayground_bluefruit/board.mk deleted file mode 100644 index 3db045ac0..000000000 --- a/hw/bsp/circuitplayground_bluefruit/board.mk +++ /dev/null @@ -1,68 +0,0 @@ -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 - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=undef -Wno-error=unused-parameter -Wno-error=cast-align - -# due to tusb_hal_nrf_power_event -GCCVERSION = $(firstword $(subst ., ,$(shell arm-none-eabi-gcc -dumpversion))) -ifeq ($(CMDEXE),1) -ifeq ($(shell if $(GCCVERSION) geq 8 echo 1), 1) -CFLAGS += -Wno-error=cast-function-type -endif -else -ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) -CFLAGS += -Wno-error=cast-function-type -endif -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)/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 - -# 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/circuitplayground_bluefruit/circuitplayground_bluefruit.c b/hw/bsp/circuitplayground_bluefruit/circuitplayground_bluefruit.c deleted file mode 100644 index 9638b3cc8..000000000 --- a/hw/bsp/circuitplayground_bluefruit/circuitplayground_bluefruit.c +++ /dev/null @@ -1,200 +0,0 @@ -/* - * 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 - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USBD_IRQHandler(void) -{ - tud_int_handler(0); -} - -/*------------------------------------------------------------------*/ -/* MACRO TYPEDEF CONSTANT ENUM - *------------------------------------------------------------------*/ -#define _PINNUM(port, pin) ((port)*32 + (pin)) - -#define LED_PIN _PINNUM(1, 14) -#define LED_STATE_ON 1 - -#define BUTTON_PIN _PINNUM(1, 15) - -// 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_PULLDOWN); - -#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 HIGH - return nrf_gpio_pin_read(BUTTON_PIN); -} - -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/circuitplayground_express/board.mk b/hw/bsp/circuitplayground_express/board.mk deleted file mode 100644 index 2a36b8335..000000000 --- a/hw/bsp/circuitplayground_express/board.mk +++ /dev/null @@ -1,44 +0,0 @@ -CFLAGS += \ - -DCONF_DFLL_OVERWRITE_CALIBRATION=0 \ - -D__SAMD21G18A__ \ - -mthumb \ - -mabi=aapcs-linux \ - -mcpu=cortex-m0plus \ - -nostdlib -nostartfiles \ - -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/asf4/samd21/gcc/gcc/startup_samd21.c \ - hw/mcu/microchip/asf4/samd21/gcc/system_samd21.c \ - hw/mcu/microchip/asf4/samd21/hpl/gclk/hpl_gclk.c \ - hw/mcu/microchip/asf4/samd21/hpl/pm/hpl_pm.c \ - hw/mcu/microchip/asf4/samd21/hpl/sysctrl/hpl_sysctrl.c \ - hw/mcu/microchip/asf4/samd21/hal/src/hal_atomic.c - -INC += \ - $(TOP)/hw/mcu/microchip/asf4/samd21/ \ - $(TOP)/hw/mcu/microchip/asf4/samd21/config \ - $(TOP)/hw/mcu/microchip/asf4/samd21/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hal/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hal/utils/include \ - $(TOP)/hw/mcu/microchip/asf4/samd51/hpl/pm/ \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hpl/port \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hri \ - $(TOP)/hw/mcu/microchip/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 - -# flash using jlink -flash: $(BUILD)/$(BOARD)-firmware.uf2 - cp $< /media/$(USER)/CPLAYBOOT/ diff --git a/hw/bsp/circuitplayground_express/circuitplayground_express.c b/hw/bsp/circuitplayground_express/circuitplayground_express.c deleted file mode 100644 index 4ff95b2ff..000000000 --- a/hw/bsp/circuitplayground_express/circuitplayground_express.c +++ /dev/null @@ -1,157 +0,0 @@ -/* - * 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" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USB_Handler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM DECLARATION -//--------------------------------------------------------------------+ -#define LED_PIN 17 -#define BUTTON_PIN 14 // pin D5 - -/* 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); - - // Update SystemCoreClock since it is hard coded with asf4 and not correct - // Init 1ms tick timer (samd SystemCoreClock may not correct) - SystemCoreClock = CONF_CPU_FREQUENCY; - SysTick_Config(CONF_CPU_FREQUENCY / 1000); - - // 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_DOWN); - -#if CFG_TUSB_OS == OPT_OS_FREERTOS - // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) - NVIC_SetPriority(USB_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); -#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 high - return gpio_get_pin_level(BUTTON_PIN); -} - -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/esp32s2_saola_1/CMakeLists.txt b/hw/bsp/esp32s2/boards/CMakeLists.txt similarity index 67% rename from hw/bsp/esp32s2_saola_1/CMakeLists.txt rename to hw/bsp/esp32s2/boards/CMakeLists.txt index 629b3104a..98c929ef3 100644 --- a/hw/bsp/esp32s2_saola_1/CMakeLists.txt +++ b/hw/bsp/esp32s2/boards/CMakeLists.txt @@ -1,7 +1,7 @@ -idf_component_register(SRCS "${BOARD}.c" "led_strip/src/led_strip_rmt_ws2812.c" - INCLUDE_DIRS "led_strip/include" +idf_component_register(SRCS esp32s2.c + INCLUDE_DIRS "." "${BOARD}" PRIV_REQUIRES "driver" - REQUIRES freertos src) + REQUIRES freertos src led_strip) target_compile_options(${COMPONENT_TARGET} PUBLIC "-DCFG_TUSB_MCU=OPT_MCU_ESP32S2" diff --git a/hw/bsp/esp32s2_kaluga_1/esp32s2_kaluga_1.c b/hw/bsp/esp32s2/boards/esp32s2.c similarity index 94% rename from hw/bsp/esp32s2_kaluga_1/esp32s2_kaluga_1.c rename to hw/bsp/esp32s2/boards/esp32s2.c index 47f9c2d47..abed39e49 100644 --- a/hw/bsp/esp32s2_kaluga_1/esp32s2_kaluga_1.c +++ b/hw/bsp/esp32s2/boards/esp32s2.c @@ -24,23 +24,22 @@ * This file is part of the TinyUSB stack. */ -#include "../board.h" +#include "../../board.h" +#include "board.h" + #include "esp_rom_gpio.h" #include "hal/gpio_ll.h" #include "hal/usb_hal.h" #include "soc/usb_periph.h" + #include "driver/periph_ctrl.h" #include "driver/rmt.h" -#include "led_strip/include/led_strip.h" +#include "led_strip.h" //--------------------------------------------------------------------+ // MACRO TYPEDEF CONSTANT ENUM DECLARATION //--------------------------------------------------------------------+ -#define LED_PIN 45 -#define BUTTON_PIN 0 -#define BUTTON_STATE_ACTIVE 0 - static void configure_pins(usb_hal_context_t *usb); static led_strip_t *strip; @@ -48,7 +47,7 @@ static led_strip_t *strip; void board_init(void) { // WS2812 Neopixel driver with RMT peripheral - rmt_config_t config = RMT_DEFAULT_CONFIG_TX(LED_PIN, RMT_CHANNEL_0); + rmt_config_t config = RMT_DEFAULT_CONFIG_TX(NEOPIXEL_PIN, RMT_CHANNEL_0); config.clk_div = 2; // set counter clock to 40MHz rmt_config(&config); diff --git a/hw/bsp/teensy_40/board.h b/hw/bsp/esp32s2/boards/esp32s2_kaluga_1/board.h similarity index 82% rename from hw/bsp/teensy_40/board.h rename to hw/bsp/esp32s2/boards/esp32s2_kaluga_1/board.h index c5338e274..6bb44f76d 100644 --- a/hw/bsp/teensy_40/board.h +++ b/hw/bsp/esp32s2/boards/esp32s2_kaluga_1/board.h @@ -1,7 +1,7 @@ /* * The MIT License (MIT) * - * Copyright (c) 2019, Ha Thach (tinyusb.org) + * Copyright (c) 2020, 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 @@ -24,13 +24,21 @@ * This file is part of the TinyUSB stack. */ - #ifndef BOARD_H_ #define BOARD_H_ +#ifdef __cplusplus + extern "C" { +#endif -// required since iMX RT10xx SDK include this file for board size -#define BOARD_FLASH_SIZE (2 * 1024 * 1024) +// Note: need to insert jumper next to WS2812 pixel +#define NEOPIXEL_PIN 45 +#define BUTTON_PIN 0 +#define BUTTON_STATE_ACTIVE 0 + +#ifdef __cplusplus + } +#endif #endif /* BOARD_H_ */ diff --git a/hw/bsp/esp32s2/boards/esp32s2_saola_1/board.h b/hw/bsp/esp32s2/boards/esp32s2_saola_1/board.h new file mode 100644 index 000000000..f450b9a8b --- /dev/null +++ b/hw/bsp/esp32s2/boards/esp32s2_saola_1/board.h @@ -0,0 +1,45 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// Note: On the production version (v1.2) WS2812 is connected to GPIO 18, +// however earlier revision v1.1 WS2812 is connected to GPIO 17 +#define NEOPIXEL_PIN 18 + +#define BUTTON_PIN 0 +#define BUTTON_STATE_ACTIVE 0 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/esp32s2/components/led_strip/CMakeLists.txt b/hw/bsp/esp32s2/components/led_strip/CMakeLists.txt new file mode 100644 index 000000000..6d0fcbc86 --- /dev/null +++ b/hw/bsp/esp32s2/components/led_strip/CMakeLists.txt @@ -0,0 +1,8 @@ +set(component_srcs "src/led_strip_rmt_ws2812.c") + +idf_component_register(SRCS "${component_srcs}" + INCLUDE_DIRS "include" + PRIV_INCLUDE_DIRS "" + PRIV_REQUIRES "driver" + REQUIRES "") + diff --git a/hw/bsp/esp32s2_kaluga_1/led_strip/include/led_strip.h b/hw/bsp/esp32s2/components/led_strip/include/led_strip.h similarity index 100% rename from hw/bsp/esp32s2_kaluga_1/led_strip/include/led_strip.h rename to hw/bsp/esp32s2/components/led_strip/include/led_strip.h diff --git a/hw/bsp/esp32s2_kaluga_1/led_strip/src/led_strip_rmt_ws2812.c b/hw/bsp/esp32s2/components/led_strip/src/led_strip_rmt_ws2812.c similarity index 100% rename from hw/bsp/esp32s2_kaluga_1/led_strip/src/led_strip_rmt_ws2812.c rename to hw/bsp/esp32s2/components/led_strip/src/led_strip_rmt_ws2812.c diff --git a/hw/bsp/esp32s2_kaluga_1/board.mk b/hw/bsp/esp32s2/family.mk similarity index 100% rename from hw/bsp/esp32s2_kaluga_1/board.mk rename to hw/bsp/esp32s2/family.mk diff --git a/hw/bsp/esp32s2_kaluga_1/CMakeLists.txt b/hw/bsp/esp32s2_kaluga_1/CMakeLists.txt deleted file mode 100644 index 1627f39a3..000000000 --- a/hw/bsp/esp32s2_kaluga_1/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -idf_component_register(SRCS "${BOARD}.c" "led_strip/src/led_strip_rmt_ws2812.c" - INCLUDE_DIRS "led_strip/include" - PRIV_REQUIRES "driver" - REQUIRES freertos src) - -target_compile_options(${COMPONENT_TARGET} PUBLIC - "-DCFG_TUSB_MCU=OPT_MCU_ESP32S2" - "-DCFG_TUSB_OS=OPT_OS_FREERTOS" -) - -idf_component_get_property( FREERTOS_ORIG_INCLUDE_PATH freertos ORIG_INCLUDE_PATH) -target_include_directories(${COMPONENT_TARGET} PUBLIC - "${FREERTOS_ORIG_INCLUDE_PATH}" - "${TOP}/hw" - "${TOP}/src" -) diff --git a/hw/bsp/esp32s2_saola_1/board.mk b/hw/bsp/esp32s2_saola_1/board.mk deleted file mode 100644 index 167ef6226..000000000 --- a/hw/bsp/esp32s2_saola_1/board.mk +++ /dev/null @@ -1,2 +0,0 @@ -# Cross Compiler for ESP32 -CROSS_COMPILE = xtensa-esp32s2-elf- diff --git a/hw/bsp/esp32s2_saola_1/esp32s2_saola_1.c b/hw/bsp/esp32s2_saola_1/esp32s2_saola_1.c deleted file mode 100644 index 5795c4b68..000000000 --- a/hw/bsp/esp32s2_saola_1/esp32s2_saola_1.c +++ /dev/null @@ -1,134 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2020, 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 "../board.h" -#include "esp_rom_gpio.h" -#include "hal/gpio_ll.h" -#include "hal/usb_hal.h" -#include "soc/usb_periph.h" - -#include "driver/periph_ctrl.h" -#include "driver/rmt.h" -#include "led_strip/include/led_strip.h" - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM DECLARATION -//--------------------------------------------------------------------+ - -// Note: On the production version (v1.2) WS2812 is connected to GPIO 18, -// however earlier revision v1.1 WS2812 is connected to GPIO 17 -//#define LED_PIN 17 // v1.1 -#define LED_PIN 18 // v1.2 and later -#define BUTTON_PIN 0 -#define BUTTON_STATE_ACTIVE 0 - -static void configure_pins(usb_hal_context_t *usb); -static led_strip_t *strip; - -// Initialize on-board peripherals : led, button, uart and USB -void board_init(void) -{ - // WS2812 Neopixel driver with RMT peripheral - rmt_config_t config = RMT_DEFAULT_CONFIG_TX(LED_PIN, RMT_CHANNEL_0); - config.clk_div = 2; // set counter clock to 40MHz - - rmt_config(&config); - rmt_driver_install(config.channel, 0, 0); - - led_strip_config_t strip_config = LED_STRIP_DEFAULT_CONFIG(1, (led_strip_dev_t) config.channel); - strip = led_strip_new_rmt_ws2812(&strip_config); - strip->clear(strip, 100); // off led - - // Button - gpio_pad_select_gpio(BUTTON_PIN); - gpio_set_direction(BUTTON_PIN, GPIO_MODE_INPUT); - gpio_set_pull_mode(BUTTON_PIN, BUTTON_STATE_ACTIVE ? GPIO_PULLDOWN_ONLY : GPIO_PULLUP_ONLY); - - // USB Controller Hal init - periph_module_reset(PERIPH_USB_MODULE); - periph_module_enable(PERIPH_USB_MODULE); - - usb_hal_context_t hal = { - .use_external_phy = false // use built-in PHY - }; - usb_hal_init(&hal); - configure_pins(&hal); -} - -static void configure_pins(usb_hal_context_t *usb) -{ - /* usb_periph_iopins currently configures USB_OTG as USB Device. - * Introduce additional parameters in usb_hal_context_t when adding support - * for USB Host. - */ - for (const usb_iopin_dsc_t *iopin = usb_periph_iopins; iopin->pin != -1; ++iopin) { - if ((usb->use_external_phy) || (iopin->ext_phy_only == 0)) { - esp_rom_gpio_pad_select_gpio(iopin->pin); - if (iopin->is_output) { - esp_rom_gpio_connect_out_signal(iopin->pin, iopin->func, false, false); - } else { - esp_rom_gpio_connect_in_signal(iopin->pin, iopin->func, false); - if ((iopin->pin != GPIO_FUNC_IN_LOW) && (iopin->pin != GPIO_FUNC_IN_HIGH)) { - gpio_ll_input_enable(&GPIO, iopin->pin); - } - } - esp_rom_gpio_pad_unhold(iopin->pin); - } - } - if (!usb->use_external_phy) { - gpio_set_drive_capability(USBPHY_DM_NUM, GPIO_DRIVE_CAP_3); - gpio_set_drive_capability(USBPHY_DP_NUM, GPIO_DRIVE_CAP_3); - } -} - -// Turn LED on or off -void board_led_write(bool state) -{ - strip->set_pixel(strip, 0, (state ? 0x88 : 0x00), 0x00, 0x00); - strip->refresh(strip, 100); -} - -// Get the current state of button -// a '1' means active (pressed), a '0' means inactive. -uint32_t board_button_read(void) -{ - return gpio_get_level(BUTTON_PIN) == BUTTON_STATE_ACTIVE; -} - -// Get characters from UART -int board_uart_read(uint8_t* buf, int len) -{ - (void) buf; (void) len; - return 0; -} - -// Send characters to UART -int board_uart_write(void const * buf, int len) -{ - (void) buf; (void) len; - return 0; -} - diff --git a/hw/bsp/esp32s2_saola_1/led_strip/include/led_strip.h b/hw/bsp/esp32s2_saola_1/led_strip/include/led_strip.h deleted file mode 100644 index a9dffc325..000000000 --- a/hw/bsp/esp32s2_saola_1/led_strip/include/led_strip.h +++ /dev/null @@ -1,126 +0,0 @@ -// Copyright 2019 Espressif Systems (Shanghai) PTE LTD -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -#pragma once - -#ifdef __cplusplus -extern "C" { -#endif - -#include "esp_err.h" - -/** -* @brief LED Strip Type -* -*/ -typedef struct led_strip_s led_strip_t; - -/** -* @brief LED Strip Device Type -* -*/ -typedef void *led_strip_dev_t; - -/** -* @brief Declare of LED Strip Type -* -*/ -struct led_strip_s { - /** - * @brief Set RGB for a specific pixel - * - * @param strip: LED strip - * @param index: index of pixel to set - * @param red: red part of color - * @param green: green part of color - * @param blue: blue part of color - * - * @return - * - ESP_OK: Set RGB for a specific pixel successfully - * - ESP_ERR_INVALID_ARG: Set RGB for a specific pixel failed because of invalid parameters - * - ESP_FAIL: Set RGB for a specific pixel failed because other error occurred - */ - esp_err_t (*set_pixel)(led_strip_t *strip, uint32_t index, uint32_t red, uint32_t green, uint32_t blue); - - /** - * @brief Refresh memory colors to LEDs - * - * @param strip: LED strip - * @param timeout_ms: timeout value for refreshing task - * - * @return - * - ESP_OK: Refresh successfully - * - ESP_ERR_TIMEOUT: Refresh failed because of timeout - * - ESP_FAIL: Refresh failed because some other error occurred - * - * @note: - * After updating the LED colors in the memory, a following invocation of this API is needed to flush colors to strip. - */ - esp_err_t (*refresh)(led_strip_t *strip, uint32_t timeout_ms); - - /** - * @brief Clear LED strip (turn off all LEDs) - * - * @param strip: LED strip - * @param timeout_ms: timeout value for clearing task - * - * @return - * - ESP_OK: Clear LEDs successfully - * - ESP_ERR_TIMEOUT: Clear LEDs failed because of timeout - * - ESP_FAIL: Clear LEDs failed because some other error occurred - */ - esp_err_t (*clear)(led_strip_t *strip, uint32_t timeout_ms); - - /** - * @brief Free LED strip resources - * - * @param strip: LED strip - * - * @return - * - ESP_OK: Free resources successfully - * - ESP_FAIL: Free resources failed because error occurred - */ - esp_err_t (*del)(led_strip_t *strip); -}; - -/** -* @brief LED Strip Configuration Type -* -*/ -typedef struct { - uint32_t max_leds; /*!< Maximum LEDs in a single strip */ - led_strip_dev_t dev; /*!< LED strip device (e.g. RMT channel, PWM channel, etc) */ -} led_strip_config_t; - -/** - * @brief Default configuration for LED strip - * - */ -#define LED_STRIP_DEFAULT_CONFIG(number, dev_hdl) \ - { \ - .max_leds = number, \ - .dev = dev_hdl, \ - } - -/** -* @brief Install a new ws2812 driver (based on RMT peripheral) -* -* @param config: LED strip configuration -* @return -* LED strip instance or NULL -*/ -led_strip_t *led_strip_new_rmt_ws2812(const led_strip_config_t *config); - -#ifdef __cplusplus -} -#endif diff --git a/hw/bsp/esp32s2_saola_1/led_strip/src/led_strip_rmt_ws2812.c b/hw/bsp/esp32s2_saola_1/led_strip/src/led_strip_rmt_ws2812.c deleted file mode 100644 index 025d3c590..000000000 --- a/hw/bsp/esp32s2_saola_1/led_strip/src/led_strip_rmt_ws2812.c +++ /dev/null @@ -1,171 +0,0 @@ -// Copyright 2019 Espressif Systems (Shanghai) PTE LTD -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -#include -#include -#include -#include "esp_log.h" -#include "esp_attr.h" -#include "led_strip.h" -#include "driver/rmt.h" - -static const char *TAG = "ws2812"; -#define STRIP_CHECK(a, str, goto_tag, ret_value, ...) \ - do \ - { \ - if (!(a)) \ - { \ - ESP_LOGE(TAG, "%s(%d): " str, __FUNCTION__, __LINE__, ##__VA_ARGS__); \ - ret = ret_value; \ - goto goto_tag; \ - } \ - } while (0) - -#define WS2812_T0H_NS (350) -#define WS2812_T0L_NS (1000) -#define WS2812_T1H_NS (1000) -#define WS2812_T1L_NS (350) -#define WS2812_RESET_US (280) - -static uint32_t ws2812_t0h_ticks = 0; -static uint32_t ws2812_t1h_ticks = 0; -static uint32_t ws2812_t0l_ticks = 0; -static uint32_t ws2812_t1l_ticks = 0; - -typedef struct { - led_strip_t parent; - rmt_channel_t rmt_channel; - uint32_t strip_len; - uint8_t buffer[0]; -} ws2812_t; - -/** - * @brief Conver RGB data to RMT format. - * - * @note For WS2812, R,G,B each contains 256 different choices (i.e. uint8_t) - * - * @param[in] src: source data, to converted to RMT format - * @param[in] dest: place where to store the convert result - * @param[in] src_size: size of source data - * @param[in] wanted_num: number of RMT items that want to get - * @param[out] translated_size: number of source data that got converted - * @param[out] item_num: number of RMT items which are converted from source data - */ -static void IRAM_ATTR ws2812_rmt_adapter(const void *src, rmt_item32_t *dest, size_t src_size, - size_t wanted_num, size_t *translated_size, size_t *item_num) -{ - if (src == NULL || dest == NULL) { - *translated_size = 0; - *item_num = 0; - return; - } - const rmt_item32_t bit0 = {{{ ws2812_t0h_ticks, 1, ws2812_t0l_ticks, 0 }}}; //Logical 0 - const rmt_item32_t bit1 = {{{ ws2812_t1h_ticks, 1, ws2812_t1l_ticks, 0 }}}; //Logical 1 - size_t size = 0; - size_t num = 0; - uint8_t *psrc = (uint8_t *)src; - rmt_item32_t *pdest = dest; - while (size < src_size && num < wanted_num) { - for (int i = 0; i < 8; i++) { - // MSB first - if (*psrc & (1 << (7 - i))) { - pdest->val = bit1.val; - } else { - pdest->val = bit0.val; - } - num++; - pdest++; - } - size++; - psrc++; - } - *translated_size = size; - *item_num = num; -} - -static esp_err_t ws2812_set_pixel(led_strip_t *strip, uint32_t index, uint32_t red, uint32_t green, uint32_t blue) -{ - esp_err_t ret = ESP_OK; - ws2812_t *ws2812 = __containerof(strip, ws2812_t, parent); - STRIP_CHECK(index < ws2812->strip_len, "index out of the maximum number of leds", err, ESP_ERR_INVALID_ARG); - uint32_t start = index * 3; - // In thr order of GRB - ws2812->buffer[start + 0] = green & 0xFF; - ws2812->buffer[start + 1] = red & 0xFF; - ws2812->buffer[start + 2] = blue & 0xFF; - return ESP_OK; -err: - return ret; -} - -static esp_err_t ws2812_refresh(led_strip_t *strip, uint32_t timeout_ms) -{ - esp_err_t ret = ESP_OK; - ws2812_t *ws2812 = __containerof(strip, ws2812_t, parent); - STRIP_CHECK(rmt_write_sample(ws2812->rmt_channel, ws2812->buffer, ws2812->strip_len * 3, true) == ESP_OK, - "transmit RMT samples failed", err, ESP_FAIL); - return rmt_wait_tx_done(ws2812->rmt_channel, pdMS_TO_TICKS(timeout_ms)); -err: - return ret; -} - -static esp_err_t ws2812_clear(led_strip_t *strip, uint32_t timeout_ms) -{ - ws2812_t *ws2812 = __containerof(strip, ws2812_t, parent); - // Write zero to turn off all leds - memset(ws2812->buffer, 0, ws2812->strip_len * 3); - return ws2812_refresh(strip, timeout_ms); -} - -static esp_err_t ws2812_del(led_strip_t *strip) -{ - ws2812_t *ws2812 = __containerof(strip, ws2812_t, parent); - free(ws2812); - return ESP_OK; -} - -led_strip_t *led_strip_new_rmt_ws2812(const led_strip_config_t *config) -{ - led_strip_t *ret = NULL; - STRIP_CHECK(config, "configuration can't be null", err, NULL); - - // 24 bits per led - uint32_t ws2812_size = sizeof(ws2812_t) + config->max_leds * 3; - ws2812_t *ws2812 = calloc(1, ws2812_size); - STRIP_CHECK(ws2812, "request memory for ws2812 failed", err, NULL); - - uint32_t counter_clk_hz = 0; - STRIP_CHECK(rmt_get_counter_clock((rmt_channel_t)config->dev, &counter_clk_hz) == ESP_OK, - "get rmt counter clock failed", err, NULL); - // ns -> ticks - float ratio = (float)counter_clk_hz / 1e9; - ws2812_t0h_ticks = (uint32_t)(ratio * WS2812_T0H_NS); - ws2812_t0l_ticks = (uint32_t)(ratio * WS2812_T0L_NS); - ws2812_t1h_ticks = (uint32_t)(ratio * WS2812_T1H_NS); - ws2812_t1l_ticks = (uint32_t)(ratio * WS2812_T1L_NS); - - // set ws2812 to rmt adapter - rmt_translator_init((rmt_channel_t)config->dev, ws2812_rmt_adapter); - - ws2812->rmt_channel = (rmt_channel_t)config->dev; - ws2812->strip_len = config->max_leds; - - ws2812->parent.set_pixel = ws2812_set_pixel; - ws2812->parent.refresh = ws2812_refresh; - ws2812->parent.clear = ws2812_clear; - ws2812->parent.del = ws2812_del; - - return &ws2812->parent; -err: - return ret; -} diff --git a/hw/bsp/feather_m0_express/board.mk b/hw/bsp/feather_m0_express/board.mk deleted file mode 100644 index 61dc7c665..000000000 --- a/hw/bsp/feather_m0_express/board.mk +++ /dev/null @@ -1,50 +0,0 @@ -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/asf4/samd21/gcc/gcc/startup_samd21.c \ - hw/mcu/microchip/asf4/samd21/gcc/system_samd21.c \ - hw/mcu/microchip/asf4/samd21/hpl/gclk/hpl_gclk.c \ - hw/mcu/microchip/asf4/samd21/hpl/pm/hpl_pm.c \ - hw/mcu/microchip/asf4/samd21/hpl/sysctrl/hpl_sysctrl.c \ - hw/mcu/microchip/asf4/samd21/hal/src/hal_atomic.c - -INC += \ - $(TOP)/hw/mcu/microchip/asf4/samd21/ \ - $(TOP)/hw/mcu/microchip/asf4/samd21/config \ - $(TOP)/hw/mcu/microchip/asf4/samd21/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hal/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hal/utils/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hpl/pm/ \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hpl/port \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hri \ - $(TOP)/hw/mcu/microchip/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 - -# flash using bossac at least version 1.8 -# 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 --offset=0x2000 -e -w $^ -R diff --git a/hw/bsp/feather_m0_express/feather_m0_express.c b/hw/bsp/feather_m0_express/feather_m0_express.c deleted file mode 100644 index 4eb157c8f..000000000 --- a/hw/bsp/feather_m0_express/feather_m0_express.c +++ /dev/null @@ -1,155 +0,0 @@ -/* - * 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" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USB_Handler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM DECLARATION -//--------------------------------------------------------------------+ -#define LED_PIN 17 -#define BUTTON_PIN 15 // pin D5 - -/* 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); - - // Update SystemCoreClock since it is hard coded with asf4 and not correct - // Init 1ms tick timer (samd SystemCoreClock may not correct) - SystemCoreClock = CONF_CPU_FREQUENCY; - SysTick_Config(CONF_CPU_FREQUENCY / 1000); - - // 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_FREERTOS - // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) - NVIC_SetPriority(USB_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); -#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/feather_m4_express/board.mk b/hw/bsp/feather_m4_express/board.mk deleted file mode 100644 index 6cc6a9091..000000000 --- a/hw/bsp/feather_m4_express/board.mk +++ /dev/null @@ -1,53 +0,0 @@ -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/asf4/samd51/gcc/gcc/startup_samd51.c \ - hw/mcu/microchip/asf4/samd51/gcc/system_samd51.c \ - hw/mcu/microchip/asf4/samd51/hpl/gclk/hpl_gclk.c \ - hw/mcu/microchip/asf4/samd51/hpl/mclk/hpl_mclk.c \ - hw/mcu/microchip/asf4/samd51/hpl/osc32kctrl/hpl_osc32kctrl.c \ - hw/mcu/microchip/asf4/samd51/hpl/oscctrl/hpl_oscctrl.c \ - hw/mcu/microchip/asf4/samd51/hal/src/hal_atomic.c - -INC += \ - $(TOP)/hw/mcu/microchip/asf4/samd51/ \ - $(TOP)/hw/mcu/microchip/asf4/samd51/config \ - $(TOP)/hw/mcu/microchip/asf4/samd51/include \ - $(TOP)/hw/mcu/microchip/asf4/samd51/hal/include \ - $(TOP)/hw/mcu/microchip/asf4/samd51/hal/utils/include \ - $(TOP)/hw/mcu/microchip/asf4/samd51/hpl/port \ - $(TOP)/hw/mcu/microchip/asf4/samd51/hri \ - $(TOP)/hw/mcu/microchip/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 - -# flash using bossac at least version 1.8 -# 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 --offset=0x4000 -e -w $^ -R diff --git a/hw/bsp/feather_nrf52840_express/feather_nrf52840_express.c b/hw/bsp/feather_nrf52840_express/feather_nrf52840_express.c deleted file mode 100644 index 34e7fa8ec..000000000 --- a/hw/bsp/feather_nrf52840_express/feather_nrf52840_express.c +++ /dev/null @@ -1,225 +0,0 @@ -/* - * 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 - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USBD_IRQHandler(void) -{ - tud_int_handler(0); -} - -/*------------------------------------------------------------------*/ -/* MACRO TYPEDEF CONSTANT ENUM - *------------------------------------------------------------------*/ -#define _PINNUM(port, pin) ((port)*32 + (pin)) - -#define LED_PIN _PINNUM(1, 15) -#define LED_STATE_ON 1 - -#define BUTTON_PIN _PINNUM(1, 02) - -#define UART_RX_PIN 24 -#define UART_TX_PIN 25 - -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); - - //------------- USB -------------// -#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/feather_nrf52840_sense/board.mk b/hw/bsp/feather_nrf52840_sense/board.mk deleted file mode 100644 index 3db045ac0..000000000 --- a/hw/bsp/feather_nrf52840_sense/board.mk +++ /dev/null @@ -1,68 +0,0 @@ -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 - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=undef -Wno-error=unused-parameter -Wno-error=cast-align - -# due to tusb_hal_nrf_power_event -GCCVERSION = $(firstword $(subst ., ,$(shell arm-none-eabi-gcc -dumpversion))) -ifeq ($(CMDEXE),1) -ifeq ($(shell if $(GCCVERSION) geq 8 echo 1), 1) -CFLAGS += -Wno-error=cast-function-type -endif -else -ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) -CFLAGS += -Wno-error=cast-function-type -endif -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)/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 - -# 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 deleted file mode 100644 index 284ae27b1..000000000 --- a/hw/bsp/feather_nrf52840_sense/feather_nrf52840_sense.c +++ /dev/null @@ -1,197 +0,0 @@ -/* - * 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 - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USBD_IRQHandler(void) -{ - tud_int_handler(0); -} - -/*------------------------------------------------------------------*/ -/* 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); - - // 1ms tick timer - SysTick_Config(SystemCoreClock/1000); - -#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_stm32f405/board.mk b/hw/bsp/feather_stm32f405/board.mk deleted file mode 100644 index 3a2134875..000000000 --- a/hw/bsp/feather_stm32f405/board.mk +++ /dev/null @@ -1,54 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m4 \ - -mfloat-abi=hard \ - -mfpu=fpv4-sp-d16 \ - -nostdlib -nostartfiles \ - -DSTM32F405xx \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F4 - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=cast-align - -ST_FAMILY = f4 -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F405RGTx_FLASH.ld - -SRC_C += \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f405xx.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For TinyUSB port source -VENDOR = st -CHIP_FAMILY = synopsys - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM4F - -# For flash-jlink target -JLINK_DEVICE = stm32f405rg - -# Path to STM32 Cube Programmer CLI, should be added into system path -STM32Prog = STM32_Programmer_CLI - -# flash target ROM bootloader -flash: $(BUILD)/$(BOARD)-firmware.bin - dfu-util -R -a 0 --dfuse-address 0x08000000 -D $< diff --git a/hw/bsp/feather_stm32f405/feather_stm32f405.c b/hw/bsp/feather_stm32f405/feather_stm32f405.c deleted file mode 100644 index a8c782da5..000000000 --- a/hw/bsp/feather_stm32f405/feather_stm32f405.c +++ /dev/null @@ -1,249 +0,0 @@ -/* - * 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 "../board.h" - -#include "stm32f4xx.h" -#include "stm32f4xx_hal_conf.h" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ - -// Blue LED is chosen because the other LEDs are connected to ST-LINK lines. -#define LED_PORT GPIOC -#define LED_PIN GPIO_PIN_1 -#define LED_STATE_ON 1 - -// Pin D5 -#define BUTTON_PORT GPIOC -#define BUTTON_PIN GPIO_PIN_7 -#define BUTTON_STATE_ACTIVE 0 - -#define UARTx USART3 -#define UART_GPIO_PORT GPIOB -#define UART_GPIO_AF GPIO_AF7_USART3 -#define UART_TX_PIN GPIO_PIN_10 -#define UART_RX_PIN GPIO_PIN_11 - -UART_HandleTypeDef UartHandle; - - -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D- - __HAL_RCC_GPIOC_CLK_ENABLE(); // LED, Button - __HAL_RCC_GPIOB_CLK_ENABLE(); // Uart tx, rx - __HAL_RCC_USART3_CLK_ENABLE(); // Uart module -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 168000000 - * HCLK(Hz) = 168000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 4 - * APB2 Prescaler = 2 - * HSE Frequency(Hz) = 12000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 336 - * PLL_P = 2 - * PLL_Q = 7 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 5 - * @param None - * @retval None - */ -static void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 336; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 7; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 - clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); -} - -void board_init(void) -{ -#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 - - SystemClock_Config(); - SystemCoreClockUpdate(); - - all_rcc_clk_enable(); - - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - board_led_write(false); - - // Button - GPIO_InitStruct.Pin = BUTTON_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - // Uart - GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = UART_GPIO_AF; - HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); - - // USB Pin Init - // PA9- VUSB, PA10- ID, PA11- DM, PA12- DP - - /* Configure DM DP Pins */ - GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure VBUS Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_9; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* This for ID line debug */ - GPIO_InitStruct.Pin = GPIO_PIN_10; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - // Enable USB OTG clock - __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - - // Enable VBUS sense (B device) via pin PA9 - USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS; - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN; -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); -} - -uint32_t board_button_read(void) -{ - return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - (void) buf; (void) len; - return 0; -} - -int board_uart_write(void const * buf, int len) -{ - HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); - return len; -} - -#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 - -void HardFault_Handler (void) -{ - asm("bkpt"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} diff --git a/hw/bsp/imxrt/boards/mimxrt1010_evk/board.h b/hw/bsp/imxrt/boards/mimxrt1010_evk/board.h new file mode 100644 index 000000000..4f21b52fa --- /dev/null +++ b/hw/bsp/imxrt/boards/mimxrt1010_evk/board.h @@ -0,0 +1,53 @@ +/* + * 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. + */ + + +#ifndef BOARD_H_ +#define BOARD_H_ + +#include "fsl_device_registers.h" + +// required since iMX RT10xx SDK include this file for board size +#define BOARD_FLASH_SIZE (0x1000000U) + +// LED +#define LED_PINMUX IOMUXC_GPIO_11_GPIOMUX_IO11 +#define LED_PORT GPIO1 +#define LED_PIN 11 +#define LED_STATE_ON 0 + +// SW8 button +#define BUTTON_PINMUX IOMUXC_GPIO_SD_05_GPIO2_IO05 +#define BUTTON_PORT GPIO2 +#define BUTTON_PIN 5 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_PORT LPUART1 +#define UART_RX_PINMUX IOMUXC_GPIO_09_LPUART1_RXD +#define UART_TX_PINMUX IOMUXC_GPIO_10_LPUART1_TXD + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/imxrt/boards/mimxrt1010_evk/board.mk b/hw/bsp/imxrt/boards/mimxrt1010_evk/board.mk new file mode 100644 index 000000000..507db7f00 --- /dev/null +++ b/hw/bsp/imxrt/boards/mimxrt1010_evk/board.mk @@ -0,0 +1,11 @@ +CFLAGS += -DCPU_MIMXRT1011DAE5A +MCU_VARIANT = MIMXRT1011 + +# For flash-jlink target +JLINK_DEVICE = MIMXRT1011DAE5A + +# For flash-pyocd target +PYOCD_TARGET = mimxrt1010 + +# flash using pyocd +flash: flash-pyocd diff --git a/hw/bsp/mimxrt1010_evk/evkmimxrt1010_flexspi_nor_config.c b/hw/bsp/imxrt/boards/mimxrt1010_evk/evkmimxrt1010_flexspi_nor_config.c similarity index 100% rename from hw/bsp/mimxrt1010_evk/evkmimxrt1010_flexspi_nor_config.c rename to hw/bsp/imxrt/boards/mimxrt1010_evk/evkmimxrt1010_flexspi_nor_config.c diff --git a/hw/bsp/mimxrt1010_evk/evkmimxrt1010_flexspi_nor_config.h b/hw/bsp/imxrt/boards/mimxrt1010_evk/evkmimxrt1010_flexspi_nor_config.h similarity index 100% rename from hw/bsp/mimxrt1010_evk/evkmimxrt1010_flexspi_nor_config.h rename to hw/bsp/imxrt/boards/mimxrt1010_evk/evkmimxrt1010_flexspi_nor_config.h diff --git a/hw/bsp/mimxrt1015_evk/board.h b/hw/bsp/imxrt/boards/mimxrt1015_evk/board.h similarity index 72% rename from hw/bsp/mimxrt1015_evk/board.h rename to hw/bsp/imxrt/boards/mimxrt1015_evk/board.h index 5f3e31586..932ce7fd7 100644 --- a/hw/bsp/mimxrt1015_evk/board.h +++ b/hw/bsp/imxrt/boards/mimxrt1015_evk/board.h @@ -31,4 +31,21 @@ // required since iMX RT10xx SDK include this file for board size #define BOARD_FLASH_SIZE (0x1000000U) +// LED +#define LED_PINMUX IOMUXC_GPIO_SD_B1_01_GPIO3_IO21 +#define LED_PORT GPIO3 +#define LED_PIN 21 +#define LED_STATE_ON 0 + +// SW8 button +#define BUTTON_PINMUX IOMUXC_GPIO_EMC_09_GPIO2_IO09 +#define BUTTON_PORT GPIO2 +#define BUTTON_PIN 9 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_PORT LPUART1 +#define UART_RX_PINMUX IOMUXC_GPIO_AD_B0_07_LPUART1_RX +#define UART_TX_PINMUX IOMUXC_GPIO_AD_B0_06_LPUART1_TX + #endif /* BOARD_H_ */ diff --git a/hw/bsp/imxrt/boards/mimxrt1015_evk/board.mk b/hw/bsp/imxrt/boards/mimxrt1015_evk/board.mk new file mode 100644 index 000000000..17fd25dfe --- /dev/null +++ b/hw/bsp/imxrt/boards/mimxrt1015_evk/board.mk @@ -0,0 +1,11 @@ +CFLAGS += -DCPU_MIMXRT1015DAF5A +MCU_VARIANT = MIMXRT1015 + +# For flash-jlink target +JLINK_DEVICE = MIMXRT1015DAF5A + +# For flash-pyocd target +PYOCD_TARGET = mimxrt1015 + +# flash using pyocd +flash: flash-pyocd diff --git a/hw/bsp/mimxrt1015_evk/evkmimxrt1015_flexspi_nor_config.c b/hw/bsp/imxrt/boards/mimxrt1015_evk/evkmimxrt1015_flexspi_nor_config.c similarity index 100% rename from hw/bsp/mimxrt1015_evk/evkmimxrt1015_flexspi_nor_config.c rename to hw/bsp/imxrt/boards/mimxrt1015_evk/evkmimxrt1015_flexspi_nor_config.c diff --git a/hw/bsp/mimxrt1015_evk/evkmimxrt1015_flexspi_nor_config.h b/hw/bsp/imxrt/boards/mimxrt1015_evk/evkmimxrt1015_flexspi_nor_config.h similarity index 100% rename from hw/bsp/mimxrt1015_evk/evkmimxrt1015_flexspi_nor_config.h rename to hw/bsp/imxrt/boards/mimxrt1015_evk/evkmimxrt1015_flexspi_nor_config.h diff --git a/hw/bsp/mimxrt1060_evk/board.h b/hw/bsp/imxrt/boards/mimxrt1020_evk/board.h similarity index 72% rename from hw/bsp/mimxrt1060_evk/board.h rename to hw/bsp/imxrt/boards/mimxrt1020_evk/board.h index f1bd06369..56ed5855b 100644 --- a/hw/bsp/mimxrt1060_evk/board.h +++ b/hw/bsp/imxrt/boards/mimxrt1020_evk/board.h @@ -31,4 +31,21 @@ // required since iMX RT10xx SDK include this file for board size #define BOARD_FLASH_SIZE (0x800000U) +// LED +#define LED_PINMUX IOMUXC_GPIO_AD_B0_05_GPIO1_IO05 +#define LED_PORT GPIO1 +#define LED_PIN 5 +#define LED_STATE_ON 0 + +// SW8 button +#define BUTTON_PINMUX IOMUXC_SNVS_WAKEUP_GPIO5_IO00 +#define BUTTON_PORT GPIO5 +#define BUTTON_PIN 0 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_PORT LPUART1 +#define UART_RX_PINMUX IOMUXC_GPIO_AD_B0_07_LPUART1_RX +#define UART_TX_PINMUX IOMUXC_GPIO_AD_B0_06_LPUART1_TX + #endif /* BOARD_H_ */ diff --git a/hw/bsp/imxrt/boards/mimxrt1020_evk/board.mk b/hw/bsp/imxrt/boards/mimxrt1020_evk/board.mk new file mode 100644 index 000000000..b15da1b67 --- /dev/null +++ b/hw/bsp/imxrt/boards/mimxrt1020_evk/board.mk @@ -0,0 +1,11 @@ +CFLAGS += -DCPU_MIMXRT1021DAG5A +MCU_VARIANT = MIMXRT1021 + +# For flash-jlink target +JLINK_DEVICE = MIMXRT1021DAG5A + +# For flash-pyocd target +PYOCD_TARGET = mimxrt1020 + +# flash using pyocd +flash: flash-pyocd diff --git a/hw/bsp/mimxrt1020_evk/evkmimxrt1020_flexspi_nor_config.c b/hw/bsp/imxrt/boards/mimxrt1020_evk/evkmimxrt1020_flexspi_nor_config.c similarity index 100% rename from hw/bsp/mimxrt1020_evk/evkmimxrt1020_flexspi_nor_config.c rename to hw/bsp/imxrt/boards/mimxrt1020_evk/evkmimxrt1020_flexspi_nor_config.c diff --git a/hw/bsp/mimxrt1020_evk/evkmimxrt1020_flexspi_nor_config.h b/hw/bsp/imxrt/boards/mimxrt1020_evk/evkmimxrt1020_flexspi_nor_config.h similarity index 100% rename from hw/bsp/mimxrt1020_evk/evkmimxrt1020_flexspi_nor_config.h rename to hw/bsp/imxrt/boards/mimxrt1020_evk/evkmimxrt1020_flexspi_nor_config.h diff --git a/hw/bsp/imxrt/boards/mimxrt1050_evkb/board.h b/hw/bsp/imxrt/boards/mimxrt1050_evkb/board.h new file mode 100644 index 000000000..928fbd727 --- /dev/null +++ b/hw/bsp/imxrt/boards/mimxrt1050_evkb/board.h @@ -0,0 +1,51 @@ +/* + * 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. + */ + + +#ifndef BOARD_H_ +#define BOARD_H_ + +// required since iMX RT10xx SDK include this file for board size +#define BOARD_FLASH_SIZE (0x4000000U) + +// LED +#define LED_PINMUX IOMUXC_GPIO_AD_B0_09_GPIO1_IO09 +#define LED_PORT GPIO1 +#define LED_PIN 9 +#define LED_STATE_ON 0 + +// SW8 button +#define BUTTON_PINMUX IOMUXC_SNVS_WAKEUP_GPIO5_IO00 +#define BUTTON_PORT GPIO5 +#define BUTTON_PIN 0 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_PORT LPUART1 +#define UART_RX_PINMUX IOMUXC_GPIO_AD_B0_13_LPUART1_RX +#define UART_TX_PINMUX IOMUXC_GPIO_AD_B0_12_LPUART1_TX + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/imxrt/boards/mimxrt1050_evkb/board.mk b/hw/bsp/imxrt/boards/mimxrt1050_evkb/board.mk new file mode 100644 index 000000000..9fd229105 --- /dev/null +++ b/hw/bsp/imxrt/boards/mimxrt1050_evkb/board.mk @@ -0,0 +1,8 @@ +CFLAGS += -DCPU_MIMXRT1052DVL6B +MCU_VARIANT = MIMXRT1052 + +# For flash-pyocd target +PYOCD_TARGET = mimxrt1050 + +# flash using pyocd +flash: flash-pyocd diff --git a/hw/bsp/mimxrt1050_evkb/evkbimxrt1050_flexspi_nor_config.c b/hw/bsp/imxrt/boards/mimxrt1050_evkb/evkbimxrt1050_flexspi_nor_config.c similarity index 100% rename from hw/bsp/mimxrt1050_evkb/evkbimxrt1050_flexspi_nor_config.c rename to hw/bsp/imxrt/boards/mimxrt1050_evkb/evkbimxrt1050_flexspi_nor_config.c diff --git a/hw/bsp/mimxrt1050_evkb/evkbimxrt1050_flexspi_nor_config.h b/hw/bsp/imxrt/boards/mimxrt1050_evkb/evkbimxrt1050_flexspi_nor_config.h similarity index 100% rename from hw/bsp/mimxrt1050_evkb/evkbimxrt1050_flexspi_nor_config.h rename to hw/bsp/imxrt/boards/mimxrt1050_evkb/evkbimxrt1050_flexspi_nor_config.h diff --git a/hw/bsp/imxrt/boards/mimxrt1060_evk/board.h b/hw/bsp/imxrt/boards/mimxrt1060_evk/board.h new file mode 100644 index 000000000..7fa37e33f --- /dev/null +++ b/hw/bsp/imxrt/boards/mimxrt1060_evk/board.h @@ -0,0 +1,51 @@ +/* + * 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. + */ + + +#ifndef BOARD_H_ +#define BOARD_H_ + +// required since iMX RT10xx SDK include this file for board size +#define BOARD_FLASH_SIZE (0x800000U) + +// LED +#define LED_PINMUX IOMUXC_GPIO_AD_B0_09_GPIO1_IO09 +#define LED_PORT GPIO1 +#define LED_PIN 9 +#define LED_STATE_ON 0 + +// SW8 button +#define BUTTON_PINMUX IOMUXC_SNVS_WAKEUP_GPIO5_IO00 +#define BUTTON_PORT GPIO5 +#define BUTTON_PIN 0 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_PORT LPUART1 +#define UART_RX_PINMUX IOMUXC_GPIO_AD_B0_13_LPUART1_RX +#define UART_TX_PINMUX IOMUXC_GPIO_AD_B0_12_LPUART1_TX + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/imxrt/boards/mimxrt1060_evk/board.mk b/hw/bsp/imxrt/boards/mimxrt1060_evk/board.mk new file mode 100644 index 000000000..d0498dbb1 --- /dev/null +++ b/hw/bsp/imxrt/boards/mimxrt1060_evk/board.mk @@ -0,0 +1,11 @@ +CFLAGS += -DCPU_MIMXRT1062DVL6A +MCU_VARIANT = MIMXRT1062 + +# For flash-jlink target +JLINK_DEVICE = MIMXRT1062xxx6A + +# For flash-pyocd target +PYOCD_TARGET = mimxrt1060 + +# flash using pyocd +flash: flash-pyocd diff --git a/hw/bsp/mimxrt1060_evk/evkmimxrt1060_flexspi_nor_config.c b/hw/bsp/imxrt/boards/mimxrt1060_evk/evkmimxrt1060_flexspi_nor_config.c similarity index 100% rename from hw/bsp/mimxrt1060_evk/evkmimxrt1060_flexspi_nor_config.c rename to hw/bsp/imxrt/boards/mimxrt1060_evk/evkmimxrt1060_flexspi_nor_config.c diff --git a/hw/bsp/mimxrt1060_evk/evkmimxrt1060_flexspi_nor_config.h b/hw/bsp/imxrt/boards/mimxrt1060_evk/evkmimxrt1060_flexspi_nor_config.h similarity index 100% rename from hw/bsp/mimxrt1060_evk/evkmimxrt1060_flexspi_nor_config.h rename to hw/bsp/imxrt/boards/mimxrt1060_evk/evkmimxrt1060_flexspi_nor_config.h diff --git a/hw/bsp/mimxrt1064_evk/board.h b/hw/bsp/imxrt/boards/mimxrt1064_evk/board.h similarity index 72% rename from hw/bsp/mimxrt1064_evk/board.h rename to hw/bsp/imxrt/boards/mimxrt1064_evk/board.h index 3157e7d5e..5f51e91a2 100644 --- a/hw/bsp/mimxrt1064_evk/board.h +++ b/hw/bsp/imxrt/boards/mimxrt1064_evk/board.h @@ -31,4 +31,22 @@ // required since iMX RT10xx SDK include this file for board size #define BOARD_FLASH_SIZE (0x400000U) +// LED +#define LED_PINMUX IOMUXC_GPIO_AD_B0_09_GPIO1_IO09 +#define LED_PORT GPIO1 +#define LED_PIN 9 +#define LED_STATE_ON 0 + +// SW8 button +#define BUTTON_PINMUX IOMUXC_SNVS_WAKEUP_GPIO5_IO00 +#define BUTTON_PORT GPIO5 +#define BUTTON_PIN 0 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_PORT LPUART1 +#define UART_RX_PINMUX IOMUXC_GPIO_AD_B0_13_LPUART1_RX +#define UART_TX_PINMUX IOMUXC_GPIO_AD_B0_12_LPUART1_TX + + #endif /* BOARD_H_ */ diff --git a/hw/bsp/imxrt/boards/mimxrt1064_evk/board.mk b/hw/bsp/imxrt/boards/mimxrt1064_evk/board.mk new file mode 100644 index 000000000..586d74fe5 --- /dev/null +++ b/hw/bsp/imxrt/boards/mimxrt1064_evk/board.mk @@ -0,0 +1,11 @@ +CFLAGS += -DCPU_MIMXRT1064DVL6A +MCU_VARIANT = MIMXRT1064 + +# For flash-jlink target +JLINK_DEVICE = MIMXRT1064xxx6A + +# For flash-pyocd target +PYOCD_TARGET = mimxrt1064 + +# flash using pyocd +flash: flash-pyocd diff --git a/hw/bsp/mimxrt1064_evk/evkmimxrt1064_flexspi_nor_config.c b/hw/bsp/imxrt/boards/mimxrt1064_evk/evkmimxrt1064_flexspi_nor_config.c similarity index 100% rename from hw/bsp/mimxrt1064_evk/evkmimxrt1064_flexspi_nor_config.c rename to hw/bsp/imxrt/boards/mimxrt1064_evk/evkmimxrt1064_flexspi_nor_config.c diff --git a/hw/bsp/mimxrt1064_evk/evkmimxrt1064_flexspi_nor_config.h b/hw/bsp/imxrt/boards/mimxrt1064_evk/evkmimxrt1064_flexspi_nor_config.h similarity index 100% rename from hw/bsp/mimxrt1064_evk/evkmimxrt1064_flexspi_nor_config.h rename to hw/bsp/imxrt/boards/mimxrt1064_evk/evkmimxrt1064_flexspi_nor_config.h diff --git a/hw/bsp/imxrt/boards/teensy_40/board.h b/hw/bsp/imxrt/boards/teensy_40/board.h new file mode 100644 index 000000000..b3cc0a8c5 --- /dev/null +++ b/hw/bsp/imxrt/boards/teensy_40/board.h @@ -0,0 +1,52 @@ +/* + * 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. + */ + + +#ifndef BOARD_H_ +#define BOARD_H_ + + +// required since iMX RT10xx SDK include this file for board size +#define BOARD_FLASH_SIZE (2 * 1024 * 1024) + +// LED +#define LED_PINMUX IOMUXC_GPIO_B0_03_GPIO2_IO03 // D13 +#define LED_PORT GPIO2 +#define LED_PIN 3 +#define LED_STATE_ON 0 + +// no button +#define BUTTON_PINMUX IOMUXC_GPIO_B0_01_GPIO2_IO01 // D12 +#define BUTTON_PORT GPIO2 +#define BUTTON_PIN 1 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_PORT LPUART6 +#define UART_RX_PINMUX IOMUXC_GPIO_AD_B0_03_LPUART6_RX // D0 +#define UART_TX_PINMUX IOMUXC_GPIO_AD_B0_02_LPUART6_TX // D1 + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/imxrt/boards/teensy_40/board.mk b/hw/bsp/imxrt/boards/teensy_40/board.mk new file mode 100644 index 000000000..02f77193f --- /dev/null +++ b/hw/bsp/imxrt/boards/teensy_40/board.mk @@ -0,0 +1,10 @@ +CFLAGS += -DCPU_MIMXRT1062DVL6A +MCU_VARIANT = MIMXRT1062 + +# For flash-jlink target +JLINK_DEVICE = MIMXRT1062xxx6A + +# flash by using teensy_loader_cli https://github.com/PaulStoffregen/teensy_loader_cli +# Make sure it is in your PATH +flash: $(BUILD)/$(BOARD)-firmware.hex + teensy_loader_cli --mcu=imxrt1062 -v -w $< diff --git a/hw/bsp/teensy_40/teensy40_flexspi_nor_config.c b/hw/bsp/imxrt/boards/teensy_40/teensy40_flexspi_nor_config.c similarity index 96% rename from hw/bsp/teensy_40/teensy40_flexspi_nor_config.c rename to hw/bsp/imxrt/boards/teensy_40/teensy40_flexspi_nor_config.c index dbedc90a0..7929906eb 100644 --- a/hw/bsp/teensy_40/teensy40_flexspi_nor_config.c +++ b/hw/bsp/imxrt/boards/teensy_40/teensy40_flexspi_nor_config.c @@ -5,7 +5,7 @@ * SPDX-License-Identifier: BSD-3-Clause */ -#include "teensy40_flexspi_nor_config.h" +#include /* Component ID definition, used by tools. */ #ifndef FSL_COMPONENT_ID diff --git a/hw/bsp/teensy_40/teensy40_flexspi_nor_config.h b/hw/bsp/imxrt/boards/teensy_40/teensy40_flexspi_nor_config.h similarity index 100% rename from hw/bsp/teensy_40/teensy40_flexspi_nor_config.h rename to hw/bsp/imxrt/boards/teensy_40/teensy40_flexspi_nor_config.h diff --git a/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c b/hw/bsp/imxrt/family.c similarity index 89% rename from hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c rename to hw/bsp/imxrt/family.c index 6fb00b9b7..9dff104f1 100644 --- a/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c +++ b/hw/bsp/imxrt/family.c @@ -24,7 +24,8 @@ * This file is part of the TinyUSB stack. */ -#include "../board.h" +#include "bsp/board.h" +#include "board.h" #include "fsl_device_registers.h" #include "fsl_gpio.h" #include "fsl_iomuxc.h" @@ -33,22 +34,6 @@ #include "clock_config.h" -#define LED_PINMUX IOMUXC_GPIO_AD_B0_09_GPIO1_IO09 -#define LED_PORT GPIO1 -#define LED_PIN 9 -#define LED_STATE_ON 0 - -// SW8 button -#define BUTTON_PINMUX IOMUXC_SNVS_WAKEUP_GPIO5_IO00 -#define BUTTON_PORT GPIO5 -#define BUTTON_PIN 0 -#define BUTTON_STATE_ACTIVE 0 - -// UART -#define UART_PORT LPUART1 -#define UART_RX_PINMUX IOMUXC_GPIO_AD_B0_13_LPUART1_RX -#define UART_TX_PINMUX IOMUXC_GPIO_AD_B0_12_LPUART1_TX - // needed by fsl_flexspi_nor_boot const uint8_t dcd_data[] = { 0x00 }; @@ -79,6 +64,7 @@ void board_init(void) // Button IOMUXC_SetPinMux( BUTTON_PINMUX, 0U); + IOMUXC_SetPinConfig(BUTTON_PINMUX, 0x01B0A0U); gpio_pin_config_t button_config = { kGPIO_DigitalInput, 0, kGPIO_IntRisingEdge, }; GPIO_PinInit(BUTTON_PORT, BUTTON_PIN, &button_config); @@ -100,7 +86,14 @@ void board_init(void) CLOCK_EnableUsbhs0PhyPllClock(kCLOCK_Usbphy480M, 480000000U); CLOCK_EnableUsbhs0Clock(kCLOCK_Usb480M, 480000000U); - USBPHY_Type* usb_phy = USBPHY1; + USBPHY_Type* usb_phy; + + // RT105x RT106x have dual USB controller. TODO support USB2 +#ifdef USBPHY1 + usb_phy = USBPHY1; +#else + usb_phy = USBPHY; +#endif // Enable PHY support for Low speed device + LS via FS Hub usb_phy->CTRL |= USBPHY_CTRL_SET_ENUTMILEVEL2_MASK | USBPHY_CTRL_SET_ENUTMILEVEL3_MASK; diff --git a/hw/bsp/mimxrt1015_evk/board.mk b/hw/bsp/imxrt/family.mk similarity index 70% rename from hw/bsp/mimxrt1015_evk/board.mk rename to hw/bsp/imxrt/family.mk index 3ce7c2f82..47d403069 100644 --- a/hw/bsp/mimxrt1015_evk/board.mk +++ b/hw/bsp/imxrt/family.mk @@ -1,3 +1,5 @@ +include $(TOP)/$(BOARD_PATH)/board.mk + CFLAGS += \ -mthumb \ -mabi=aapcs \ @@ -5,7 +7,6 @@ CFLAGS += \ -mfloat-abi=hard \ -mfpu=fpv5-d16 \ -D__ARMVFP__=0 -D__ARMFPV5__=0\ - -DCPU_MIMXRT1015DAF5A \ -DXIP_EXTERNAL_FLASH=1 \ -DXIP_BOOT_HEADER_ENABLE=1 \ -DCFG_TUSB_MCU=OPT_MCU_MIMXRT10XX @@ -13,13 +14,17 @@ CFLAGS += \ # mcu driver cause following warnings CFLAGS += -Wno-error=unused-parameter -Wno-error=implicit-fallthrough= -MCU_DIR = hw/mcu/nxp/sdk/devices/MIMXRT1015 +MCU_DIR = hw/mcu/nxp/sdk/devices/$(MCU_VARIANT) # All source paths should be relative to the top level. -LD_FILE = $(MCU_DIR)/gcc/MIMXRT1015xxxxx_flexspi_nor.ld +LD_FILE = $(MCU_DIR)/gcc/$(MCU_VARIANT)xxxxx_flexspi_nor.ld + +# TODO for net_lwip_webserver exmaple, but may not needed !! +LDFLAGS += \ + -Wl,--defsym,__stack_size__=0x800 \ SRC_C += \ - $(MCU_DIR)/system_MIMXRT1015.c \ + $(MCU_DIR)/system_$(MCU_VARIANT).c \ $(MCU_DIR)/xip/fsl_flexspi_nor_boot.c \ $(MCU_DIR)/project_template/clock_config.c \ $(MCU_DIR)/drivers/fsl_clock.c \ @@ -28,13 +33,13 @@ SRC_C += \ $(MCU_DIR)/drivers/fsl_lpuart.c INC += \ - $(TOP)/hw/bsp/$(BOARD) \ + $(TOP)/$(BOARD_PATH) \ $(TOP)/$(MCU_DIR)/../../CMSIS/Include \ $(TOP)/$(MCU_DIR) \ $(TOP)/$(MCU_DIR)/drivers \ $(TOP)/$(MCU_DIR)/project_template \ -SRC_S += $(MCU_DIR)/gcc/startup_MIMXRT1015.S +SRC_S += $(MCU_DIR)/gcc/startup_$(MCU_VARIANT).S # For TinyUSB port source VENDOR = nxp @@ -43,11 +48,3 @@ CHIP_FAMILY = transdimension # For freeRTOS port source FREERTOS_PORT = ARM_CM7/r0p1 -# For flash-jlink target -JLINK_DEVICE = MIMXRT1015DAF5A - -# For flash-pyocd target -PYOCD_TARGET = mimxrt1015 - -# flash using pyocd -flash: flash-pyocd diff --git a/hw/bsp/itsybitsy_m4/board.mk b/hw/bsp/itsybitsy_m4/board.mk deleted file mode 100644 index 6cc6a9091..000000000 --- a/hw/bsp/itsybitsy_m4/board.mk +++ /dev/null @@ -1,53 +0,0 @@ -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/asf4/samd51/gcc/gcc/startup_samd51.c \ - hw/mcu/microchip/asf4/samd51/gcc/system_samd51.c \ - hw/mcu/microchip/asf4/samd51/hpl/gclk/hpl_gclk.c \ - hw/mcu/microchip/asf4/samd51/hpl/mclk/hpl_mclk.c \ - hw/mcu/microchip/asf4/samd51/hpl/osc32kctrl/hpl_osc32kctrl.c \ - hw/mcu/microchip/asf4/samd51/hpl/oscctrl/hpl_oscctrl.c \ - hw/mcu/microchip/asf4/samd51/hal/src/hal_atomic.c - -INC += \ - $(TOP)/hw/mcu/microchip/asf4/samd51/ \ - $(TOP)/hw/mcu/microchip/asf4/samd51/config \ - $(TOP)/hw/mcu/microchip/asf4/samd51/include \ - $(TOP)/hw/mcu/microchip/asf4/samd51/hal/include \ - $(TOP)/hw/mcu/microchip/asf4/samd51/hal/utils/include \ - $(TOP)/hw/mcu/microchip/asf4/samd51/hpl/port \ - $(TOP)/hw/mcu/microchip/asf4/samd51/hri \ - $(TOP)/hw/mcu/microchip/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 - -# flash using bossac at least version 1.8 -# 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 --offset=0x4000 -e -w $^ -R diff --git a/hw/bsp/itsybitsy_m4/itsybitsy_m4.c b/hw/bsp/itsybitsy_m4/itsybitsy_m4.c deleted file mode 100644 index 0195a9fc4..000000000 --- a/hw/bsp/itsybitsy_m4/itsybitsy_m4.c +++ /dev/null @@ -1,163 +0,0 @@ -/* - * 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" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USB_0_Handler (void) -{ - tud_int_handler(0); -} - -void USB_1_Handler (void) -{ - tud_int_handler(0); -} - -void USB_2_Handler (void) -{ - tud_int_handler(0); -} - -void USB_3_Handler (void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// 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); - - // Update SystemCoreClock since it is hard coded with asf4 and not correct - // Init 1ms tick timer (samd SystemCoreClock may not correct) - SystemCoreClock = CONF_CPU_FREQUENCY; - SysTick_Config(CONF_CPU_FREQUENCY / 1000); - - // 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_FREERTOS - // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) - NVIC_SetPriority(USB_0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); - NVIC_SetPriority(USB_1_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); - NVIC_SetPriority(USB_2_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); - NVIC_SetPriority(USB_3_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); -#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_nrf52840/board.mk b/hw/bsp/itsybitsy_nrf52840/board.mk deleted file mode 100644 index 059e55dff..000000000 --- a/hw/bsp/itsybitsy_nrf52840/board.mk +++ /dev/null @@ -1,69 +0,0 @@ -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 - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=undef -Wno-error=unused-parameter -Wno-error=cast-align - -# due to tusb_hal_nrf_power_event -GCCVERSION = $(firstword $(subst ., ,$(shell arm-none-eabi-gcc -dumpversion))) -ifeq ($(CMDEXE),1) -ifeq ($(shell if $(GCCVERSION) geq 8 echo 1), 1) -CFLAGS += -Wno-error=cast-function-type -endif -else -ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) -CFLAGS += -Wno-error=cast-function-type -endif -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/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 - -# 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/itsybitsy_nrf52840/itsybitsy_nrf52840.c b/hw/bsp/itsybitsy_nrf52840/itsybitsy_nrf52840.c deleted file mode 100644 index e9e5a3876..000000000 --- a/hw/bsp/itsybitsy_nrf52840/itsybitsy_nrf52840.c +++ /dev/null @@ -1,225 +0,0 @@ -/* - * 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 - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USBD_IRQHandler(void) -{ - tud_int_handler(0); -} - -/*------------------------------------------------------------------*/ -/* MACRO TYPEDEF CONSTANT ENUM - *------------------------------------------------------------------*/ -#define _PINNUM(port, pin) ((port)*32 + (pin)) - -#define LED_PIN _PINNUM(0, 6) -#define LED_STATE_ON 1 - -#define BUTTON_PIN _PINNUM(0, 29) - -#define UART_RX_PIN 25 -#define UART_TX_PIN 24 - -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); - - //------------- USB -------------// -#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/luna/board.mk b/hw/bsp/luna/board.mk deleted file mode 100644 index 272c9f4e1..000000000 --- a/hw/bsp/luna/board.mk +++ /dev/null @@ -1,46 +0,0 @@ -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/asf4/samd21/gcc/gcc/startup_samd21.c \ - hw/mcu/microchip/asf4/samd21/gcc/system_samd21.c \ - hw/mcu/microchip/asf4/samd21/hpl/gclk/hpl_gclk.c \ - hw/mcu/microchip/asf4/samd21/hpl/pm/hpl_pm.c \ - hw/mcu/microchip/asf4/samd21/hpl/sysctrl/hpl_sysctrl.c \ - hw/mcu/microchip/asf4/samd21/hal/src/hal_atomic.c - -INC += \ - $(TOP)/hw/mcu/microchip/asf4/samd21/ \ - $(TOP)/hw/mcu/microchip/asf4/samd21/config \ - $(TOP)/hw/mcu/microchip/asf4/samd21/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hal/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hal/utils/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hpl/pm/ \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hpl/port \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hri \ - $(TOP)/hw/mcu/microchip/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 - -# flash using jlink -flash: $(BUILD)/$(BOARD)-firmware.bin - dfu-util -a 0 -d 1d50:615c -D $< || dfu-util -a 0 -d 16d0:05a5 -D $< - diff --git a/hw/bsp/luna/luna.c b/hw/bsp/luna/luna.c deleted file mode 100644 index fa321aa43..000000000 --- a/hw/bsp/luna/luna.c +++ /dev/null @@ -1,144 +0,0 @@ -/* - * 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 "sam.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" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USB_Handler(void) -{ - tud_int_handler(0); -} - - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM DECLARATION -//--------------------------------------------------------------------+ -#define LED_PIN PIN_PA22 // pin PA22 -#define BUTTON_PIN PIN_PB22 // pin PB22 - -/* 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); - - // 1ms tick timer (samd SystemCoreClock may not correct) - SystemCoreClock = CONF_CPU_FREQUENCY; - SysTick_Config(CONF_CPU_FREQUENCY / 1000); - - // 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); - - /* 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); -} - -//--------------------------------------------------------------------+ -// 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/metro_m0_express/board.mk b/hw/bsp/metro_m0_express/board.mk deleted file mode 100644 index 61dc7c665..000000000 --- a/hw/bsp/metro_m0_express/board.mk +++ /dev/null @@ -1,50 +0,0 @@ -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/asf4/samd21/gcc/gcc/startup_samd21.c \ - hw/mcu/microchip/asf4/samd21/gcc/system_samd21.c \ - hw/mcu/microchip/asf4/samd21/hpl/gclk/hpl_gclk.c \ - hw/mcu/microchip/asf4/samd21/hpl/pm/hpl_pm.c \ - hw/mcu/microchip/asf4/samd21/hpl/sysctrl/hpl_sysctrl.c \ - hw/mcu/microchip/asf4/samd21/hal/src/hal_atomic.c - -INC += \ - $(TOP)/hw/mcu/microchip/asf4/samd21/ \ - $(TOP)/hw/mcu/microchip/asf4/samd21/config \ - $(TOP)/hw/mcu/microchip/asf4/samd21/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hal/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hal/utils/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hpl/pm/ \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hpl/port \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hri \ - $(TOP)/hw/mcu/microchip/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 - -# flash using bossac at least version 1.8 -# 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 --offset=0x2000 -e -w $^ -R diff --git a/hw/bsp/metro_m0_express/metro_m0_express.c b/hw/bsp/metro_m0_express/metro_m0_express.c deleted file mode 100644 index 4eb157c8f..000000000 --- a/hw/bsp/metro_m0_express/metro_m0_express.c +++ /dev/null @@ -1,155 +0,0 @@ -/* - * 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" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USB_Handler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM DECLARATION -//--------------------------------------------------------------------+ -#define LED_PIN 17 -#define BUTTON_PIN 15 // pin D5 - -/* 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); - - // Update SystemCoreClock since it is hard coded with asf4 and not correct - // Init 1ms tick timer (samd SystemCoreClock may not correct) - SystemCoreClock = CONF_CPU_FREQUENCY; - SysTick_Config(CONF_CPU_FREQUENCY / 1000); - - // 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_FREERTOS - // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) - NVIC_SetPriority(USB_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); -#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/metro_m4_express/metro_m4_express.c b/hw/bsp/metro_m4_express/metro_m4_express.c deleted file mode 100644 index b489b79c4..000000000 --- a/hw/bsp/metro_m4_express/metro_m4_express.c +++ /dev/null @@ -1,163 +0,0 @@ -/* - * 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" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USB_0_Handler (void) -{ - tud_int_handler(0); -} - -void USB_1_Handler (void) -{ - tud_int_handler(0); -} - -void USB_2_Handler (void) -{ - tud_int_handler(0); -} - -void USB_3_Handler (void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM DECLARATION -//--------------------------------------------------------------------+ -#define LED_PIN 16 -#define BUTTON_PIN (14 + 32) // 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); - - // Update SystemCoreClock since it is hard coded with asf4 and not correct - // Init 1ms tick timer (samd SystemCoreClock may not correct) - SystemCoreClock = CONF_CPU_FREQUENCY; - SysTick_Config(CONF_CPU_FREQUENCY / 1000); - - // 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_FREERTOS - // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) - NVIC_SetPriority(USB_0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); - NVIC_SetPriority(USB_1_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); - NVIC_SetPriority(USB_2_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); - NVIC_SetPriority(USB_3_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); -#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/mimxrt1010_evk/board.mk b/hw/bsp/mimxrt1010_evk/board.mk deleted file mode 100644 index bb714c1c5..000000000 --- a/hw/bsp/mimxrt1010_evk/board.mk +++ /dev/null @@ -1,57 +0,0 @@ -CFLAGS += \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m7 \ - -mfloat-abi=hard \ - -mfpu=fpv5-d16 \ - -D__ARMVFP__=0 -D__ARMFPV5__=0\ - -DCPU_MIMXRT1011DAE5A \ - -DXIP_EXTERNAL_FLASH=1 \ - -DXIP_BOOT_HEADER_ENABLE=1 \ - -DCFG_TUSB_MCU=OPT_MCU_MIMXRT10XX - -# mcu driver cause following warnings -# CFLAGS += -Wno-error=unused-parameter -Wno-error=implicit-fallthrough= -CFLAGS += -Wno-error=unused-parameter - -MCU_DIR = hw/mcu/nxp/sdk/devices/MIMXRT1011 - -# All source paths should be relative to the top level. -LD_FILE = $(MCU_DIR)/gcc/MIMXRT1011xxxxx_flexspi_nor.ld - -LDFLAGS += \ - -Wl,--defsym,__stack_size__=0x800 \ - -SRC_C += \ - $(MCU_DIR)/system_MIMXRT1011.c \ - $(MCU_DIR)/xip/fsl_flexspi_nor_boot.c \ - $(MCU_DIR)/project_template/clock_config.c \ - $(MCU_DIR)/drivers/fsl_clock.c \ - $(MCU_DIR)/drivers/fsl_gpio.c \ - $(MCU_DIR)/drivers/fsl_common.c \ - $(MCU_DIR)/drivers/fsl_lpuart.c - -INC += \ - $(TOP)/hw/bsp/$(BOARD) \ - $(TOP)/$(MCU_DIR)/../../CMSIS/Include \ - $(TOP)/$(MCU_DIR) \ - $(TOP)/$(MCU_DIR)/drivers \ - $(TOP)/$(MCU_DIR)/project_template \ - -SRC_S += $(MCU_DIR)/gcc/startup_MIMXRT1011.S - -# For TinyUSB port source -VENDOR = nxp -CHIP_FAMILY = transdimension - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM7/r0p1 - -# For flash-jlink target -JLINK_DEVICE = MIMXRT1011DAE5A - -# For flash-pyocd target -PYOCD_TARGET = mimxrt1010 - -# flash using pyocd -flash: flash-pyocd diff --git a/hw/bsp/mimxrt1010_evk/mimxrt1010_evk.c b/hw/bsp/mimxrt1010_evk/mimxrt1010_evk.c deleted file mode 100644 index 1c4b1798c..000000000 --- a/hw/bsp/mimxrt1010_evk/mimxrt1010_evk.c +++ /dev/null @@ -1,170 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2018, hathach (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 "../board.h" -#include "fsl_device_registers.h" -#include "fsl_gpio.h" -#include "fsl_iomuxc.h" -#include "fsl_clock.h" -#include "fsl_lpuart.h" - -#include "clock_config.h" - -#define LED_PINMUX IOMUXC_GPIO_11_GPIOMUX_IO11 -#define LED_PORT GPIO1 -#define LED_PIN 11 -#define LED_STATE_ON 0 - -// SW8 button -#define BUTTON_PINMUX IOMUXC_GPIO_SD_05_GPIO2_IO05 -#define BUTTON_PORT GPIO2 -#define BUTTON_PIN 5 -#define BUTTON_STATE_ACTIVE 0 - -// UART -#define UART_PORT LPUART1 -#define UART_RX_PINMUX IOMUXC_GPIO_09_LPUART1_RXD -#define UART_TX_PINMUX IOMUXC_GPIO_10_LPUART1_TXD - -const uint8_t dcd_data[] = { 0x00 }; - -void board_init(void) -{ - // Init clock - BOARD_BootClockRUN(); - SystemCoreClockUpdate(); - - // Enable IOCON clock - CLOCK_EnableClock(kCLOCK_Iomuxc); - -#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 - - // LED - IOMUXC_SetPinMux( LED_PINMUX, 0U); - IOMUXC_SetPinConfig( LED_PINMUX, 0x10B0U); - - gpio_pin_config_t led_config = { kGPIO_DigitalOutput, 0, kGPIO_NoIntmode }; - GPIO_PinInit(LED_PORT, LED_PIN, &led_config); - board_led_write(true); - - // Button - IOMUXC_SetPinMux( BUTTON_PINMUX, 0U); - IOMUXC_SetPinConfig(BUTTON_PINMUX, 0x01B0A0U); - gpio_pin_config_t button_config = { kGPIO_DigitalInput, 0, kGPIO_IntRisingEdge, }; - GPIO_PinInit(BUTTON_PORT, BUTTON_PIN, &button_config); - - // UART - IOMUXC_SetPinMux( UART_TX_PINMUX, 0U); - IOMUXC_SetPinMux( UART_RX_PINMUX, 0U); - IOMUXC_SetPinConfig( UART_TX_PINMUX, 0x10B0u); - IOMUXC_SetPinConfig( UART_RX_PINMUX, 0x10B0u); - - lpuart_config_t uart_config; - LPUART_GetDefaultConfig(&uart_config); - uart_config.baudRate_Bps = CFG_BOARD_UART_BAUDRATE; - uart_config.enableTx = true; - uart_config.enableRx = true; - LPUART_Init(UART_PORT, &uart_config, (CLOCK_GetPllFreq(kCLOCK_PllUsb1) / 6U) / (CLOCK_GetDiv(kCLOCK_UartDiv) + 1U)); - - //------------- USB0 -------------// - // Clock - CLOCK_EnableUsbhs0PhyPllClock(kCLOCK_Usbphy480M, 480000000U); - CLOCK_EnableUsbhs0Clock(kCLOCK_Usb480M, 480000000U); - - USBPHY_Type* usb_phy = USBPHY; - - // Enable PHY support for Low speed device + LS via FS Hub - usb_phy->CTRL |= USBPHY_CTRL_SET_ENUTMILEVEL2_MASK | USBPHY_CTRL_SET_ENUTMILEVEL3_MASK; - - // Enable all power for normal operation - usb_phy->PWD = 0; - - // TX Timing - uint32_t phytx = usb_phy->TX; - phytx &= ~(USBPHY_TX_D_CAL_MASK | USBPHY_TX_TXCAL45DM_MASK | USBPHY_TX_TXCAL45DP_MASK); - phytx |= USBPHY_TX_D_CAL(0x0C) | USBPHY_TX_TXCAL45DP(0x06) | USBPHY_TX_TXCAL45DM(0x06); - usb_phy->TX = phytx; -} - -//--------------------------------------------------------------------+ -// USB Interrupt Handler -//--------------------------------------------------------------------+ -void USB_OTG1_IRQHandler(void) -{ - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST - tuh_int_handler(0); - #endif - - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE - tud_int_handler(0); - #endif -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - GPIO_PinWrite(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); -} - -uint32_t board_button_read(void) -{ - // active low - return BUTTON_STATE_ACTIVE == GPIO_PinRead(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - LPUART_ReadBlocking(UART_PORT, buf, len); - return len; -} - -int board_uart_write(void const * buf, int len) -{ - LPUART_WriteBlocking(UART_PORT, (uint8_t*)buf, len); - return len; -} - -#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/mimxrt1015_evk/mimxrt1015_evk.c b/hw/bsp/mimxrt1015_evk/mimxrt1015_evk.c deleted file mode 100644 index 2b1f3cc80..000000000 --- a/hw/bsp/mimxrt1015_evk/mimxrt1015_evk.c +++ /dev/null @@ -1,170 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2018, hathach (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 "../board.h" -#include "fsl_device_registers.h" -#include "fsl_gpio.h" -#include "fsl_iomuxc.h" -#include "fsl_clock.h" -#include "fsl_lpuart.h" - -#include "clock_config.h" - -#define LED_PINMUX IOMUXC_GPIO_SD_B1_01_GPIO3_IO21 -#define LED_PORT GPIO3 -#define LED_PIN 21 -#define LED_STATE_ON 0 - -// SW8 button -#define BUTTON_PINMUX IOMUXC_GPIO_EMC_09_GPIO2_IO09 -#define BUTTON_PORT GPIO2 -#define BUTTON_PIN 9 -#define BUTTON_STATE_ACTIVE 0 - -// UART -#define UART_PORT LPUART1 -#define UART_RX_PINMUX IOMUXC_GPIO_AD_B0_07_LPUART1_RX -#define UART_TX_PINMUX IOMUXC_GPIO_AD_B0_06_LPUART1_TX - -const uint8_t dcd_data[] = { 0x00 }; - -void board_init(void) -{ - // Init clock - BOARD_BootClockRUN(); - SystemCoreClockUpdate(); - - // Enable IOCON clock - CLOCK_EnableClock(kCLOCK_Iomuxc); - -#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 - - // LED - IOMUXC_SetPinMux( LED_PINMUX, 0U); - IOMUXC_SetPinConfig( LED_PINMUX, 0x10B0U); - - gpio_pin_config_t led_config = { kGPIO_DigitalOutput, 0, kGPIO_NoIntmode }; - GPIO_PinInit(LED_PORT, LED_PIN, &led_config); - board_led_write(true); - - // Button - IOMUXC_SetPinMux( BUTTON_PINMUX, 0U); - IOMUXC_SetPinConfig(BUTTON_PINMUX, 0x01B0A0U); - gpio_pin_config_t button_config = { kGPIO_DigitalInput, 0, kGPIO_IntRisingEdge, }; - GPIO_PinInit(BUTTON_PORT, BUTTON_PIN, &button_config); - - // UART - IOMUXC_SetPinMux( UART_TX_PINMUX, 0U); - IOMUXC_SetPinMux( UART_RX_PINMUX, 0U); - IOMUXC_SetPinConfig( UART_TX_PINMUX, 0x10B0u); - IOMUXC_SetPinConfig( UART_RX_PINMUX, 0x10B0u); - - lpuart_config_t uart_config; - LPUART_GetDefaultConfig(&uart_config); - uart_config.baudRate_Bps = CFG_BOARD_UART_BAUDRATE; - uart_config.enableTx = true; - uart_config.enableRx = true; - LPUART_Init(UART_PORT, &uart_config, (CLOCK_GetPllFreq(kCLOCK_PllUsb1) / 6U) / (CLOCK_GetDiv(kCLOCK_UartDiv) + 1U)); - - //------------- USB0 -------------// - // Clock - CLOCK_EnableUsbhs0PhyPllClock(kCLOCK_Usbphy480M, 480000000U); - CLOCK_EnableUsbhs0Clock(kCLOCK_Usb480M, 480000000U); - - USBPHY_Type* usb_phy = USBPHY; - - // Enable PHY support for Low speed device + LS via FS Hub - usb_phy->CTRL |= USBPHY_CTRL_SET_ENUTMILEVEL2_MASK | USBPHY_CTRL_SET_ENUTMILEVEL3_MASK; - - // Enable all power for normal operation - usb_phy->PWD = 0; - - // TX Timing - uint32_t phytx = usb_phy->TX; - phytx &= ~(USBPHY_TX_D_CAL_MASK | USBPHY_TX_TXCAL45DM_MASK | USBPHY_TX_TXCAL45DP_MASK); - phytx |= USBPHY_TX_D_CAL(0x0C) | USBPHY_TX_TXCAL45DP(0x06) | USBPHY_TX_TXCAL45DM(0x06); - usb_phy->TX = phytx; -} - -//--------------------------------------------------------------------+ -// USB Interrupt Handler -//--------------------------------------------------------------------+ -void USB_OTG1_IRQHandler(void) -{ - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST - tuh_int_handler(0); - #endif - - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE - tud_int_handler(0); - #endif -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - GPIO_PinWrite(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); -} - -uint32_t board_button_read(void) -{ - // active low - return BUTTON_STATE_ACTIVE == GPIO_PinRead(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - LPUART_ReadBlocking(UART_PORT, buf, len); - return len; -} - -int board_uart_write(void const * buf, int len) -{ - LPUART_WriteBlocking(UART_PORT, (uint8_t*)buf, len); - return len; -} - -#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/mimxrt1020_evk/board.mk b/hw/bsp/mimxrt1020_evk/board.mk deleted file mode 100644 index 66bcdf89b..000000000 --- a/hw/bsp/mimxrt1020_evk/board.mk +++ /dev/null @@ -1,53 +0,0 @@ -CFLAGS += \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m7 \ - -mfloat-abi=hard \ - -mfpu=fpv5-d16 \ - -D__ARMVFP__=0 -D__ARMFPV5__=0\ - -DCPU_MIMXRT1021DAG5A \ - -DXIP_EXTERNAL_FLASH=1 \ - -DXIP_BOOT_HEADER_ENABLE=1 \ - -DCFG_TUSB_MCU=OPT_MCU_MIMXRT10XX - -# mcu driver cause following warnings -CFLAGS += -Wno-error=unused-parameter - -MCU_DIR = hw/mcu/nxp/sdk/devices/MIMXRT1021 - -# All source paths should be relative to the top level. -LD_FILE = $(MCU_DIR)/gcc/MIMXRT1021xxxxx_flexspi_nor.ld - -SRC_C += \ - $(MCU_DIR)/system_MIMXRT1021.c \ - $(MCU_DIR)/xip/fsl_flexspi_nor_boot.c \ - $(MCU_DIR)/project_template/clock_config.c \ - $(MCU_DIR)/drivers/fsl_clock.c \ - $(MCU_DIR)/drivers/fsl_gpio.c \ - $(MCU_DIR)/drivers/fsl_common.c \ - $(MCU_DIR)/drivers/fsl_lpuart.c - -INC += \ - $(TOP)/hw/bsp/$(BOARD) \ - $(TOP)/$(MCU_DIR)/../../CMSIS/Include \ - $(TOP)/$(MCU_DIR) \ - $(TOP)/$(MCU_DIR)/drivers \ - $(TOP)/$(MCU_DIR)/project_template \ - -SRC_S += $(MCU_DIR)/gcc/startup_MIMXRT1021.S - -# For TinyUSB port source -VENDOR = nxp -CHIP_FAMILY = transdimension - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM7/r0p1 - -# For flash-jlink target -JLINK_DEVICE = MIMXRT1021DAG5A - -# For flash-pyocd target -PYOCD_TARGET = mimxrt1020 - -# flash using pyocd -flash: flash-pyocd diff --git a/hw/bsp/mimxrt1020_evk/mimxrt1020_evk.c b/hw/bsp/mimxrt1020_evk/mimxrt1020_evk.c deleted file mode 100644 index 273f3a0c9..000000000 --- a/hw/bsp/mimxrt1020_evk/mimxrt1020_evk.c +++ /dev/null @@ -1,169 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2018, hathach (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 "../board.h" -#include "fsl_device_registers.h" -#include "fsl_gpio.h" -#include "fsl_iomuxc.h" -#include "fsl_clock.h" -#include "fsl_lpuart.h" - -#include "clock_config.h" - -#define LED_PINMUX IOMUXC_GPIO_AD_B0_05_GPIO1_IO05 -#define LED_PORT GPIO1 -#define LED_PIN 5 -#define LED_STATE_ON 0 - -// SW8 button -#define BUTTON_PINMUX IOMUXC_SNVS_WAKEUP_GPIO5_IO00 -#define BUTTON_PORT GPIO5 -#define BUTTON_PIN 0 -#define BUTTON_STATE_ACTIVE 0 - -// UART -#define UART_PORT LPUART1 -#define UART_RX_PINMUX IOMUXC_GPIO_AD_B0_07_LPUART1_RX -#define UART_TX_PINMUX IOMUXC_GPIO_AD_B0_06_LPUART1_TX - -const uint8_t dcd_data[] = { 0x00 }; - -void board_init(void) -{ - // Init clock - BOARD_BootClockRUN(); - SystemCoreClockUpdate(); - - // Enable IOCON clock - CLOCK_EnableClock(kCLOCK_Iomuxc); - -#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 - - // LED - IOMUXC_SetPinMux( LED_PINMUX, 0U); - IOMUXC_SetPinConfig( LED_PINMUX, 0x10B0U); - - gpio_pin_config_t led_config = { kGPIO_DigitalOutput, 0, kGPIO_NoIntmode }; - GPIO_PinInit(LED_PORT, LED_PIN, &led_config); - board_led_write(true); - - // Button - IOMUXC_SetPinMux( BUTTON_PINMUX, 0U); - gpio_pin_config_t button_config = { kGPIO_DigitalInput, 0, kGPIO_IntRisingEdge, }; - GPIO_PinInit(BUTTON_PORT, BUTTON_PIN, &button_config); - - // UART - IOMUXC_SetPinMux( UART_TX_PINMUX, 0U); - IOMUXC_SetPinMux( UART_RX_PINMUX, 0U); - IOMUXC_SetPinConfig( UART_TX_PINMUX, 0x10B0u); - IOMUXC_SetPinConfig( UART_RX_PINMUX, 0x10B0u); - - lpuart_config_t uart_config; - LPUART_GetDefaultConfig(&uart_config); - uart_config.baudRate_Bps = CFG_BOARD_UART_BAUDRATE; - uart_config.enableTx = true; - uart_config.enableRx = true; - LPUART_Init(UART_PORT, &uart_config, (CLOCK_GetPllFreq(kCLOCK_PllUsb1) / 6U) / (CLOCK_GetDiv(kCLOCK_UartDiv) + 1U)); - - //------------- USB0 -------------// - // Clock - CLOCK_EnableUsbhs0PhyPllClock(kCLOCK_Usbphy480M, 480000000U); - CLOCK_EnableUsbhs0Clock(kCLOCK_Usb480M, 480000000U); - - USBPHY_Type* usb_phy = USBPHY; - - // Enable PHY support for Low speed device + LS via FS Hub - usb_phy->CTRL |= USBPHY_CTRL_SET_ENUTMILEVEL2_MASK | USBPHY_CTRL_SET_ENUTMILEVEL3_MASK; - - // Enable all power for normal operation - usb_phy->PWD = 0; - - // TX Timing - uint32_t phytx = usb_phy->TX; - phytx &= ~(USBPHY_TX_D_CAL_MASK | USBPHY_TX_TXCAL45DM_MASK | USBPHY_TX_TXCAL45DP_MASK); - phytx |= USBPHY_TX_D_CAL(0x0C) | USBPHY_TX_TXCAL45DP(0x06) | USBPHY_TX_TXCAL45DM(0x06); - usb_phy->TX = phytx; -} - -//--------------------------------------------------------------------+ -// USB Interrupt Handler -//--------------------------------------------------------------------+ -void USB_OTG1_IRQHandler(void) -{ - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST - tuh_int_handler(0); - #endif - - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE - tud_int_handler(0); - #endif -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - GPIO_PinWrite(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); -} - -uint32_t board_button_read(void) -{ - // active low - return BUTTON_STATE_ACTIVE == GPIO_PinRead(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - LPUART_ReadBlocking(UART_PORT, buf, len); - return len; -} - -int board_uart_write(void const * buf, int len) -{ - LPUART_WriteBlocking(UART_PORT, (uint8_t*)buf, len); - return len; -} - -#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/mimxrt1050_evkb/board.mk b/hw/bsp/mimxrt1050_evkb/board.mk deleted file mode 100644 index 123e2ea82..000000000 --- a/hw/bsp/mimxrt1050_evkb/board.mk +++ /dev/null @@ -1,50 +0,0 @@ -CFLAGS += \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m7 \ - -mfloat-abi=hard \ - -mfpu=fpv5-d16 \ - -D__ARMVFP__=0 -D__ARMFPV5__=0\ - -DCPU_MIMXRT1052DVL6B \ - -DXIP_EXTERNAL_FLASH=1 \ - -DXIP_BOOT_HEADER_ENABLE=1 \ - -DCFG_TUSB_MCU=OPT_MCU_MIMXRT10XX - -# mcu driver cause following warnings -CFLAGS += -Wno-error=unused-parameter - -MCU_DIR = hw/mcu/nxp/sdk/devices/MIMXRT1052 - -# All source paths should be relative to the top level. -LD_FILE = $(MCU_DIR)/gcc/MIMXRT1052xxxxx_flexspi_nor.ld - -SRC_C += \ - $(MCU_DIR)/system_MIMXRT1052.c \ - $(MCU_DIR)/xip/fsl_flexspi_nor_boot.c \ - $(MCU_DIR)/project_template/clock_config.c \ - $(MCU_DIR)/drivers/fsl_clock.c \ - $(MCU_DIR)/drivers/fsl_gpio.c \ - $(MCU_DIR)/drivers/fsl_common.c \ - $(MCU_DIR)/drivers/fsl_lpuart.c - -INC += \ - $(TOP)/hw/bsp/$(BOARD) \ - $(TOP)/$(MCU_DIR)/../../CMSIS/Include \ - $(TOP)/$(MCU_DIR) \ - $(TOP)/$(MCU_DIR)/drivers \ - $(TOP)/$(MCU_DIR)/project_template \ - -SRC_S += $(MCU_DIR)/gcc/startup_MIMXRT1052.S - -# For TinyUSB port source -VENDOR = nxp -CHIP_FAMILY = transdimension - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM7/r0p1 - -# For flash-pyocd target -PYOCD_TARGET = mimxrt1050 - -# flash using pyocd -flash: flash-pyocd diff --git a/hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c b/hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c deleted file mode 100644 index 1042bcfe7..000000000 --- a/hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c +++ /dev/null @@ -1,184 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2018, hathach (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 "../board.h" -#include "fsl_device_registers.h" -#include "fsl_gpio.h" -#include "fsl_iomuxc.h" -#include "fsl_clock.h" -#include "fsl_lpuart.h" - -#include "clock_config.h" - -#define LED_PINMUX IOMUXC_GPIO_AD_B0_09_GPIO1_IO09 -#define LED_PORT GPIO1 -#define LED_PIN 9 -#define LED_STATE_ON 0 - -// SW8 button -#define BUTTON_PINMUX IOMUXC_SNVS_WAKEUP_GPIO5_IO00 -#define BUTTON_PORT GPIO5 -#define BUTTON_PIN 0 -#define BUTTON_STATE_ACTIVE 0 - -// UART -#define UART_PORT LPUART1 -#define UART_RX_PINMUX IOMUXC_GPIO_AD_B0_13_LPUART1_RX -#define UART_TX_PINMUX IOMUXC_GPIO_AD_B0_12_LPUART1_TX - -const uint8_t dcd_data[] = { 0x00 }; - -void board_init(void) -{ - // Init clock - BOARD_BootClockRUN(); - SystemCoreClockUpdate(); - - // Enable IOCON clock - CLOCK_EnableClock(kCLOCK_Iomuxc); - -#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 - - // LED - IOMUXC_SetPinMux( LED_PINMUX, 0U); - IOMUXC_SetPinConfig( LED_PINMUX, 0x10B0U); - - gpio_pin_config_t led_config = { kGPIO_DigitalOutput, 0, kGPIO_NoIntmode }; - GPIO_PinInit(LED_PORT, LED_PIN, &led_config); - board_led_write(true); - - // Button - IOMUXC_SetPinMux( BUTTON_PINMUX, 0U); - gpio_pin_config_t button_config = { kGPIO_DigitalInput, 0, kGPIO_IntRisingEdge, }; - GPIO_PinInit(BUTTON_PORT, BUTTON_PIN, &button_config); - - // UART - IOMUXC_SetPinMux( UART_TX_PINMUX, 0U); - IOMUXC_SetPinMux( UART_RX_PINMUX, 0U); - IOMUXC_SetPinConfig( UART_TX_PINMUX, 0x10B0u); - IOMUXC_SetPinConfig( UART_RX_PINMUX, 0x10B0u); - - lpuart_config_t uart_config; - LPUART_GetDefaultConfig(&uart_config); - uart_config.baudRate_Bps = CFG_BOARD_UART_BAUDRATE; - uart_config.enableTx = true; - uart_config.enableRx = true; - LPUART_Init(UART_PORT, &uart_config, (CLOCK_GetPllFreq(kCLOCK_PllUsb1) / 6U) / (CLOCK_GetDiv(kCLOCK_UartDiv) + 1U)); - - //------------- USB0 -------------// - // Clock - CLOCK_EnableUsbhs0PhyPllClock(kCLOCK_Usbphy480M, 480000000U); - CLOCK_EnableUsbhs0Clock(kCLOCK_Usb480M, 480000000U); - - USBPHY_Type* usb_phy = USBPHY1; - - // Enable PHY support for Low speed device + LS via FS Hub - usb_phy->CTRL |= USBPHY_CTRL_SET_ENUTMILEVEL2_MASK | USBPHY_CTRL_SET_ENUTMILEVEL3_MASK; - - // Enable all power for normal operation - usb_phy->PWD = 0; - - // TX Timing - uint32_t phytx = usb_phy->TX; - phytx &= ~(USBPHY_TX_D_CAL_MASK | USBPHY_TX_TXCAL45DM_MASK | USBPHY_TX_TXCAL45DP_MASK); - phytx |= USBPHY_TX_D_CAL(0x0C) | USBPHY_TX_TXCAL45DP(0x06) | USBPHY_TX_TXCAL45DM(0x06); - usb_phy->TX = phytx; - - // USB1 -// CLOCK_EnableUsbhs1PhyPllClock(kCLOCK_Usbphy480M, 480000000U); -// CLOCK_EnableUsbhs1Clock(kCLOCK_Usb480M, 480000000U); -} - -//--------------------------------------------------------------------+ -// USB Interrupt Handler -//--------------------------------------------------------------------+ -void USB_OTG1_IRQHandler(void) -{ - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST - tuh_int_handler(0); - #endif - - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE - tud_int_handler(0); - #endif -} - -void USB_OTG2_IRQHandler(void) -{ - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST - tuh_int_handler(1); - #endif - - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE - tud_int_handler(1); - #endif -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - GPIO_PinWrite(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); -} - -uint32_t board_button_read(void) -{ - // active low - return BUTTON_STATE_ACTIVE == GPIO_PinRead(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - LPUART_ReadBlocking(UART_PORT, buf, len); - return len; -} - -int board_uart_write(void const * buf, int len) -{ - LPUART_WriteBlocking(UART_PORT, (uint8_t*)buf, len); - return len; -} - -#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/mimxrt1060_evk/board.mk b/hw/bsp/mimxrt1060_evk/board.mk deleted file mode 100644 index 5c93e1cdf..000000000 --- a/hw/bsp/mimxrt1060_evk/board.mk +++ /dev/null @@ -1,53 +0,0 @@ -CFLAGS += \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m7 \ - -mfloat-abi=hard \ - -mfpu=fpv5-d16 \ - -D__ARMVFP__=0 -D__ARMFPV5__=0\ - -DCPU_MIMXRT1062DVL6A \ - -DXIP_EXTERNAL_FLASH=1 \ - -DXIP_BOOT_HEADER_ENABLE=1 \ - -DCFG_TUSB_MCU=OPT_MCU_MIMXRT10XX - -# mcu driver cause following warnings -CFLAGS += -Wno-error=unused-parameter - -MCU_DIR = hw/mcu/nxp/sdk/devices/MIMXRT1062 - -# All source paths should be relative to the top level. -LD_FILE = $(MCU_DIR)/gcc/MIMXRT1062xxxxx_flexspi_nor.ld - -SRC_C += \ - $(MCU_DIR)/system_MIMXRT1062.c \ - $(MCU_DIR)/xip/fsl_flexspi_nor_boot.c \ - $(MCU_DIR)/project_template/clock_config.c \ - $(MCU_DIR)/drivers/fsl_clock.c \ - $(MCU_DIR)/drivers/fsl_gpio.c \ - $(MCU_DIR)/drivers/fsl_common.c \ - $(MCU_DIR)/drivers/fsl_lpuart.c - -INC += \ - $(TOP)/hw/bsp/$(BOARD) \ - $(TOP)/$(MCU_DIR)/../../CMSIS/Include \ - $(TOP)/$(MCU_DIR) \ - $(TOP)/$(MCU_DIR)/drivers \ - $(TOP)/$(MCU_DIR)/project_template \ - -SRC_S += $(MCU_DIR)/gcc/startup_MIMXRT1062.S - -# For TinyUSB port source -VENDOR = nxp -CHIP_FAMILY = transdimension - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM7/r0p1 - -# For flash-jlink target -JLINK_DEVICE = MIMXRT1062xxx6A - -# For flash-pyocd target -PYOCD_TARGET = mimxrt1060 - -# flash using pyocd -flash: flash-pyocd diff --git a/hw/bsp/mimxrt1064_evk/board.mk b/hw/bsp/mimxrt1064_evk/board.mk deleted file mode 100644 index f6a277497..000000000 --- a/hw/bsp/mimxrt1064_evk/board.mk +++ /dev/null @@ -1,53 +0,0 @@ -CFLAGS += \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m7 \ - -mfloat-abi=hard \ - -mfpu=fpv5-d16 \ - -D__ARMVFP__=0 -D__ARMFPV5__=0\ - -DCPU_MIMXRT1064DVL6A \ - -DXIP_EXTERNAL_FLASH=1 \ - -DXIP_BOOT_HEADER_ENABLE=1 \ - -DCFG_TUSB_MCU=OPT_MCU_MIMXRT10XX - -# mcu driver cause following warnings -CFLAGS += -Wno-error=unused-parameter - -MCU_DIR = hw/mcu/nxp/sdk/devices/MIMXRT1064 - -# All source paths should be relative to the top level. -LD_FILE = $(MCU_DIR)/gcc/MIMXRT1064xxxxx_flexspi_nor.ld - -SRC_C += \ - $(MCU_DIR)/system_MIMXRT1064.c \ - $(MCU_DIR)/xip/fsl_flexspi_nor_boot.c \ - $(MCU_DIR)/project_template/clock_config.c \ - $(MCU_DIR)/drivers/fsl_clock.c \ - $(MCU_DIR)/drivers/fsl_gpio.c \ - $(MCU_DIR)/drivers/fsl_common.c \ - $(MCU_DIR)/drivers/fsl_lpuart.c - -INC += \ - $(TOP)/hw/bsp/$(BOARD) \ - $(TOP)/$(MCU_DIR)/../../CMSIS/Include \ - $(TOP)/$(MCU_DIR) \ - $(TOP)/$(MCU_DIR)/drivers \ - $(TOP)/$(MCU_DIR)/project_template \ - -SRC_S += $(MCU_DIR)/gcc/startup_MIMXRT1064.S - -# For TinyUSB port source -VENDOR = nxp -CHIP_FAMILY = transdimension - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM7/r0p1 - -# For flash-jlink target -JLINK_DEVICE = MIMXRT1064xxx6A - -# For flash-pyocd target -PYOCD_TARGET = mimxrt1064 - -# flash using pyocd -flash: flash-pyocd diff --git a/hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c b/hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c deleted file mode 100644 index 1042bcfe7..000000000 --- a/hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c +++ /dev/null @@ -1,184 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2018, hathach (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 "../board.h" -#include "fsl_device_registers.h" -#include "fsl_gpio.h" -#include "fsl_iomuxc.h" -#include "fsl_clock.h" -#include "fsl_lpuart.h" - -#include "clock_config.h" - -#define LED_PINMUX IOMUXC_GPIO_AD_B0_09_GPIO1_IO09 -#define LED_PORT GPIO1 -#define LED_PIN 9 -#define LED_STATE_ON 0 - -// SW8 button -#define BUTTON_PINMUX IOMUXC_SNVS_WAKEUP_GPIO5_IO00 -#define BUTTON_PORT GPIO5 -#define BUTTON_PIN 0 -#define BUTTON_STATE_ACTIVE 0 - -// UART -#define UART_PORT LPUART1 -#define UART_RX_PINMUX IOMUXC_GPIO_AD_B0_13_LPUART1_RX -#define UART_TX_PINMUX IOMUXC_GPIO_AD_B0_12_LPUART1_TX - -const uint8_t dcd_data[] = { 0x00 }; - -void board_init(void) -{ - // Init clock - BOARD_BootClockRUN(); - SystemCoreClockUpdate(); - - // Enable IOCON clock - CLOCK_EnableClock(kCLOCK_Iomuxc); - -#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 - - // LED - IOMUXC_SetPinMux( LED_PINMUX, 0U); - IOMUXC_SetPinConfig( LED_PINMUX, 0x10B0U); - - gpio_pin_config_t led_config = { kGPIO_DigitalOutput, 0, kGPIO_NoIntmode }; - GPIO_PinInit(LED_PORT, LED_PIN, &led_config); - board_led_write(true); - - // Button - IOMUXC_SetPinMux( BUTTON_PINMUX, 0U); - gpio_pin_config_t button_config = { kGPIO_DigitalInput, 0, kGPIO_IntRisingEdge, }; - GPIO_PinInit(BUTTON_PORT, BUTTON_PIN, &button_config); - - // UART - IOMUXC_SetPinMux( UART_TX_PINMUX, 0U); - IOMUXC_SetPinMux( UART_RX_PINMUX, 0U); - IOMUXC_SetPinConfig( UART_TX_PINMUX, 0x10B0u); - IOMUXC_SetPinConfig( UART_RX_PINMUX, 0x10B0u); - - lpuart_config_t uart_config; - LPUART_GetDefaultConfig(&uart_config); - uart_config.baudRate_Bps = CFG_BOARD_UART_BAUDRATE; - uart_config.enableTx = true; - uart_config.enableRx = true; - LPUART_Init(UART_PORT, &uart_config, (CLOCK_GetPllFreq(kCLOCK_PllUsb1) / 6U) / (CLOCK_GetDiv(kCLOCK_UartDiv) + 1U)); - - //------------- USB0 -------------// - // Clock - CLOCK_EnableUsbhs0PhyPllClock(kCLOCK_Usbphy480M, 480000000U); - CLOCK_EnableUsbhs0Clock(kCLOCK_Usb480M, 480000000U); - - USBPHY_Type* usb_phy = USBPHY1; - - // Enable PHY support for Low speed device + LS via FS Hub - usb_phy->CTRL |= USBPHY_CTRL_SET_ENUTMILEVEL2_MASK | USBPHY_CTRL_SET_ENUTMILEVEL3_MASK; - - // Enable all power for normal operation - usb_phy->PWD = 0; - - // TX Timing - uint32_t phytx = usb_phy->TX; - phytx &= ~(USBPHY_TX_D_CAL_MASK | USBPHY_TX_TXCAL45DM_MASK | USBPHY_TX_TXCAL45DP_MASK); - phytx |= USBPHY_TX_D_CAL(0x0C) | USBPHY_TX_TXCAL45DP(0x06) | USBPHY_TX_TXCAL45DM(0x06); - usb_phy->TX = phytx; - - // USB1 -// CLOCK_EnableUsbhs1PhyPllClock(kCLOCK_Usbphy480M, 480000000U); -// CLOCK_EnableUsbhs1Clock(kCLOCK_Usb480M, 480000000U); -} - -//--------------------------------------------------------------------+ -// USB Interrupt Handler -//--------------------------------------------------------------------+ -void USB_OTG1_IRQHandler(void) -{ - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST - tuh_int_handler(0); - #endif - - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE - tud_int_handler(0); - #endif -} - -void USB_OTG2_IRQHandler(void) -{ - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST - tuh_int_handler(1); - #endif - - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE - tud_int_handler(1); - #endif -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - GPIO_PinWrite(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); -} - -uint32_t board_button_read(void) -{ - // active low - return BUTTON_STATE_ACTIVE == GPIO_PinRead(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - LPUART_ReadBlocking(UART_PORT, buf, len); - return len; -} - -int board_uart_write(void const * buf, int len) -{ - LPUART_WriteBlocking(UART_PORT, (uint8_t*)buf, len); - return len; -} - -#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/nrf/boards/adafruit_clue/board.h b/hw/bsp/nrf/boards/adafruit_clue/board.h new file mode 100644 index 000000000..2c58e8fe8 --- /dev/null +++ b/hw/bsp/nrf/boards/adafruit_clue/board.h @@ -0,0 +1,52 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define _PINNUM(port, pin) ((port)*32 + (pin)) + +// LED +#define LED_PIN _PINNUM(1, 1) +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN _PINNUM(1, 02) +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 4 +#define UART_TX_PIN 5 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/nrf/boards/adafruit_clue/board.mk b/hw/bsp/nrf/boards/adafruit_clue/board.mk new file mode 100644 index 000000000..d8530dc74 --- /dev/null +++ b/hw/bsp/nrf/boards/adafruit_clue/board.mk @@ -0,0 +1,10 @@ +MCU_VARIANT = nrf52840 +CFLAGS += -DNRF52840_XXAA + +$(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/nrf/boards/adafruit_clue/nrf52840_s140_v6.ld similarity index 100% rename from hw/bsp/adafruit_clue/nrf52840_s140_v6.ld rename to hw/bsp/nrf/boards/adafruit_clue/nrf52840_s140_v6.ld diff --git a/hw/bsp/arduino_nano33_ble/arduino_nano33_ble.ld b/hw/bsp/nrf/boards/arduino_nano33_ble/arduino_nano33_ble.ld similarity index 100% rename from hw/bsp/arduino_nano33_ble/arduino_nano33_ble.ld rename to hw/bsp/nrf/boards/arduino_nano33_ble/arduino_nano33_ble.ld diff --git a/hw/bsp/nrf/boards/arduino_nano33_ble/board.h b/hw/bsp/nrf/boards/arduino_nano33_ble/board.h new file mode 100644 index 000000000..d548e01c3 --- /dev/null +++ b/hw/bsp/nrf/boards/arduino_nano33_ble/board.h @@ -0,0 +1,52 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define _PINNUM(port, pin) ((port)*32 + (pin)) + +// LED +#define LED_PIN _PINNUM(0, 24) +#define LED_STATE_ON 0 + +// Button +#define BUTTON_PIN _PINNUM(1, 11) // D2 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN _PINNUM(1, 10) +#define UART_TX_PIN _PINNUM(1, 3) + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/nrf/boards/arduino_nano33_ble/board.mk b/hw/bsp/nrf/boards/arduino_nano33_ble/board.mk new file mode 100644 index 000000000..7d8e9bce1 --- /dev/null +++ b/hw/bsp/nrf/boards/arduino_nano33_ble/board.mk @@ -0,0 +1,13 @@ +MCU_VARIANT = nrf52840 +CFLAGS += -DNRF52840_XXAA + +LD_FILE = $(BOARD_PATH)/$(BOARD).ld + +# 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 diff --git a/hw/bsp/nrf/boards/circuitplayground_bluefruit/board.h b/hw/bsp/nrf/boards/circuitplayground_bluefruit/board.h new file mode 100644 index 000000000..a86c9dc7f --- /dev/null +++ b/hw/bsp/nrf/boards/circuitplayground_bluefruit/board.h @@ -0,0 +1,52 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define _PINNUM(port, pin) ((port)*32 + (pin)) + +// LED +#define LED_PIN _PINNUM(1, 14) +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN _PINNUM(1, 15) +#define BUTTON_STATE_ACTIVE 1 + +// UART +#define UART_RX_PIN 30 +#define UART_TX_PIN 14 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/nrf/boards/circuitplayground_bluefruit/board.mk b/hw/bsp/nrf/boards/circuitplayground_bluefruit/board.mk new file mode 100644 index 000000000..d8530dc74 --- /dev/null +++ b/hw/bsp/nrf/boards/circuitplayground_bluefruit/board.mk @@ -0,0 +1,10 @@ +MCU_VARIANT = nrf52840 +CFLAGS += -DNRF52840_XXAA + +$(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/circuitplayground_bluefruit/nrf52840_s140_v6.ld b/hw/bsp/nrf/boards/circuitplayground_bluefruit/nrf52840_s140_v6.ld similarity index 100% rename from hw/bsp/circuitplayground_bluefruit/nrf52840_s140_v6.ld rename to hw/bsp/nrf/boards/circuitplayground_bluefruit/nrf52840_s140_v6.ld diff --git a/hw/bsp/nrf/boards/feather_nrf52840_express/board.h b/hw/bsp/nrf/boards/feather_nrf52840_express/board.h new file mode 100644 index 000000000..3208a948a --- /dev/null +++ b/hw/bsp/nrf/boards/feather_nrf52840_express/board.h @@ -0,0 +1,52 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define _PINNUM(port, pin) ((port)*32 + (pin)) + +// LED +#define LED_PIN _PINNUM(1, 15) +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN _PINNUM(1, 02) +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 24 +#define UART_TX_PIN 25 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/nrf/boards/feather_nrf52840_express/board.mk b/hw/bsp/nrf/boards/feather_nrf52840_express/board.mk new file mode 100644 index 000000000..d8530dc74 --- /dev/null +++ b/hw/bsp/nrf/boards/feather_nrf52840_express/board.mk @@ -0,0 +1,10 @@ +MCU_VARIANT = nrf52840 +CFLAGS += -DNRF52840_XXAA + +$(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_express/nrf52840_s140_v6.ld b/hw/bsp/nrf/boards/feather_nrf52840_express/nrf52840_s140_v6.ld similarity index 100% rename from hw/bsp/feather_nrf52840_express/nrf52840_s140_v6.ld rename to hw/bsp/nrf/boards/feather_nrf52840_express/nrf52840_s140_v6.ld diff --git a/hw/bsp/nrf/boards/feather_nrf52840_sense/board.h b/hw/bsp/nrf/boards/feather_nrf52840_sense/board.h new file mode 100644 index 000000000..ece6e34cb --- /dev/null +++ b/hw/bsp/nrf/boards/feather_nrf52840_sense/board.h @@ -0,0 +1,52 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define _PINNUM(port, pin) ((port)*32 + (pin)) + +// LED +#define LED_PIN _PINNUM(1, 9) +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN _PINNUM(1, 02) +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 24 +#define UART_TX_PIN 25 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/nrf/boards/feather_nrf52840_sense/board.mk b/hw/bsp/nrf/boards/feather_nrf52840_sense/board.mk new file mode 100644 index 000000000..d8530dc74 --- /dev/null +++ b/hw/bsp/nrf/boards/feather_nrf52840_sense/board.mk @@ -0,0 +1,10 @@ +MCU_VARIANT = nrf52840 +CFLAGS += -DNRF52840_XXAA + +$(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/nrf52840_s140_v6.ld b/hw/bsp/nrf/boards/feather_nrf52840_sense/nrf52840_s140_v6.ld similarity index 100% rename from hw/bsp/feather_nrf52840_sense/nrf52840_s140_v6.ld rename to hw/bsp/nrf/boards/feather_nrf52840_sense/nrf52840_s140_v6.ld diff --git a/hw/bsp/nrf/boards/itsybitsy_nrf52840/board.h b/hw/bsp/nrf/boards/itsybitsy_nrf52840/board.h new file mode 100644 index 000000000..132173a80 --- /dev/null +++ b/hw/bsp/nrf/boards/itsybitsy_nrf52840/board.h @@ -0,0 +1,52 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define _PINNUM(port, pin) ((port)*32 + (pin)) + +// LED +#define LED_PIN _PINNUM(0, 6) +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN _PINNUM(0, 29) +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 25 +#define UART_TX_PIN 24 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/nrf/boards/itsybitsy_nrf52840/board.mk b/hw/bsp/nrf/boards/itsybitsy_nrf52840/board.mk new file mode 100644 index 000000000..d8530dc74 --- /dev/null +++ b/hw/bsp/nrf/boards/itsybitsy_nrf52840/board.mk @@ -0,0 +1,10 @@ +MCU_VARIANT = nrf52840 +CFLAGS += -DNRF52840_XXAA + +$(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/itsybitsy_nrf52840/nrf52840_s140_v6.ld b/hw/bsp/nrf/boards/itsybitsy_nrf52840/nrf52840_s140_v6.ld similarity index 100% rename from hw/bsp/itsybitsy_nrf52840/nrf52840_s140_v6.ld rename to hw/bsp/nrf/boards/itsybitsy_nrf52840/nrf52840_s140_v6.ld diff --git a/hw/bsp/nrf/boards/nrf52840_mdk_dongle/board.h b/hw/bsp/nrf/boards/nrf52840_mdk_dongle/board.h new file mode 100644 index 000000000..01dd1f24f --- /dev/null +++ b/hw/bsp/nrf/boards/nrf52840_mdk_dongle/board.h @@ -0,0 +1,52 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define _PINNUM(port, pin) ((port)*32 + (pin)) + +// LED +#define LED_PIN _PINNUM(0, 23) +#define LED_STATE_ON 0 + +// Button +#define BUTTON_PIN _PINNUM(0, 18) +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 2 +#define UART_TX_PIN 3 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/nrf/boards/nrf52840_mdk_dongle/board.mk b/hw/bsp/nrf/boards/nrf52840_mdk_dongle/board.mk new file mode 100644 index 000000000..a184fa892 --- /dev/null +++ b/hw/bsp/nrf/boards/nrf52840_mdk_dongle/board.mk @@ -0,0 +1,15 @@ +MCU_VARIANT = nrf52840 +CFLAGS += -DNRF52840_XXAA + +LD_FILE = $(BOARD_PATH)/$(BOARD).ld + +# flash using Nordic nrfutil (pip3 install nrfutil) +# make BOARD=nrf52840_mdk_dongle SERIAL=/dev/ttyACM0 all flash +NRFUTIL = nrfutil + +$(BUILD)/$(BOARD)-firmware.zip: $(BUILD)/$(BOARD)-firmware.hex + $(NRFUTIL) pkg generate --hw-version 52 --sd-req 0x0000 --debug-mode --application $^ $@ + +flash: $(BUILD)/$(BOARD)-firmware.zip + @:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0) + $(NRFUTIL) dfu usb-serial --package $^ -p $(SERIAL) -b 115200 \ No newline at end of file diff --git a/hw/bsp/nrf52840_mdk_dongle/nrf52840_mdk_dongle.ld b/hw/bsp/nrf/boards/nrf52840_mdk_dongle/nrf52840_mdk_dongle.ld similarity index 100% rename from hw/bsp/nrf52840_mdk_dongle/nrf52840_mdk_dongle.ld rename to hw/bsp/nrf/boards/nrf52840_mdk_dongle/nrf52840_mdk_dongle.ld diff --git a/hw/bsp/mimxrt1020_evk/board.h b/hw/bsp/nrf/boards/pca10056/board.h similarity index 78% rename from hw/bsp/mimxrt1020_evk/board.h rename to hw/bsp/nrf/boards/pca10056/board.h index f1bd06369..ab12d21aa 100644 --- a/hw/bsp/mimxrt1020_evk/board.h +++ b/hw/bsp/nrf/boards/pca10056/board.h @@ -1,7 +1,7 @@ /* * The MIT License (MIT) * - * Copyright (c) 2019, Ha Thach (tinyusb.org) + * Copyright (c) 2020, 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 @@ -24,11 +24,27 @@ * This file is part of the TinyUSB stack. */ - #ifndef BOARD_H_ #define BOARD_H_ -// required since iMX RT10xx SDK include this file for board size -#define BOARD_FLASH_SIZE (0x800000U) +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PIN 13 +#define LED_STATE_ON 0 + +// Button +#define BUTTON_PIN 11 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 8 +#define UART_TX_PIN 6 + +#ifdef __cplusplus + } +#endif #endif /* BOARD_H_ */ diff --git a/hw/bsp/nrf/boards/pca10056/board.mk b/hw/bsp/nrf/boards/pca10056/board.mk new file mode 100644 index 000000000..be2ed3314 --- /dev/null +++ b/hw/bsp/nrf/boards/pca10056/board.mk @@ -0,0 +1,7 @@ +MCU_VARIANT = nrf52840 +CFLAGS += -DNRF52840_XXAA + +LD_FILE = hw/mcu/nordic/nrfx/mdk/nrf52840_xxaa.ld + +# flash using jlink +flash: flash-jlink diff --git a/hw/bsp/nrf/boards/pca10059/board.h b/hw/bsp/nrf/boards/pca10059/board.h new file mode 100644 index 000000000..0810be648 --- /dev/null +++ b/hw/bsp/nrf/boards/pca10059/board.h @@ -0,0 +1,52 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define _PINNUM(port, pin) ((port)*32 + (pin)) + +// LED +#define LED_PIN 8 +#define LED_STATE_ON 0 + +// Button +#define BUTTON_PIN _PINNUM(1, 6) +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 8 +#define UART_TX_PIN 6 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/nrf/boards/pca10059/board.mk b/hw/bsp/nrf/boards/pca10059/board.mk new file mode 100644 index 000000000..25609f2fa --- /dev/null +++ b/hw/bsp/nrf/boards/pca10059/board.mk @@ -0,0 +1,15 @@ +MCU_VARIANT = nrf52840 +CFLAGS += -DNRF52840_XXAA + +LD_FILE = $(BOARD_PATH)/$(BOARD).ld + +# flash using Nordic nrfutil (pip2 install nrfutil) +# make BOARD=pca10059 SERIAL=/dev/ttyACM0 all flash +NRFUTIL = nrfutil + +$(BUILD)/$(BOARD)-firmware.zip: $(BUILD)/$(BOARD)-firmware.hex + $(NRFUTIL) pkg generate --hw-version 52 --sd-req 0x0000 --debug-mode --application $^ $@ + +flash: $(BUILD)/$(BOARD)-firmware.zip + @:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0) + $(NRFUTIL) dfu usb-serial --package $^ -p $(SERIAL) -b 115200 diff --git a/hw/bsp/pca10059/pca10059.ld b/hw/bsp/nrf/boards/pca10059/pca10059.ld similarity index 100% rename from hw/bsp/pca10059/pca10059.ld rename to hw/bsp/nrf/boards/pca10059/pca10059.ld diff --git a/hw/bsp/nrf/boards/pca10100/board.h b/hw/bsp/nrf/boards/pca10100/board.h new file mode 100644 index 000000000..881133035 --- /dev/null +++ b/hw/bsp/nrf/boards/pca10100/board.h @@ -0,0 +1,52 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define _PINNUM(port, pin) ((port)*32 + (pin)) + +// LED +#define LED_PIN 13 +#define LED_STATE_ON 0 + +// Button +#define BUTTON_PIN 11 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 8 +#define UART_TX_PIN 6 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/nrf/boards/pca10100/board.mk b/hw/bsp/nrf/boards/pca10100/board.mk new file mode 100644 index 000000000..5fba269b7 --- /dev/null +++ b/hw/bsp/nrf/boards/pca10100/board.mk @@ -0,0 +1,7 @@ +MCU_VARIANT = nrf52833 +CFLAGS += -DNRF52833_XXAA + +LD_FILE = hw/mcu/nordic/nrfx/mdk/nrf52833_xxaa.ld + +# flash using jlink +flash: flash-jlink diff --git a/hw/bsp/nrf/boards/raytac_mdbt50q_rx/board.h b/hw/bsp/nrf/boards/raytac_mdbt50q_rx/board.h new file mode 100644 index 000000000..dcf829d9c --- /dev/null +++ b/hw/bsp/nrf/boards/raytac_mdbt50q_rx/board.h @@ -0,0 +1,52 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define _PINNUM(port, pin) ((port)*32 + (pin)) + +// LED +#define LED_PIN _PINNUM(1, 13) +#define LED_STATE_ON 0 + +// Button +#define BUTTON_PIN _PINNUM(0, 15) +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 25 +#define UART_TX_PIN 24 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/nrf/boards/raytac_mdbt50q_rx/board.mk b/hw/bsp/nrf/boards/raytac_mdbt50q_rx/board.mk new file mode 100644 index 000000000..be2ed3314 --- /dev/null +++ b/hw/bsp/nrf/boards/raytac_mdbt50q_rx/board.mk @@ -0,0 +1,7 @@ +MCU_VARIANT = nrf52840 +CFLAGS += -DNRF52840_XXAA + +LD_FILE = hw/mcu/nordic/nrfx/mdk/nrf52840_xxaa.ld + +# flash using jlink +flash: flash-jlink diff --git a/hw/bsp/pca10056/pca10056.c b/hw/bsp/nrf/family.c similarity index 94% rename from hw/bsp/pca10056/pca10056.c rename to hw/bsp/nrf/family.c index 30df50124..48f560a6f 100644 --- a/hw/bsp/pca10056/pca10056.c +++ b/hw/bsp/nrf/family.c @@ -26,6 +26,8 @@ #include "bsp/board.h" +#include "board.h" + #include "nrfx.h" #include "nrfx/hal/nrf_gpio.h" #include "nrfx/drivers/include/nrfx_power.h" @@ -47,17 +49,8 @@ void USBD_IRQHandler(void) /*------------------------------------------------------------------*/ /* MACRO TYPEDEF CONSTANT ENUM *------------------------------------------------------------------*/ -#define LED_PIN 13 -#define LED_STATE_ON 0 - -#define BUTTON_PIN 11 -#define BUTTON_STATE_ACTIVE 0 - -#define UART_RX_PIN 8 -#define UART_TX_PIN 6 static nrfx_uarte_t _uart_id = NRFX_UARTE_INSTANCE(0); -//static void uart_handler(nrfx_uart_event_t const * p_event, void* p_context); // 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. @@ -100,6 +93,7 @@ void board_init(void) nrfx_uarte_init(&_uart_id, &uart_cfg, NULL); //uart_handler); + //------------- USB -------------// #if TUSB_OPT_DEVICE_ENABLED // Priorities 0, 1, 4 (nRF52) are reserved for SoftDevice // 2 is highest for application @@ -155,11 +149,6 @@ uint32_t board_button_read(void) return BUTTON_STATE_ACTIVE == nrf_gpio_pin_read(BUTTON_PIN); } -//static void uart_handler(nrfx_uart_event_t const * p_event, void* p_context) -//{ -// -//} - int board_uart_read(uint8_t* buf, int len) { (void) buf; (void) len; diff --git a/hw/bsp/feather_nrf52840_express/board.mk b/hw/bsp/nrf/family.mk similarity index 59% rename from hw/bsp/feather_nrf52840_express/board.mk rename to hw/bsp/nrf/family.mk index 059e55dff..7d8f10956 100644 --- a/hw/bsp/feather_nrf52840_express/board.mk +++ b/hw/bsp/nrf/family.mk @@ -1,3 +1,5 @@ +include $(TOP)/$(BOARD_PATH)/board.mk + CFLAGS += \ -flto \ -mthumb \ @@ -6,7 +8,6 @@ CFLAGS += \ -mfloat-abi=hard \ -mfpu=fpv4-sp-d16 \ -DCFG_TUSB_MCU=OPT_MCU_NRF5X \ - -DNRF52840_XXAA \ -DCONFIG_GPIO_AS_PINRESET # suppress warning caused by vendor mcu driver @@ -15,26 +16,27 @@ CFLAGS += -Wno-error=undef -Wno-error=unused-parameter -Wno-error=cast-align # due to tusb_hal_nrf_power_event GCCVERSION = $(firstword $(subst ., ,$(shell arm-none-eabi-gcc -dumpversion))) ifeq ($(CMDEXE),1) -ifeq ($(shell if $(GCCVERSION) geq 8 echo 1), 1) -CFLAGS += -Wno-error=cast-function-type -endif + ifeq ($(shell if $(GCCVERSION) geq 8 echo 1), 1) + CFLAGS += -Wno-error=cast-function-type + endif else -ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) -CFLAGS += -Wno-error=cast-function-type -endif + ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) + CFLAGS += -Wno-error=cast-function-type + endif endif # All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/nrf52840_s140_v6.ld +LD_FILE ?= hw/bsp/nrf/boards/$(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/drivers/src/nrfx_uarte.c \ - hw/mcu/nordic/nrfx/mdk/system_nrf52840.c + hw/mcu/nordic/nrfx/mdk/system_$(MCU_VARIANT).c INC += \ + $(TOP)/$(BOARD_PATH) \ $(TOP)/lib/CMSIS_4/CMSIS/Include \ $(TOP)/hw/mcu/nordic \ $(TOP)/hw/mcu/nordic/nrfx \ @@ -43,7 +45,7 @@ INC += \ $(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 +SRC_S += hw/mcu/nordic/nrfx/mdk/gcc_startup_$(MCU_VARIANT).S ASFLAGS += -D__HEAP_SIZE=0 @@ -55,15 +57,7 @@ CHIP_FAMILY = nrf5x FREERTOS_PORT = ARM_CM4F # For flash-jlink target -JLINK_DEVICE = nRF52840_xxAA +JLINK_DEVICE = $(MCU_VARIANT)_xxaa # 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/nrf52840_mdk_dongle/board.mk b/hw/bsp/nrf52840_mdk_dongle/board.mk deleted file mode 100644 index 3c44e402c..000000000 --- a/hw/bsp/nrf52840_mdk_dongle/board.mk +++ /dev/null @@ -1,67 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m4 \ - -mfloat-abi=hard \ - -mfpu=fpv4-sp-d16 \ - -DNRF52840_XXAA \ - -DCFG_TUSB_MCU=OPT_MCU_NRF5X - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=undef -Wno-error=unused-parameter -Wno-error=cast-align - -# due to tusb_hal_nrf_power_event -GCCVERSION = $(firstword $(subst ., ,$(shell arm-none-eabi-gcc -dumpversion))) -ifeq ($(CMDEXE),1) -ifeq ($(shell if $(GCCVERSION) geq 8 echo 1), 1) -CFLAGS += -Wno-error=cast-function-type -endif -else -ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) -CFLAGS += -Wno-error=cast-function-type -endif -endif - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/$(BOARD).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)/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 - -# flash using Nordic nrfutil (pip2 install nrfutil) -# make BOARD=nrf52840_mdk_dongle SERIAL=/dev/ttyACM0 all flash -NRFUTIL = nrfutil - -$(BUILD)/$(BOARD)-firmware.zip: $(BUILD)/$(BOARD)-firmware.hex - $(NRFUTIL) pkg generate --hw-version 52 --sd-req 0x0000 --debug-mode --application $^ $@ - -flash: $(BUILD)/$(BOARD)-firmware.zip - @:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0) - $(NRFUTIL) dfu usb-serial --package $^ -p $(SERIAL) -b 115200 diff --git a/hw/bsp/nrf52840_mdk_dongle/nrf52840_mdk_dongle.c b/hw/bsp/nrf52840_mdk_dongle/nrf52840_mdk_dongle.c deleted file mode 100644 index 870a290dd..000000000 --- a/hw/bsp/nrf52840_mdk_dongle/nrf52840_mdk_dongle.c +++ /dev/null @@ -1,198 +0,0 @@ -/* - * 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 - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USBD_IRQHandler(void) -{ - tud_int_handler(0); -} - -/*------------------------------------------------------------------*/ -/* MACRO TYPEDEF CONSTANT ENUM - *------------------------------------------------------------------*/ -#define LED_PIN 23 -#define LED_STATE_ON 0 - -// Button 1 -#define BUTTON_PIN 18 -#define BUTTON_STATE_ACTIVE 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) -{ - // 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) -{ - return BUTTON_STATE_ACTIVE == nrf_gpio_pin_read(BUTTON_PIN); -} - -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/pca10056/board.mk b/hw/bsp/pca10056/board.mk deleted file mode 100644 index b8691525b..000000000 --- a/hw/bsp/pca10056/board.mk +++ /dev/null @@ -1,61 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m4 \ - -mfloat-abi=hard \ - -mfpu=fpv4-sp-d16 \ - -DNRF52840_XXAA \ - -DCONFIG_GPIO_AS_PINRESET \ - -DCFG_TUSB_MCU=OPT_MCU_NRF5X - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=undef -Wno-error=unused-parameter -Wno-error=cast-align - -# due to tusb_hal_nrf_power_event -GCCVERSION = $(firstword $(subst ., ,$(shell arm-none-eabi-gcc -dumpversion))) -ifeq ($(CMDEXE),1) -ifeq ($(shell if $(GCCVERSION) geq 8 echo 1), 1) -CFLAGS += -Wno-error=cast-function-type -endif -else -ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) -CFLAGS += -Wno-error=cast-function-type -endif -endif - -# All source paths should be relative to the top level. -LD_FILE = hw/mcu/nordic/nrfx/mdk/nrf52840_xxaa.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 - -# flash using jlink -flash: flash-jlink diff --git a/hw/bsp/pca10059/board.mk b/hw/bsp/pca10059/board.mk deleted file mode 100644 index 178f09474..000000000 --- a/hw/bsp/pca10059/board.mk +++ /dev/null @@ -1,68 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m4 \ - -mfloat-abi=hard \ - -mfpu=fpv4-sp-d16 \ - -DNRF52840_XXAA \ - -DCONFIG_GPIO_AS_PINRESET \ - -DCFG_TUSB_MCU=OPT_MCU_NRF5X - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=undef -Wno-error=unused-parameter -Wno-error=cast-align - -# due to tusb_hal_nrf_power_event -GCCVERSION = $(firstword $(subst ., ,$(shell arm-none-eabi-gcc -dumpversion))) -ifeq ($(CMDEXE),1) -ifeq ($(shell if $(GCCVERSION) geq 8 echo 1), 1) -CFLAGS += -Wno-error=cast-function-type -endif -else -ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) -CFLAGS += -Wno-error=cast-function-type -endif -endif - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/$(BOARD).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)/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 - -# flash using Nordic nrfutil (pip2 install nrfutil) -# make BOARD=pca10059 SERIAL=/dev/ttyACM0 all flash -NRFUTIL = nrfutil - -$(BUILD)/$(BOARD)-firmware.zip: $(BUILD)/$(BOARD)-firmware.hex - $(NRFUTIL) pkg generate --hw-version 52 --sd-req 0x0000 --debug-mode --application $^ $@ - -flash: $(BUILD)/$(BOARD)-firmware.zip - @:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0) - $(NRFUTIL) dfu usb-serial --package $^ -p $(SERIAL) -b 115200 diff --git a/hw/bsp/pca10059/pca10059.c b/hw/bsp/pca10059/pca10059.c deleted file mode 100644 index 2a2a45eb2..000000000 --- a/hw/bsp/pca10059/pca10059.c +++ /dev/null @@ -1,196 +0,0 @@ -/* - * 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 - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USBD_IRQHandler(void) -{ - tud_int_handler(0); -} - -/*------------------------------------------------------------------*/ -/* MACRO TYPEDEF CONSTANT ENUM - *------------------------------------------------------------------*/ -#define LED_PIN 8 -#define LED_STATE_ON 0 - -// Button 1 -#define BUTTON_PIN (32+6) // P1.06 -#define BUTTON_STATE_ACTIVE 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) -{ - // 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); - -#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) -{ - return BUTTON_STATE_ACTIVE == nrf_gpio_pin_read(BUTTON_PIN); -} - -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/pca10100/board.mk b/hw/bsp/pca10100/board.mk deleted file mode 100644 index 8ada94ba0..000000000 --- a/hw/bsp/pca10100/board.mk +++ /dev/null @@ -1,61 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m4 \ - -mfloat-abi=hard \ - -mfpu=fpv4-sp-d16 \ - -DNRF52833_XXAA \ - -DCONFIG_GPIO_AS_PINRESET \ - -DCFG_TUSB_MCU=OPT_MCU_NRF5X - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=undef -Wno-error=unused-parameter -Wno-error=cast-align - -# due to tusb_hal_nrf_power_event -GCCVERSION = $(firstword $(subst ., ,$(shell arm-none-eabi-gcc -dumpversion))) -ifeq ($(CMDEXE),1) -ifeq ($(shell if $(GCCVERSION) geq 8 echo 1), 1) -CFLAGS += -Wno-error=cast-function-type -endif -else -ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) -CFLAGS += -Wno-error=cast-function-type -endif -endif - -# All source paths should be relative to the top level. -LD_FILE = hw/mcu/nordic/nrfx/mdk/nrf52833_xxaa.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_nrf52833.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_nrf52833.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 = nRF52833_XXAA - -# flash using jlink -flash: flash-jlink diff --git a/hw/bsp/pca10100/pca10100.c b/hw/bsp/pca10100/pca10100.c deleted file mode 100644 index 30df50124..000000000 --- a/hw/bsp/pca10100/pca10100.c +++ /dev/null @@ -1,229 +0,0 @@ -/* - * 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 - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USBD_IRQHandler(void) -{ - tud_int_handler(0); -} - -/*------------------------------------------------------------------*/ -/* MACRO TYPEDEF CONSTANT ENUM - *------------------------------------------------------------------*/ -#define LED_PIN 13 -#define LED_STATE_ON 0 - -#define BUTTON_PIN 11 -#define BUTTON_STATE_ACTIVE 0 - -#define UART_RX_PIN 8 -#define UART_TX_PIN 6 - -static nrfx_uarte_t _uart_id = NRFX_UARTE_INSTANCE(0); -//static void uart_handler(nrfx_uart_event_t const * p_event, void* p_context); - -// 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; - - // Use Internal OSC to compatible with all boards - NRF_CLOCK->LFCLKSRC = CLOCK_LFCLKSRC_SRC_RC; - 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 - // cause cast-function-type warning - 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) -{ - return BUTTON_STATE_ACTIVE == nrf_gpio_pin_read(BUTTON_PIN); -} - -//static void uart_handler(nrfx_uart_event_t const * p_event, void* p_context) -//{ -// -//} - -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/pyboardv11/board.mk b/hw/bsp/pyboardv11/board.mk deleted file mode 100644 index a8fc2ca1e..000000000 --- a/hw/bsp/pyboardv11/board.mk +++ /dev/null @@ -1,46 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m4 \ - -mfloat-abi=hard \ - -mfpu=fpv4-sp-d16 \ - -nostdlib -nostartfiles \ - -DSTM32F405xx \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F4 - -ST_FAMILY = f4 -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F405RGTx_FLASH.ld - -SRC_C += \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f405xx.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For TinyUSB port source -VENDOR = st -CHIP_FAMILY = synopsys - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM4F - -# For flash-jlink target -JLINK_DEVICE = stm32f405rg - -# flash target using on-board stlink -flash: flash-stlink diff --git a/hw/bsp/pyboardv11/pyboardv11.c b/hw/bsp/pyboardv11/pyboardv11.c deleted file mode 100644 index 5c910484d..000000000 --- a/hw/bsp/pyboardv11/pyboardv11.c +++ /dev/null @@ -1,232 +0,0 @@ -/* - * 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 "../board.h" - -#include "stm32f4xx.h" -#include "stm32f4xx_hal_conf.h" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ - -// Blue LED is chosen because the other LEDs are connected to ST-LINK lines. -#define LED_PORT GPIOB -#define LED_PIN GPIO_PIN_4 -#define LED_STATE_ON 1 - -#define BUTTON_PORT GPIOB -#define BUTTON_PIN GPIO_PIN_3 -#define BUTTON_STATE_ACTIVE 1 - - -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D- - __HAL_RCC_GPIOB_CLK_ENABLE(); // LED, Button -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 168000000 - * HCLK(Hz) = 168000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 4 - * APB2 Prescaler = 2 - * HSE Frequency(Hz) = 12000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 336 - * PLL_P = 2 - * PLL_Q = 7 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 5 - * @param None - * @retval None - */ -static void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 336; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 7; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 - clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); -} - -void board_init(void) -{ -#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 - - SystemClock_Config(); - - // Notify runtime of frequency change. - SystemCoreClockUpdate(); - - all_rcc_clk_enable(); - - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - board_led_write(false); - - // Button - GPIO_InitStruct.Pin = BUTTON_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_PULLDOWN; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - // USB Pin Init - // PA9- VUSB, PA10- ID, PA11- DM, PA12- DP - - /* Configure DM DP Pins */ - GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure VBUS Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_9; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* This for ID line debug */ - GPIO_InitStruct.Pin = GPIO_PIN_10; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - // Enable USB OTG clock - __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - - // Enable VBUS sense (B device) via pin PA9 - USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS; - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN; -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); -} - -uint32_t board_button_read(void) -{ - return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN); -} - -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 - -void HardFault_Handler (void) -{ - asm("bkpt"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} diff --git a/hw/bsp/raytac_mdbt50q_rx/board.mk b/hw/bsp/raytac_mdbt50q_rx/board.mk deleted file mode 100644 index 2c29acfa6..000000000 --- a/hw/bsp/raytac_mdbt50q_rx/board.mk +++ /dev/null @@ -1,59 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m4 \ - -mfloat-abi=hard \ - -mfpu=fpv4-sp-d16 \ - -DNRF52840_XXAA \ - -DCFG_TUSB_MCU=OPT_MCU_NRF5X - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=undef -Wno-error=unused-parameter -Wno-error=cast-align - -# due to tusb_hal_nrf_power_event -GCCVERSION = $(firstword $(subst ., ,$(shell arm-none-eabi-gcc -dumpversion))) -ifeq ($(CMDEXE),1) -ifeq ($(shell if $(GCCVERSION) geq 8 echo 1), 1) -CFLAGS += -Wno-error=cast-function-type -endif -else -ifeq ($(shell expr $(GCCVERSION) \>= 8), 1) -CFLAGS += -Wno-error=cast-function-type -endif -endif - -# All source paths should be relative to the top level. -LD_FILE = hw/mcu/nordic/nrfx/mdk/nrf52840_xxaa.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)/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 - -# flash using jlink -flash: flash-jlink diff --git a/hw/bsp/raytac_mdbt50q_rx/raytac_mdbt50q_rx.c b/hw/bsp/raytac_mdbt50q_rx/raytac_mdbt50q_rx.c deleted file mode 100644 index 97f3cbf05..000000000 --- a/hw/bsp/raytac_mdbt50q_rx/raytac_mdbt50q_rx.c +++ /dev/null @@ -1,198 +0,0 @@ -/* - * 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 - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USBD_IRQHandler(void) -{ - tud_int_handler(0); -} - -/*------------------------------------------------------------------*/ -/* MACRO TYPEDEF CONSTANT ENUM - *------------------------------------------------------------------*/ -#define LED_PIN (32+13) // P1.13 -#define LED_STATE_ON 0 - -// Button 1 -#define BUTTON_PIN 15 // P0.15 -#define BUTTON_STATE_ACTIVE 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) -{ - // 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) -{ - return BUTTON_STATE_ACTIVE == nrf_gpio_pin_read(BUTTON_PIN); -} - -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/samd21/boards/atsamd21_xpro/board.h b/hw/bsp/samd21/boards/atsamd21_xpro/board.h new file mode 100644 index 000000000..a3e03997c --- /dev/null +++ b/hw/bsp/samd21/boards/atsamd21_xpro/board.h @@ -0,0 +1,50 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PIN (32 + 30) // PB30 +#define LED_STATE_ON 0 + +// Button +#define BUTTON_PIN (0 + 15) // PA15 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 4 +#define UART_TX_PIN 5 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/samd21/boards/atsamd21_xpro/board.mk b/hw/bsp/samd21/boards/atsamd21_xpro/board.mk new file mode 100644 index 000000000..5cd82735c --- /dev/null +++ b/hw/bsp/samd21/boards/atsamd21_xpro/board.mk @@ -0,0 +1,10 @@ +CFLAGS += -D__SAMD21J18A__ + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/samd21j18a_flash.ld + +# For flash-jlink target +JLINK_DEVICE = ATSAMD21J18 + +# flash using jlink +flash: flash-jlink diff --git a/hw/bsp/atsamd21_xpro/samd21j18a_flash.ld b/hw/bsp/samd21/boards/atsamd21_xpro/samd21j18a_flash.ld similarity index 100% rename from hw/bsp/atsamd21_xpro/samd21j18a_flash.ld rename to hw/bsp/samd21/boards/atsamd21_xpro/samd21j18a_flash.ld diff --git a/hw/bsp/mimxrt1050_evkb/board.h b/hw/bsp/samd21/boards/circuitplayground_express/board.h similarity index 78% rename from hw/bsp/mimxrt1050_evkb/board.h rename to hw/bsp/samd21/boards/circuitplayground_express/board.h index 3f660ac7d..2d7da1c0b 100644 --- a/hw/bsp/mimxrt1050_evkb/board.h +++ b/hw/bsp/samd21/boards/circuitplayground_express/board.h @@ -1,7 +1,7 @@ /* * The MIT License (MIT) * - * Copyright (c) 2019, Ha Thach (tinyusb.org) + * Copyright (c) 2020, 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 @@ -24,11 +24,27 @@ * This file is part of the TinyUSB stack. */ - #ifndef BOARD_H_ #define BOARD_H_ -// required since iMX RT10xx SDK include this file for board size -#define BOARD_FLASH_SIZE (0x4000000U) +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PIN 17 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN 28 +#define BUTTON_STATE_ACTIVE 1 + +// UART +#define UART_RX_PIN 4 +#define UART_TX_PIN 5 + +#ifdef __cplusplus + } +#endif #endif /* BOARD_H_ */ diff --git a/hw/bsp/samd21/boards/circuitplayground_express/board.mk b/hw/bsp/samd21/boards/circuitplayground_express/board.mk new file mode 100644 index 000000000..bb426cdaa --- /dev/null +++ b/hw/bsp/samd21/boards/circuitplayground_express/board.mk @@ -0,0 +1,9 @@ +CFLAGS += -D__SAMD21G18A__ + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/$(BOARD).ld + +# For flash-jlink target +JLINK_DEVICE = ATSAMD21G18 + +flash: flash-bossac diff --git a/hw/bsp/circuitplayground_express/samd21g18a_flash.ld b/hw/bsp/samd21/boards/circuitplayground_express/circuitplayground_express.ld similarity index 100% rename from hw/bsp/circuitplayground_express/samd21g18a_flash.ld rename to hw/bsp/samd21/boards/circuitplayground_express/circuitplayground_express.ld diff --git a/hw/bsp/samd21/boards/feather_m0_express/board.h b/hw/bsp/samd21/boards/feather_m0_express/board.h new file mode 100644 index 000000000..b9292b9af --- /dev/null +++ b/hw/bsp/samd21/boards/feather_m0_express/board.h @@ -0,0 +1,50 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PIN 17 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN 15 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 4 +#define UART_TX_PIN 5 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/samd21/boards/feather_m0_express/board.mk b/hw/bsp/samd21/boards/feather_m0_express/board.mk new file mode 100644 index 000000000..bb426cdaa --- /dev/null +++ b/hw/bsp/samd21/boards/feather_m0_express/board.mk @@ -0,0 +1,9 @@ +CFLAGS += -D__SAMD21G18A__ + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/$(BOARD).ld + +# For flash-jlink target +JLINK_DEVICE = ATSAMD21G18 + +flash: flash-bossac diff --git a/hw/bsp/feather_m0_express/samd21g18a_flash.ld b/hw/bsp/samd21/boards/feather_m0_express/feather_m0_express.ld similarity index 100% rename from hw/bsp/feather_m0_express/samd21g18a_flash.ld rename to hw/bsp/samd21/boards/feather_m0_express/feather_m0_express.ld diff --git a/hw/bsp/samd21/boards/itsybitsy_m0/board.h b/hw/bsp/samd21/boards/itsybitsy_m0/board.h new file mode 100644 index 000000000..177fb695e --- /dev/null +++ b/hw/bsp/samd21/boards/itsybitsy_m0/board.h @@ -0,0 +1,50 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PIN 17 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN 21 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 4 +#define UART_TX_PIN 5 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/samd21/boards/itsybitsy_m0/board.mk b/hw/bsp/samd21/boards/itsybitsy_m0/board.mk new file mode 100644 index 000000000..bb426cdaa --- /dev/null +++ b/hw/bsp/samd21/boards/itsybitsy_m0/board.mk @@ -0,0 +1,9 @@ +CFLAGS += -D__SAMD21G18A__ + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/$(BOARD).ld + +# For flash-jlink target +JLINK_DEVICE = ATSAMD21G18 + +flash: flash-bossac diff --git a/hw/bsp/itsybitsy_m0/samd21g18a_flash.ld b/hw/bsp/samd21/boards/itsybitsy_m0/itsybitsy_m0.ld similarity index 100% rename from hw/bsp/itsybitsy_m0/samd21g18a_flash.ld rename to hw/bsp/samd21/boards/itsybitsy_m0/itsybitsy_m0.ld diff --git a/hw/bsp/mimxrt1010_evk/board.h b/hw/bsp/samd21/boards/luna/board.h similarity index 81% rename from hw/bsp/mimxrt1010_evk/board.h rename to hw/bsp/samd21/boards/luna/board.h index 7e4b57297..2e0a2a60f 100644 --- a/hw/bsp/mimxrt1010_evk/board.h +++ b/hw/bsp/samd21/boards/luna/board.h @@ -1,7 +1,7 @@ /* * The MIT License (MIT) * - * Copyright (c) 2019, Ha Thach (tinyusb.org) + * Copyright (c) 2021, 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 @@ -24,13 +24,23 @@ * This file is part of the TinyUSB stack. */ - #ifndef BOARD_H_ #define BOARD_H_ -#include "fsl_device_registers.h" +#ifdef __cplusplus + extern "C" { +#endif -// required since iMX RT10xx SDK include this file for board size -#define BOARD_FLASH_SIZE (0x1000000U) +// LED +#define LED_PIN PIN_PA22 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN PIN_PB22 +#define BUTTON_STATE_ACTIVE 0 + +#ifdef __cplusplus + } +#endif #endif /* BOARD_H_ */ diff --git a/hw/bsp/samd21/boards/luna/board.mk b/hw/bsp/samd21/boards/luna/board.mk new file mode 100644 index 000000000..0feae9313 --- /dev/null +++ b/hw/bsp/samd21/boards/luna/board.mk @@ -0,0 +1,11 @@ +CFLAGS += -D__SAMD21G18A__ + +LD_FILE = $(BOARD_PATH)/samd21g18a_flash.ld + +# For flash-jlink target +JLINK_DEVICE = ATSAMD21G18 + +# flash using dfu-util +flash: $(BUILD)/$(BOARD)-firmware.bin + dfu-util -a 0 -d 1d50:615c -D $< || dfu-util -a 0 -d 16d0:05a5 -D $< + diff --git a/hw/bsp/luna/samd21g18a_flash.ld b/hw/bsp/samd21/boards/luna/samd21g18a_flash.ld similarity index 100% rename from hw/bsp/luna/samd21g18a_flash.ld rename to hw/bsp/samd21/boards/luna/samd21g18a_flash.ld diff --git a/hw/bsp/samd21/boards/metro_m0_express/board.h b/hw/bsp/samd21/boards/metro_m0_express/board.h new file mode 100644 index 000000000..b9292b9af --- /dev/null +++ b/hw/bsp/samd21/boards/metro_m0_express/board.h @@ -0,0 +1,50 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PIN 17 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN 15 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 4 +#define UART_TX_PIN 5 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/samd21/boards/metro_m0_express/board.mk b/hw/bsp/samd21/boards/metro_m0_express/board.mk new file mode 100644 index 000000000..bb426cdaa --- /dev/null +++ b/hw/bsp/samd21/boards/metro_m0_express/board.mk @@ -0,0 +1,9 @@ +CFLAGS += -D__SAMD21G18A__ + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/$(BOARD).ld + +# For flash-jlink target +JLINK_DEVICE = ATSAMD21G18 + +flash: flash-bossac diff --git a/hw/bsp/metro_m0_express/samd21g18a_flash.ld b/hw/bsp/samd21/boards/metro_m0_express/metro_m0_express.ld similarity index 100% rename from hw/bsp/metro_m0_express/samd21g18a_flash.ld rename to hw/bsp/samd21/boards/metro_m0_express/metro_m0_express.ld diff --git a/hw/bsp/samd21/boards/seeeduino_xiao/board.h b/hw/bsp/samd21/boards/seeeduino_xiao/board.h new file mode 100644 index 000000000..abededed2 --- /dev/null +++ b/hw/bsp/samd21/boards/seeeduino_xiao/board.h @@ -0,0 +1,50 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PIN 26 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN 9 // PA4 pin D1 on seed input +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 4 +#define UART_TX_PIN 5 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/samd21/boards/seeeduino_xiao/board.mk b/hw/bsp/samd21/boards/seeeduino_xiao/board.mk new file mode 100644 index 000000000..54591b3a5 --- /dev/null +++ b/hw/bsp/samd21/boards/seeeduino_xiao/board.mk @@ -0,0 +1,9 @@ +CFLAGS += -D__SAMD21G18A__ + +LD_FILE = $(BOARD_PATH)/$(BOARD).ld + +# For flash-jlink target +JLINK_DEVICE = ATSAMD21G18 + +# flash using jlink +flash: flash-jlink diff --git a/hw/bsp/seeeduino_xiao/samd21g18a_flash.ld b/hw/bsp/samd21/boards/seeeduino_xiao/seeeduino_xiao.ld similarity index 100% rename from hw/bsp/seeeduino_xiao/samd21g18a_flash.ld rename to hw/bsp/samd21/boards/seeeduino_xiao/seeeduino_xiao.ld diff --git a/hw/bsp/itsybitsy_m0/itsybitsy_m0.c b/hw/bsp/samd21/family.c similarity index 94% rename from hw/bsp/itsybitsy_m0/itsybitsy_m0.c rename to hw/bsp/samd21/family.c index 652bc6b3d..eb5b55863 100644 --- a/hw/bsp/itsybitsy_m0/itsybitsy_m0.c +++ b/hw/bsp/samd21/family.c @@ -26,6 +26,7 @@ #include "sam.h" #include "bsp/board.h" +#include "board.h" #include "hal/include/hal_gpio.h" #include "hal/include/hal_init.h" @@ -46,8 +47,6 @@ void USB_Handler(void) //--------------------------------------------------------------------+ // 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) @@ -75,11 +74,11 @@ void board_init(void) // Led init gpio_set_pin_direction(LED_PIN, GPIO_DIRECTION_OUT); - gpio_set_pin_level(LED_PIN, 0); + board_led_write(false); // Button init gpio_set_pin_direction(BUTTON_PIN, GPIO_DIRECTION_IN); - gpio_set_pin_pull_mode(BUTTON_PIN, GPIO_PULL_UP); + gpio_set_pin_pull_mode(BUTTON_PIN, BUTTON_STATE_ACTIVE ? GPIO_PULL_DOWN : GPIO_PULL_UP); #if CFG_TUSB_OS == OPT_OS_FREERTOS // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) @@ -120,13 +119,12 @@ void board_init(void) void board_led_write(bool state) { - gpio_set_pin_level(LED_PIN, state); + gpio_set_pin_level(LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); } uint32_t board_button_read(void) { - // button is active low - return gpio_get_pin_level(BUTTON_PIN) ? 0 : 1; + return BUTTON_STATE_ACTIVE == gpio_get_pin_level(BUTTON_PIN); } int board_uart_read(uint8_t* buf, int len) diff --git a/hw/bsp/itsybitsy_m0/board.mk b/hw/bsp/samd21/family.mk similarity index 85% rename from hw/bsp/itsybitsy_m0/board.mk rename to hw/bsp/samd21/family.mk index 61dc7c665..2f4d6b7ae 100644 --- a/hw/bsp/itsybitsy_m0/board.mk +++ b/hw/bsp/samd21/family.mk @@ -1,16 +1,14 @@ +include $(TOP)/$(BOARD_PATH)/board.mk + CFLAGS += \ -flto \ -mthumb \ - -mabi=aapcs-linux \ + -mabi=aapcs \ -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/asf4/samd21/gcc/gcc/startup_samd21.c \ hw/mcu/microchip/asf4/samd21/gcc/system_samd21.c \ @@ -20,6 +18,7 @@ SRC_C += \ hw/mcu/microchip/asf4/samd21/hal/src/hal_atomic.c INC += \ + $(TOP)/$(BOARD_PATH) \ $(TOP)/hw/mcu/microchip/asf4/samd21/ \ $(TOP)/hw/mcu/microchip/asf4/samd21/config \ $(TOP)/hw/mcu/microchip/asf4/samd21/include \ @@ -37,14 +36,11 @@ CHIP_FAMILY = samd # For freeRTOS port source FREERTOS_PORT = ARM_CM0 -# For flash-jlink target -JLINK_DEVICE = ATSAMD21G18 - # flash using bossac at least version 1.8 # 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 +flash-bossac: $(BUILD)/$(BOARD)-firmware.bin @:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0) $(BOSSAC) --port=$(SERIAL) -U -i --offset=0x2000 -e -w $^ -R diff --git a/hw/bsp/samd51/boards/feather_m4_express/board.h b/hw/bsp/samd51/boards/feather_m4_express/board.h new file mode 100644 index 000000000..a2b361a49 --- /dev/null +++ b/hw/bsp/samd51/boards/feather_m4_express/board.h @@ -0,0 +1,50 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PIN 23 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN 16 // D5 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 4 +#define UART_TX_PIN 5 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/samd51/boards/feather_m4_express/board.mk b/hw/bsp/samd51/boards/feather_m4_express/board.mk new file mode 100644 index 000000000..a8a98a987 --- /dev/null +++ b/hw/bsp/samd51/boards/feather_m4_express/board.mk @@ -0,0 +1,8 @@ +CFLAGS += -D__SAMD51J19A__ + +LD_FILE = $(BOARD_PATH)/$(BOARD).ld + +# For flash-jlink target +JLINK_DEVICE = ATSAMD51J19 + +flash: flash-bossac diff --git a/hw/bsp/feather_m4_express/samd51g19a_flash.ld b/hw/bsp/samd51/boards/feather_m4_express/feather_m4_express.ld similarity index 100% rename from hw/bsp/feather_m4_express/samd51g19a_flash.ld rename to hw/bsp/samd51/boards/feather_m4_express/feather_m4_express.ld diff --git a/hw/bsp/samd51/boards/itsybitsy_m4/board.h b/hw/bsp/samd51/boards/itsybitsy_m4/board.h new file mode 100644 index 000000000..a3788a79b --- /dev/null +++ b/hw/bsp/samd51/boards/itsybitsy_m4/board.h @@ -0,0 +1,50 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PIN 22 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN 18 // D5 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 4 +#define UART_TX_PIN 5 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/samd51/boards/itsybitsy_m4/board.mk b/hw/bsp/samd51/boards/itsybitsy_m4/board.mk new file mode 100644 index 000000000..57a680e91 --- /dev/null +++ b/hw/bsp/samd51/boards/itsybitsy_m4/board.mk @@ -0,0 +1,9 @@ +CFLAGS += -D__SAMD51J19A__ + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/$(BOARD).ld + +# For flash-jlink target +JLINK_DEVICE = ATSAMD51J19 + +flash: flash-bossac diff --git a/hw/bsp/itsybitsy_m4/samd51g19a_flash.ld b/hw/bsp/samd51/boards/itsybitsy_m4/itsybitsy_m4.ld similarity index 100% rename from hw/bsp/itsybitsy_m4/samd51g19a_flash.ld rename to hw/bsp/samd51/boards/itsybitsy_m4/itsybitsy_m4.ld diff --git a/hw/bsp/samd51/boards/metro_m4_express/board.h b/hw/bsp/samd51/boards/metro_m4_express/board.h new file mode 100644 index 000000000..de604bae3 --- /dev/null +++ b/hw/bsp/samd51/boards/metro_m4_express/board.h @@ -0,0 +1,50 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PIN 16 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN (32+14) // D5 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_RX_PIN 4 +#define UART_TX_PIN 5 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/samd51/boards/metro_m4_express/board.mk b/hw/bsp/samd51/boards/metro_m4_express/board.mk new file mode 100644 index 000000000..d7953cc24 --- /dev/null +++ b/hw/bsp/samd51/boards/metro_m4_express/board.mk @@ -0,0 +1,10 @@ +CFLAGS += -D__SAMD51J19A__ + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/$(BOARD).ld + +# For flash-jlink target +JLINK_DEVICE = ATSAMD51J19 + +flash: flash-bossac + diff --git a/hw/bsp/metro_m4_express/samd51g19a_flash.ld b/hw/bsp/samd51/boards/metro_m4_express/metro_m4_express.ld similarity index 100% rename from hw/bsp/metro_m4_express/samd51g19a_flash.ld rename to hw/bsp/samd51/boards/metro_m4_express/metro_m4_express.ld diff --git a/hw/bsp/feather_m4_express/feather_m4_express.c b/hw/bsp/samd51/family.c similarity index 98% rename from hw/bsp/feather_m4_express/feather_m4_express.c rename to hw/bsp/samd51/family.c index 72183c612..020e638c4 100644 --- a/hw/bsp/feather_m4_express/feather_m4_express.c +++ b/hw/bsp/samd51/family.c @@ -26,6 +26,7 @@ #include "sam.h" #include "bsp/board.h" +#include "board.h" #include "hal/include/hal_gpio.h" #include "hal/include/hal_init.h" @@ -58,8 +59,6 @@ void USB_3_Handler (void) //--------------------------------------------------------------------+ // MACRO TYPEDEF CONSTANT ENUM DECLARATION //--------------------------------------------------------------------+ -#define LED_PIN 23 -#define BUTTON_PIN 16 // pin D5 /* Referenced GCLKs, should be initialized firstly */ #define _GCLK_INIT_1ST 0xFFFFFFFF diff --git a/hw/bsp/metro_m4_express/board.mk b/hw/bsp/samd51/family.mk similarity index 85% rename from hw/bsp/metro_m4_express/board.mk rename to hw/bsp/samd51/family.mk index 6cc6a9091..097593748 100644 --- a/hw/bsp/metro_m4_express/board.mk +++ b/hw/bsp/samd51/family.mk @@ -1,19 +1,17 @@ +include $(TOP)/$(BOARD_PATH)/board.mk + CFLAGS += \ -flto \ -mthumb \ - -mabi=aapcs-linux \ + -mabi=aapcs \ -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/asf4/samd51/gcc/gcc/startup_samd51.c \ hw/mcu/microchip/asf4/samd51/gcc/system_samd51.c \ @@ -24,6 +22,7 @@ SRC_C += \ hw/mcu/microchip/asf4/samd51/hal/src/hal_atomic.c INC += \ + $(TOP)/$(BOARD_PATH) \ $(TOP)/hw/mcu/microchip/asf4/samd51/ \ $(TOP)/hw/mcu/microchip/asf4/samd51/config \ $(TOP)/hw/mcu/microchip/asf4/samd51/include \ @@ -40,14 +39,11 @@ CHIP_FAMILY = samd # For freeRTOS port source FREERTOS_PORT = ARM_CM4F -# For flash-jlink target -JLINK_DEVICE = ATSAMD51J19 - # flash using bossac at least version 1.8 # 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 +flash-bossac: $(BUILD)/$(BOARD)-firmware.bin @:$(call check_defined, SERIAL, example: SERIAL=/dev/ttyACM0) $(BOSSAC) --port=$(SERIAL) -U -i --offset=0x4000 -e -w $^ -R diff --git a/hw/bsp/seeeduino_xiao/board.mk b/hw/bsp/seeeduino_xiao/board.mk deleted file mode 100644 index c954dbc29..000000000 --- a/hw/bsp/seeeduino_xiao/board.mk +++ /dev/null @@ -1,44 +0,0 @@ -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/asf4/samd21/gcc/gcc/startup_samd21.c \ - hw/mcu/microchip/asf4/samd21/gcc/system_samd21.c \ - hw/mcu/microchip/asf4/samd21/hpl/gclk/hpl_gclk.c \ - hw/mcu/microchip/asf4/samd21/hpl/pm/hpl_pm.c \ - hw/mcu/microchip/asf4/samd21/hpl/sysctrl/hpl_sysctrl.c \ - hw/mcu/microchip/asf4/samd21/hal/src/hal_atomic.c - -INC += \ - $(TOP)/hw/mcu/microchip/asf4/samd21/ \ - $(TOP)/hw/mcu/microchip/asf4/samd21/config \ - $(TOP)/hw/mcu/microchip/asf4/samd21/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hal/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hal/utils/include \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hpl/pm/ \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hpl/port \ - $(TOP)/hw/mcu/microchip/asf4/samd21/hri \ - $(TOP)/hw/mcu/microchip/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 - -# flash using jlink -flash: flash-jlink diff --git a/hw/bsp/seeeduino_xiao/seeeduino_xiao.c b/hw/bsp/seeeduino_xiao/seeeduino_xiao.c deleted file mode 100644 index 0456228da..000000000 --- a/hw/bsp/seeeduino_xiao/seeeduino_xiao.c +++ /dev/null @@ -1,150 +0,0 @@ -/* - * 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" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USB_Handler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM DECLARATION -//--------------------------------------------------------------------+ -#define LED_PIN 26 -#define BUTTON_PIN 9 // PA4, pin D1 on seeed pinout - -/* 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); - - // Update SystemCoreClock since it is hard coded with asf4 and not correct - // Init 1ms tick timer (samd SystemCoreClock may not correct) - SystemCoreClock = CONF_CPU_FREQUENCY; - SysTick_Config(CONF_CPU_FREQUENCY / 1000); - - // 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_FREERTOS - // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) - NVIC_SetPriority(USB_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); -#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); -} - -//--------------------------------------------------------------------+ -// 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 - -void HardFault_Handler(void) { - while(1); -} diff --git a/hw/bsp/stlinkv3mini/board.mk b/hw/bsp/stlinkv3mini/board.mk deleted file mode 100644 index fb8b6b29f..000000000 --- a/hw/bsp/stlinkv3mini/board.mk +++ /dev/null @@ -1,63 +0,0 @@ -# Only OTG-HS has a connector on this board - -SPEED ?= high - -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m7 \ - -mfloat-abi=hard \ - -mfpu=fpv5-d16 \ - -nostdlib -nostartfiles \ - -DSTM32F723xx \ - -DHSE_VALUE=25000000 \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ - -DBOARD_DEVICE_RHPORT_NUM=1 - -ifeq ($(SPEED), high) - CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED - $(info "Using OTG_HS in HighSpeed mode") -else - CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED - $(info "Using OTG_HS in FullSpeed mode") -endif - -# mcu driver cause following warnings -CFLAGS += -Wno-error=shadow -Wno-error=cast-align - -ST_FAMILY = f7 -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F723xE_FLASH.ld - -SRC_C += \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc_ex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_pwr_ex.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f723xx.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For TinyUSB port source -VENDOR = st -CHIP_FAMILY = synopsys - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM7/r0p1 - -# flash target using on-board stlink -flash: flash-stlink diff --git a/hw/bsp/stlinkv3mini/stlinkv3mini.c b/hw/bsp/stlinkv3mini/stlinkv3mini.c deleted file mode 100644 index 03babcfa9..000000000 --- a/hw/bsp/stlinkv3mini/stlinkv3mini.c +++ /dev/null @@ -1,298 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2020 Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de), - * 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 "../board.h" - -#include "stm32f7xx_hal.h" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -// Despite being call USB2_OTG -// OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port -void OTG_HS_IRQHandler(void) -{ - tud_int_handler(1); -} - -// Pin configuartion with help from -// RadioOperator/CMSIS-DAP_for_STLINK-V3MINI.git -// CMSIS-DAP_for_STLINK-V3MINI/STLINK-V3MINI/Sch/STLINK-V3MINI_GPIOs.JPG - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ - -#define LED_PORT GPIOA -#define LED_PIN GPIO_PIN_10 -#define LED_STATE_ON 1 - -/* No Buttom */ - -#define UARTx USART6 -#define UART_GPIO_PORT GPIOG -#define UART_GPIO_AF GPIO_AF8_USART6 -#define UART_TX_PIN GPIO_PIN_9 -#define UART_RX_PIN GPIO_PIN_14 - -UART_HandleTypeDef UartHandle; - -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, LED - __HAL_RCC_GPIOB_CLK_ENABLE(); // OTG_HS - __HAL_RCC_GPIOD_CLK_ENABLE(); // OTG_HS ID - __HAL_RCC_GPIOG_CLK_ENABLE(); // Uart TX, RX - __HAL_RCC_USART6_CLK_ENABLE(); // Uart module -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 216000000 - * HCLK(Hz) = 216000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 4 - * APB2 Prescaler = 2 - * HSE Frequency(Hz) = 25000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 432 - * PLL_P = 2 - * PLL_Q = 9 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 7 - * The USB clock configuration from PLLSAI: - * PLLSAIP = 8 - * PLLSAIN = 384 - * PLLSAIQ = 7 - * @param None - * @retval None - */ -void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 432; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 9; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Activate the OverDrive to reach the 216 MHz Frequency */ - HAL_PWREx_EnableOverDrive(); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); -} - -void board_init(void) -{ - - - SystemClock_Config(); - all_rcc_clk_enable(); - -#if CFG_TUSB_OS == OPT_OS_NONE - // 1ms tick timer - SysTick_Config(SystemCoreClock / 1000); -#endif - - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - // Uart - GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = UART_GPIO_AF; - HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); - - UartHandle.Instance = UARTx; - UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; - UartHandle.Init.WordLength = UART_WORDLENGTH_8B; - UartHandle.Init.StopBits = UART_STOPBITS_1; - UartHandle.Init.Parity = UART_PARITY_NONE; - UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; - UartHandle.Init.Mode = UART_MODE_TX_RX; - UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; - HAL_UART_Init(&UartHandle); - -#if BOARD_DEVICE_RHPORT_NUM == 0 - /* Configure USB FS GPIOs */ - /* Configure DM DP Pins */ - GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure VBUS Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_9; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure OTG-FS ID pin */ - GPIO_InitStruct.Pin = GPIO_PIN_10; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Enable USB FS Clocks */ - __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - - // Enable VBUS sense (B device) via pin PA9 - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; - -#else - /* Configure USB HS GPIOs */ - /* Configure DM DP Pins */ - GPIO_InitStruct.Pin = (GPIO_PIN_14 | GPIO_PIN_15); - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); - - // Enable HS VBUS sense (B device) via pin PB13 - USB_OTG_HS->GCCFG |= USB_OTG_GCCFG_VBDEN; - - /* Configure OTG-HS ID pin */ - GPIO_InitStruct.Pin = GPIO_PIN_13; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); - - /* Enable PHYC Clocks */ - __HAL_RCC_OTGPHYC_CLK_ENABLE(); - - /* Enable USB HS Clocks */ - __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); - __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); - - // Enable VBUS sense (B device) via pin PA9 - USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; - - // B-peripheral session valid override enable - USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; - USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; - - // Force device mode - USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; - USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; - -#endif -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); -} - -uint32_t board_button_read(void) -{ - return 0; -} - -int board_uart_read(uint8_t* buf, int len) -{ - (void) buf; (void) len; - return 0; -} - -int board_uart_write(void const * buf, int len) -{ - HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); - return len; -} - -#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 - -void HardFault_Handler (void) -{ - asm("bkpt"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} diff --git a/hw/bsp/feather_stm32f405/STM32F405RGTx_FLASH.ld b/hw/bsp/stm32f4/boards/feather_stm32f405/STM32F405RGTx_FLASH.ld similarity index 100% rename from hw/bsp/feather_stm32f405/STM32F405RGTx_FLASH.ld rename to hw/bsp/stm32f4/boards/feather_stm32f405/STM32F405RGTx_FLASH.ld diff --git a/hw/bsp/stm32f4/boards/feather_stm32f405/board.h b/hw/bsp/stm32f4/boards/feather_stm32f405/board.h new file mode 100644 index 000000000..19d0a1ea4 --- /dev/null +++ b/hw/bsp/stm32f4/boards/feather_stm32f405/board.h @@ -0,0 +1,104 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PORT GPIOC +#define LED_PIN GPIO_PIN_1 +#define LED_STATE_ON 1 + +// Button: Pin D5 +#define BUTTON_PORT GPIOC +#define BUTTON_PIN GPIO_PIN_7 +#define BUTTON_STATE_ACTIVE 0 + +// UART +#define UART_DEV USART3 +#define UART_GPIO_PORT GPIOB +#define UART_GPIO_AF GPIO_AF7_USART3 +#define UART_TX_PIN GPIO_PIN_10 +#define UART_RX_PIN GPIO_PIN_11 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 336; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 7; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); + + // Enable clocks for LED, Button, Uart + __HAL_RCC_GPIOB_CLK_ENABLE(); + __HAL_RCC_GPIOC_CLK_ENABLE(); + __HAL_RCC_USART3_CLK_ENABLE(); +} + +static inline void board_vbus_sense_init(void) +{ + // Enable VBUS sense (B device) via pin PA9 + USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS; + USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN; +} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f4/boards/feather_stm32f405/board.mk b/hw/bsp/stm32f4/boards/feather_stm32f405/board.mk new file mode 100644 index 000000000..f78bb63fc --- /dev/null +++ b/hw/bsp/stm32f4/boards/feather_stm32f405/board.mk @@ -0,0 +1,12 @@ +CFLAGS += -DSTM32F405xx + +LD_FILE = $(BOARD_PATH)/STM32F405RGTx_FLASH.ld + +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f405xx.s + +# For flash-jlink target +JLINK_DEVICE = stm32f405rg + +# flash target ROM bootloader +flash: $(BUILD)/$(BOARD)-firmware.bin + dfu-util -R -a 0 --dfuse-address 0x08000000 -D $< diff --git a/hw/bsp/feather_stm32f405/stm32f4xx_hal_conf.h b/hw/bsp/stm32f4/boards/feather_stm32f405/stm32f4xx_hal_conf.h similarity index 100% rename from hw/bsp/feather_stm32f405/stm32f4xx_hal_conf.h rename to hw/bsp/stm32f4/boards/feather_stm32f405/stm32f4xx_hal_conf.h diff --git a/hw/bsp/pyboardv11/STM32F405RGTx_FLASH.ld b/hw/bsp/stm32f4/boards/pyboardv11/STM32F405RGTx_FLASH.ld similarity index 100% rename from hw/bsp/pyboardv11/STM32F405RGTx_FLASH.ld rename to hw/bsp/stm32f4/boards/pyboardv11/STM32F405RGTx_FLASH.ld diff --git a/hw/bsp/stm32f4/boards/pyboardv11/board.h b/hw/bsp/stm32f4/boards/pyboardv11/board.h new file mode 100644 index 000000000..685919c57 --- /dev/null +++ b/hw/bsp/stm32f4/boards/pyboardv11/board.h @@ -0,0 +1,102 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// Blue LED is chosen because the other LEDs are connected to ST-LINK lines. +#define LED_PORT GPIOB +#define LED_PIN GPIO_PIN_4 +#define LED_STATE_ON 1 + +#define BUTTON_PORT GPIOB +#define BUTTON_PIN GPIO_PIN_3 +#define BUTTON_STATE_ACTIVE 1 + +// Enable PA2 as the debug log UART +// It is not routed to the ST/Link on the Discovery board. +//#define UART_DEV USART2 +//#define UART_GPIO_PORT GPIOA +//#define UART_GPIO_AF GPIO_AF7_USART2 +//#define UART_TX_PIN GPIO_PIN_2 +//#define UART_RX_PIN GPIO_PIN_3 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 336; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 7; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); + + // Enable clocks for LED, Button, Uart + __HAL_RCC_GPIOB_CLK_ENABLE(); +} + +static inline void board_vbus_sense_init(void) +{ + // Enable VBUS sense (B device) via pin PA9 + USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS; + USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN; +} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f4/boards/pyboardv11/board.mk b/hw/bsp/stm32f4/boards/pyboardv11/board.mk new file mode 100644 index 000000000..02dcd1219 --- /dev/null +++ b/hw/bsp/stm32f4/boards/pyboardv11/board.mk @@ -0,0 +1,11 @@ +CFLAGS += -DSTM32F405xx + +LD_FILE = $(BOARD_PATH)/STM32F405RGTx_FLASH.ld + +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f405xx.s + +# For flash-jlink target +JLINK_DEVICE = stm32f405rg + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/pyboardv11/stm32f4xx_hal_conf.h b/hw/bsp/stm32f4/boards/pyboardv11/stm32f4xx_hal_conf.h similarity index 98% rename from hw/bsp/pyboardv11/stm32f4xx_hal_conf.h rename to hw/bsp/stm32f4/boards/pyboardv11/stm32f4xx_hal_conf.h index dbef20e0a..b892df3b6 100644 --- a/hw/bsp/pyboardv11/stm32f4xx_hal_conf.h +++ b/hw/bsp/stm32f4/boards/pyboardv11/stm32f4xx_hal_conf.h @@ -75,7 +75,7 @@ /* #define HAL_MMC_MODULE_ENABLED */ /* #define HAL_SPI_MODULE_ENABLED */ /* #define HAL_TIM_MODULE_ENABLED */ -/* #define HAL_UART_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED /* #define HAL_USART_MODULE_ENABLED */ /* #define HAL_IRDA_MODULE_ENABLED */ /* #define HAL_SMARTCARD_MODULE_ENABLED */ @@ -199,6 +199,8 @@ #define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ #define USE_HAL_SWPMI_REGISTER_CALLBACKS 0U /* SWPMI register callback disabled */ #define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ #define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ /* ########################## Assert Selection ############################## */ diff --git a/hw/bsp/stm32f401blackpill/STM32F401VCTx_FLASH.ld b/hw/bsp/stm32f4/boards/stm32f401blackpill/STM32F401VCTx_FLASH.ld similarity index 100% rename from hw/bsp/stm32f401blackpill/STM32F401VCTx_FLASH.ld rename to hw/bsp/stm32f4/boards/stm32f401blackpill/STM32F401VCTx_FLASH.ld diff --git a/hw/bsp/stm32f4/boards/stm32f401blackpill/board.h b/hw/bsp/stm32f4/boards/stm32f401blackpill/board.h new file mode 100644 index 000000000..570f5fcec --- /dev/null +++ b/hw/bsp/stm32f4/boards/stm32f401blackpill/board.h @@ -0,0 +1,106 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PORT GPIOC +#define LED_PIN GPIO_PIN_13 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PORT GPIOA +#define BUTTON_PIN GPIO_PIN_0 +#define BUTTON_STATE_ACTIVE 0 + +// Enable PA2 as the debug log UART +//#define UART_DEV USART2 +//#define UART_GPIO_PORT GPIOA +//#define UART_GPIO_AF GPIO_AF7_USART2 +//#define UART_TX_PIN GPIO_PIN_2 +//#define UART_RX_PIN GPIO_PIN_3 + + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 336; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; + RCC_OscInitStruct.PLL.PLLQ = 7; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2); + + // Enable clocks for LED, Button, Uart + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOC_CLK_ENABLE(); + //__HAL_RCC_USART2_CLK_ENABLE(); +} + +static inline void board_vbus_sense_init(void) +{ + // Blackpill doens't use VBUS sense (B device) explicitly disable it + USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS; + USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN; + USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN; +} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f4/boards/stm32f401blackpill/board.mk b/hw/bsp/stm32f4/boards/stm32f401blackpill/board.mk new file mode 100644 index 000000000..2d8b10318 --- /dev/null +++ b/hw/bsp/stm32f4/boards/stm32f401blackpill/board.mk @@ -0,0 +1,12 @@ +CFLAGS += -DSTM32F401xC + +LD_FILE = $(BOARD_PATH)/STM32F401VCTx_FLASH.ld + +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f401xc.s + +# For flash-jlink target +JLINK_DEVICE = stm32f401cc + +# flash target ROM bootloader +flash: $(BUILD)/$(BOARD)-firmware.bin + dfu-util -R -a 0 --dfuse-address 0x08000000 -D $< diff --git a/hw/bsp/stm32f401blackpill/stm32f4xx_hal_conf.h b/hw/bsp/stm32f4/boards/stm32f401blackpill/stm32f4xx_hal_conf.h similarity index 99% rename from hw/bsp/stm32f401blackpill/stm32f4xx_hal_conf.h rename to hw/bsp/stm32f4/boards/stm32f401blackpill/stm32f4xx_hal_conf.h index a6c88f249..2ab9a1d57 100644 --- a/hw/bsp/stm32f401blackpill/stm32f4xx_hal_conf.h +++ b/hw/bsp/stm32f4/boards/stm32f401blackpill/stm32f4xx_hal_conf.h @@ -68,7 +68,7 @@ /* #define HAL_SD_MODULE_ENABLED */ // #define HAL_SPI_MODULE_ENABLED /* #define HAL_TIM_MODULE_ENABLED */ -/* #define HAL_UART_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED /* #define HAL_USART_MODULE_ENABLED */ /* #define HAL_IRDA_MODULE_ENABLED */ /* #define HAL_SMARTCARD_MODULE_ENABLED */ diff --git a/hw/bsp/stm32f407disco/STM32F407VGTx_FLASH.ld b/hw/bsp/stm32f4/boards/stm32f407disco/STM32F407VGTx_FLASH.ld similarity index 100% rename from hw/bsp/stm32f407disco/STM32F407VGTx_FLASH.ld rename to hw/bsp/stm32f4/boards/stm32f407disco/STM32F407VGTx_FLASH.ld diff --git a/hw/bsp/stm32f4/boards/stm32f407disco/board.h b/hw/bsp/stm32f4/boards/stm32f407disco/board.h new file mode 100644 index 000000000..693e0393f --- /dev/null +++ b/hw/bsp/stm32f4/boards/stm32f407disco/board.h @@ -0,0 +1,105 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PORT GPIOD +#define LED_PIN GPIO_PIN_14 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PORT GPIOA +#define BUTTON_PIN GPIO_PIN_0 +#define BUTTON_STATE_ACTIVE 1 + +// Enable PA2 as the debug log UART +// It is not routed to the ST/Link on the Discovery board. +#define UART_DEV USART2 +#define UART_GPIO_PORT GPIOA +#define UART_GPIO_AF GPIO_AF7_USART2 +#define UART_TX_PIN GPIO_PIN_2 +#define UART_RX_PIN GPIO_PIN_3 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 336; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 7; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); + + // Enable clocks for LED, Button, Uart + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOD_CLK_ENABLE(); + __HAL_RCC_USART2_CLK_ENABLE(); +} + +static inline void board_vbus_sense_init(void) +{ + // Enable VBUS sense (B device) via pin PA9 + USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS; + USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN; +} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f4/boards/stm32f407disco/board.mk b/hw/bsp/stm32f4/boards/stm32f407disco/board.mk new file mode 100644 index 000000000..212b924b4 --- /dev/null +++ b/hw/bsp/stm32f4/boards/stm32f407disco/board.mk @@ -0,0 +1,11 @@ +CFLAGS += -DSTM32F407xx + +LD_FILE = $(BOARD_PATH)/STM32F407VGTx_FLASH.ld + +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f407xx.s + +# For flash-jlink target +JLINK_DEVICE = stm32f407vg + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32f407disco/stm32f4xx_hal_conf.h b/hw/bsp/stm32f4/boards/stm32f407disco/stm32f4xx_hal_conf.h similarity index 100% rename from hw/bsp/stm32f407disco/stm32f4xx_hal_conf.h rename to hw/bsp/stm32f4/boards/stm32f407disco/stm32f4xx_hal_conf.h diff --git a/hw/bsp/stm32f411blackpill/STM32F411CEUx_FLASH.ld b/hw/bsp/stm32f4/boards/stm32f411blackpill/STM32F411CEUx_FLASH.ld similarity index 100% rename from hw/bsp/stm32f411blackpill/STM32F411CEUx_FLASH.ld rename to hw/bsp/stm32f4/boards/stm32f411blackpill/STM32F411CEUx_FLASH.ld diff --git a/hw/bsp/stm32f4/boards/stm32f411blackpill/board.h b/hw/bsp/stm32f4/boards/stm32f411blackpill/board.h new file mode 100644 index 000000000..570f5fcec --- /dev/null +++ b/hw/bsp/stm32f4/boards/stm32f411blackpill/board.h @@ -0,0 +1,106 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PORT GPIOC +#define LED_PIN GPIO_PIN_13 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PORT GPIOA +#define BUTTON_PIN GPIO_PIN_0 +#define BUTTON_STATE_ACTIVE 0 + +// Enable PA2 as the debug log UART +//#define UART_DEV USART2 +//#define UART_GPIO_PORT GPIOA +//#define UART_GPIO_AF GPIO_AF7_USART2 +//#define UART_TX_PIN GPIO_PIN_2 +//#define UART_RX_PIN GPIO_PIN_3 + + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 336; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; + RCC_OscInitStruct.PLL.PLLQ = 7; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2); + + // Enable clocks for LED, Button, Uart + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOC_CLK_ENABLE(); + //__HAL_RCC_USART2_CLK_ENABLE(); +} + +static inline void board_vbus_sense_init(void) +{ + // Blackpill doens't use VBUS sense (B device) explicitly disable it + USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS; + USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN; + USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN; +} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f4/boards/stm32f411blackpill/board.mk b/hw/bsp/stm32f4/boards/stm32f411blackpill/board.mk new file mode 100644 index 000000000..a8287d0bc --- /dev/null +++ b/hw/bsp/stm32f4/boards/stm32f411blackpill/board.mk @@ -0,0 +1,12 @@ +CFLAGS += -DSTM32F411xE + +LD_FILE = $(BOARD_PATH)/STM32F411CEUx_FLASH.ld + +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f411xe.s + +# For flash-jlink target +JLINK_DEVICE = stm32f411ce + +# flash target ROM bootloader +flash: $(BUILD)/$(BOARD)-firmware.bin + dfu-util -R -a 0 --dfuse-address 0x08000000 -D $< diff --git a/hw/bsp/stm32f411blackpill/stm32f4xx_hal_conf.h b/hw/bsp/stm32f4/boards/stm32f411blackpill/stm32f4xx_hal_conf.h similarity index 99% rename from hw/bsp/stm32f411blackpill/stm32f4xx_hal_conf.h rename to hw/bsp/stm32f4/boards/stm32f411blackpill/stm32f4xx_hal_conf.h index a6c88f249..2ab9a1d57 100644 --- a/hw/bsp/stm32f411blackpill/stm32f4xx_hal_conf.h +++ b/hw/bsp/stm32f4/boards/stm32f411blackpill/stm32f4xx_hal_conf.h @@ -68,7 +68,7 @@ /* #define HAL_SD_MODULE_ENABLED */ // #define HAL_SPI_MODULE_ENABLED /* #define HAL_TIM_MODULE_ENABLED */ -/* #define HAL_UART_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED /* #define HAL_USART_MODULE_ENABLED */ /* #define HAL_IRDA_MODULE_ENABLED */ /* #define HAL_SMARTCARD_MODULE_ENABLED */ diff --git a/hw/bsp/stm32f411disco/STM32F411VETx_FLASH.ld b/hw/bsp/stm32f4/boards/stm32f411disco/STM32F411VETx_FLASH.ld similarity index 100% rename from hw/bsp/stm32f411disco/STM32F411VETx_FLASH.ld rename to hw/bsp/stm32f4/boards/stm32f411disco/STM32F411VETx_FLASH.ld diff --git a/hw/bsp/stm32f4/boards/stm32f411disco/board.h b/hw/bsp/stm32f4/boards/stm32f411disco/board.h new file mode 100644 index 000000000..008a94a5d --- /dev/null +++ b/hw/bsp/stm32f4/boards/stm32f411disco/board.h @@ -0,0 +1,104 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// Orange LED +#define LED_PORT GPIOD +#define LED_PIN GPIO_PIN_13 +#define LED_STATE_ON 1 + +#define BUTTON_PORT GPIOA +#define BUTTON_PIN GPIO_PIN_0 +#define BUTTON_STATE_ACTIVE 1 + +// Enable PA2 as the debug log UART +#define UART_DEV USART2 +#define UART_GPIO_PORT GPIOA +#define UART_GPIO_AF GPIO_AF7_USART2 +#define UART_TX_PIN GPIO_PIN_2 +#define UART_RX_PIN GPIO_PIN_3 + + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 336; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; + RCC_OscInitStruct.PLL.PLLQ = 7; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2); + + // Enable clocks for LED, Button, Uart + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOD_CLK_ENABLE(); + __HAL_RCC_USART2_CLK_ENABLE(); +} + +static inline void board_vbus_sense_init(void) +{ + // Enable VBUS sense (B device) via pin PA9 + USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS; + USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN; +} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f4/boards/stm32f411disco/board.mk b/hw/bsp/stm32f4/boards/stm32f411disco/board.mk new file mode 100644 index 000000000..48272acff --- /dev/null +++ b/hw/bsp/stm32f4/boards/stm32f411disco/board.mk @@ -0,0 +1,11 @@ +CFLAGS += -DSTM32F411xE + +LD_FILE = $(BOARD_PATH)/STM32F411VETx_FLASH.ld + +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f411xe.s + +# For flash-jlink target +JLINK_DEVICE = stm32f411ve + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32f411disco/stm32f4xx_hal_conf.h b/hw/bsp/stm32f4/boards/stm32f411disco/stm32f4xx_hal_conf.h similarity index 100% rename from hw/bsp/stm32f411disco/stm32f4xx_hal_conf.h rename to hw/bsp/stm32f4/boards/stm32f411disco/stm32f4xx_hal_conf.h diff --git a/hw/bsp/stm32f412disco/STM32F412ZGTx_FLASH.ld b/hw/bsp/stm32f4/boards/stm32f412disco/STM32F412ZGTx_FLASH.ld similarity index 100% rename from hw/bsp/stm32f412disco/STM32F412ZGTx_FLASH.ld rename to hw/bsp/stm32f4/boards/stm32f412disco/STM32F412ZGTx_FLASH.ld diff --git a/hw/bsp/stm32f4/boards/stm32f412disco/board.h b/hw/bsp/stm32f4/boards/stm32f412disco/board.h new file mode 100644 index 000000000..7f4a4fa15 --- /dev/null +++ b/hw/bsp/stm32f4/boards/stm32f412disco/board.h @@ -0,0 +1,118 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED +#define LED_PORT GPIOE +#define LED_PIN GPIO_PIN_2 +#define LED_STATE_ON 0 + +// Button +#define BUTTON_PORT GPIOA +#define BUTTON_PIN GPIO_PIN_0 +#define BUTTON_STATE_ACTIVE 1 + +// UART Enable PA2 as the debug log UART +#define UART_DEV USART2 +#define UART_GPIO_PORT GPIOA +#define UART_GPIO_AF GPIO_AF7_USART2 +#define UART_TX_PIN GPIO_PIN_2 +#define UART_RX_PIN GPIO_PIN_3 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the + * device is clocked below the maximum system frequency, to update the + * voltage scaling value regarding system frequency refer to product + * datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 200; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 7; + RCC_OscInitStruct.PLL.PLLR = 2; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Select PLLSAI output as USB clock source */ + PeriphClkInitStruct.PLLI2S.PLLI2SM = 8; + PeriphClkInitStruct.PLLI2S.PLLI2SQ = 4; + PeriphClkInitStruct.PLLI2S.PLLI2SN = 192; + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CK48; + PeriphClkInitStruct.Clk48ClockSelection = RCC_CK48CLKSOURCE_PLLI2SQ; + PeriphClkInitStruct.PLLI2SSelection = RCC_PLLI2SCLKSOURCE_PLLSRC; + PeriphClkInitStruct.PLLI2S.PLLI2SR = 7; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + * clocks dividers */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | + RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3); + + // Enable clocks for LED, Button, Uart + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOE_CLK_ENABLE(); + __HAL_RCC_USART2_CLK_ENABLE(); +} + +static inline void board_vbus_sense_init(void) +{ + // Enable VBUS sense (B device) via pin PA9 + USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; +} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f4/boards/stm32f412disco/board.mk b/hw/bsp/stm32f4/boards/stm32f412disco/board.mk new file mode 100644 index 000000000..50973f737 --- /dev/null +++ b/hw/bsp/stm32f4/boards/stm32f412disco/board.mk @@ -0,0 +1,11 @@ +CFLAGS += -DSTM32F412Zx + +LD_FILE = $(BOARD_PATH)/STM32F412ZGTx_FLASH.ld + +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f412zx.s + +# For flash-jlink target +JLINK_DEVICE = stm32f412zg + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32f412disco/stm32f4xx_hal_conf.h b/hw/bsp/stm32f4/boards/stm32f412disco/stm32f4xx_hal_conf.h similarity index 100% rename from hw/bsp/stm32f412disco/stm32f4xx_hal_conf.h rename to hw/bsp/stm32f4/boards/stm32f412disco/stm32f4xx_hal_conf.h diff --git a/hw/bsp/stm32f411disco/stm32f411disco.c b/hw/bsp/stm32f4/family.c similarity index 58% rename from hw/bsp/stm32f411disco/stm32f411disco.c rename to hw/bsp/stm32f4/family.c index 5d432fe23..e10b24505 100644 --- a/hw/bsp/stm32f411disco/stm32f411disco.c +++ b/hw/bsp/stm32f4/family.c @@ -24,8 +24,9 @@ * This file is part of the TinyUSB stack. */ -#include "../board.h" #include "stm32f4xx_hal.h" +#include "bsp/board.h" +#include "board.h" //--------------------------------------------------------------------+ // Forward USB interrupt events to TinyUSB IRQ Handler @@ -38,91 +39,12 @@ void OTG_FS_IRQHandler(void) //--------------------------------------------------------------------+ // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ - -// Orange LED -#define LED_PORT GPIOD -#define LED_PIN GPIO_PIN_13 -#define LED_STATE_ON 1 - -#define BUTTON_PORT GPIOA -#define BUTTON_PIN GPIO_PIN_0 -#define BUTTON_STATE_ACTIVE 1 - -// Enable PA2 as the debug log UART -#define UARTx USART2 -#define UART_GPIO_PORT GPIOA -#define UART_GPIO_AF GPIO_AF7_USART2 -#define UART_TX_PIN GPIO_PIN_2 -#define UART_RX_PIN GPIO_PIN_3 - UART_HandleTypeDef UartHandle; -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, Button - __HAL_RCC_GPIOD_CLK_ENABLE(); // LED - __HAL_RCC_USART2_CLK_ENABLE(); // Uart module -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 84000000 - * HCLK(Hz) = 84000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 2 - * APB2 Prescaler = 1 - * HSE Frequency(Hz) = 8000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 336 - * PLL_P = 4 - * PLL_Q = 7 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale2 mode - * Flash Latency(WS) = 2 - * @param None - * @retval None - */ -static void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 336; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; - RCC_OscInitStruct.PLL.PLLQ = 7; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 - clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2); -} - void board_init(void) { - SystemClock_Config(); - all_rcc_clk_enable(); + board_clock_init(); + //SystemCoreClockUpdate(); #if CFG_TUSB_OS == OPT_OS_NONE // 1ms tick timer @@ -138,7 +60,7 @@ void board_init(void) GPIO_InitStruct.Pin = LED_PIN; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); board_led_write(false); @@ -146,11 +68,35 @@ void board_init(void) // Button GPIO_InitStruct.Pin = BUTTON_PIN; GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_PULLDOWN; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; + GPIO_InitStruct.Pull = BUTTON_STATE_ACTIVE ? GPIO_PULLDOWN : GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); +#ifdef UART_DEV + // UART + GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = UART_GPIO_AF; + HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); + + UartHandle = (UART_HandleTypeDef){ + .Instance = UART_DEV, + .Init.BaudRate = CFG_BOARD_UART_BAUDRATE, + .Init.WordLength = UART_WORDLENGTH_8B, + .Init.StopBits = UART_STOPBITS_1, + .Init.Parity = UART_PARITY_NONE, + .Init.HwFlowCtl = UART_HWCONTROL_NONE, + .Init.Mode = UART_MODE_TX_RX, + .Init.OverSampling = UART_OVERSAMPLING_16 + }; + HAL_UART_Init(&UartHandle); +#endif + /* Configure USB FS GPIOs */ + __HAL_RCC_GPIOA_CLK_ENABLE(); + /* Configure USB D+ D- Pins */ GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; @@ -165,7 +111,7 @@ void board_init(void) GPIO_InitStruct.Pull = GPIO_NOPULL; HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - /* This for ID line debug */ + /* ID Pin */ GPIO_InitStruct.Pin = GPIO_PIN_10; GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; GPIO_InitStruct.Pull = GPIO_PULLUP; @@ -173,31 +119,19 @@ void board_init(void) GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = UART_GPIO_AF; - HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); - - UartHandle = (UART_HandleTypeDef){ - .Instance = UARTx, - .Init.BaudRate = CFG_BOARD_UART_BAUDRATE, - .Init.WordLength = UART_WORDLENGTH_8B, - .Init.StopBits = UART_STOPBITS_1, - .Init.Parity = UART_PARITY_NONE, - .Init.HwFlowCtl = UART_HWCONTROL_NONE, - .Init.Mode = UART_MODE_TX_RX, - .Init.OverSampling = UART_OVERSAMPLING_16 - }; - HAL_UART_Init(&UartHandle); +#ifdef STM32F412Zx + /* Configure POWER_SWITCH IO pin */ + __HAL_RCC_GPIOG_CLK_ENABLE(); + GPIO_InitStruct.Pin = GPIO_PIN_8; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_OD; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOG, &GPIO_InitStruct); +#endif // Enable USB OTG clock __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - // Enable VBUS sense (B device) via pin PA9 - USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS; - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN; + board_vbus_sense_init(); } //--------------------------------------------------------------------+ @@ -222,8 +156,13 @@ int board_uart_read(uint8_t* buf, int len) int board_uart_write(void const * buf, int len) { +#ifdef UART_DEV HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); return len; +#else + (void) buf; (void) len; (void) UartHandle; + return 0; +#endif } #if CFG_TUSB_OS == OPT_OS_NONE diff --git a/hw/bsp/stm32f412disco/board.mk b/hw/bsp/stm32f4/family.mk similarity index 81% rename from hw/bsp/stm32f412disco/board.mk rename to hw/bsp/stm32f4/family.mk index 9356f344d..89e28174f 100644 --- a/hw/bsp/stm32f412disco/board.mk +++ b/hw/bsp/stm32f4/family.mk @@ -1,3 +1,5 @@ +include $(TOP)/$(BOARD_PATH)/board.mk + CFLAGS += \ -flto \ -mthumb \ @@ -6,7 +8,6 @@ CFLAGS += \ -mfloat-abi=hard \ -mfpu=fpv4-sp-d16 \ -nostdlib -nostartfiles \ - -DSTM32F412Zx \ -DCFG_TUSB_MCU=OPT_MCU_STM32F4 # suppress warning caused by vendor mcu driver @@ -16,9 +17,6 @@ ST_FAMILY = f4 ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F412ZGTx_FLASH.ld - SRC_C += \ $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ @@ -28,10 +26,8 @@ SRC_C += \ $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c \ $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f412zx.s - INC += \ + $(TOP)/$(BOARD_PATH) \ $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ $(TOP)/$(ST_CMSIS)/Include \ $(TOP)/$(ST_HAL_DRIVER)/Inc \ @@ -44,8 +40,5 @@ CHIP_FAMILY = synopsys # For freeRTOS port source FREERTOS_PORT = ARM_CM4F -# For flash-jlink target -JLINK_DEVICE = stm32f41zx - # flash target using on-board stlink flash: flash-stlink diff --git a/hw/bsp/stm32f401blackpill/board.mk b/hw/bsp/stm32f401blackpill/board.mk deleted file mode 100644 index 522b02774..000000000 --- a/hw/bsp/stm32f401blackpill/board.mk +++ /dev/null @@ -1,47 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m4 \ - -mfloat-abi=hard \ - -mfpu=fpv4-sp-d16 \ - -nostdlib -nostartfiles \ - -DSTM32F401xC \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F4 - -ST_FAMILY = f4 -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F401VCTx_FLASH.ld - -SRC_C += \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f401xc.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For TinyUSB port source -VENDOR = st -CHIP_FAMILY = synopsys - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM4F - -# For flash-jlink target -JLINK_DEVICE = stm32f401cc - -# flash target ROM bootloader -flash: $(BUILD)/$(BOARD)-firmware.bin - dfu-util -R -a 0 --dfuse-address 0x08000000 -D $< diff --git a/hw/bsp/stm32f401blackpill/stm32f401blackpill.c b/hw/bsp/stm32f401blackpill/stm32f401blackpill.c deleted file mode 100644 index f9daa364f..000000000 --- a/hw/bsp/stm32f401blackpill/stm32f401blackpill.c +++ /dev/null @@ -1,226 +0,0 @@ -/* - * 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 "../board.h" - -#include "stm32f4xx.h" -#include "stm32f4xx_hal_conf.h" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ - -#define LED_PORT GPIOC -#define LED_PIN GPIO_PIN_13 -#define LED_STATE_ON 1 - -#define BUTTON_PORT GPIOA -#define BUTTON_PIN GPIO_PIN_0 -#define BUTTON_STATE_ACTIVE 0 - -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, Button - __HAL_RCC_GPIOC_CLK_ENABLE(); // LED -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 84000000 - * HCLK(Hz) = 84000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 2 - * APB2 Prescaler = 1 - * HSE Frequency(Hz) = 25000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 336 - * PLL_P = 4 - * PLL_Q = 7 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale2 mode - * Flash Latency(WS) = 2 - * @param None - * @retval None - */ -static void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 336; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; - RCC_OscInitStruct.PLL.PLLQ = 7; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 - clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2); -} - -void board_init(void) -{ - SystemClock_Config(); - all_rcc_clk_enable(); - -#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 - - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - board_led_write(false); - - // Button - GPIO_InitStruct.Pin = BUTTON_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = BUTTON_STATE_ACTIVE ? GPIO_PULLDOWN : GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - /* Configure USB FS GPIOs */ - /* Configure USB D+ D- Pins */ - GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure VBUS Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_9; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* This for ID line debug */ - GPIO_InitStruct.Pin = GPIO_PIN_10; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - // Enable USB OTG clock - __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - - // Blackpill doens't use VBUS sense (B device) - // explicitly disable it - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS; - USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN; - USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN; -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); -} - -uint32_t board_button_read(void) -{ - return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN); -} - -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 - -void HardFault_Handler (void) -{ - asm("bkpt"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} diff --git a/hw/bsp/stm32f407disco/board.mk b/hw/bsp/stm32f407disco/board.mk deleted file mode 100644 index 76e13af32..000000000 --- a/hw/bsp/stm32f407disco/board.mk +++ /dev/null @@ -1,50 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m4 \ - -mfloat-abi=hard \ - -mfpu=fpv4-sp-d16 \ - -nostdlib -nostartfiles \ - -DSTM32F407xx \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F4 - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=cast-align - -ST_FAMILY = f4 -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F407VGTx_FLASH.ld - -SRC_C += \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f407xx.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For TinyUSB port source -VENDOR = st -CHIP_FAMILY = synopsys - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM4F - -# For flash-jlink target -JLINK_DEVICE = stm32f407vg - -# flash target using on-board stlink -flash: flash-stlink diff --git a/hw/bsp/stm32f407disco/stm32f407disco.c b/hw/bsp/stm32f407disco/stm32f407disco.c deleted file mode 100644 index ce3b67da0..000000000 --- a/hw/bsp/stm32f407disco/stm32f407disco.c +++ /dev/null @@ -1,254 +0,0 @@ -/* - * 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 "../board.h" - -#include "stm32f4xx_hal.h" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ - -#define LED_PORT GPIOD -#define LED_PIN GPIO_PIN_14 -#define LED_STATE_ON 1 - -#define BUTTON_PORT GPIOA -#define BUTTON_PIN GPIO_PIN_0 -#define BUTTON_STATE_ACTIVE 1 - -// Enable PA2 as the debug log UART -// It is not routed to the ST/Link on the Discovery board. -#define UARTx USART2 -#define UART_GPIO_PORT GPIOA -#define UART_GPIO_AF GPIO_AF7_USART2 -#define UART_TX_PIN GPIO_PIN_2 -#define UART_RX_PIN GPIO_PIN_3 - -UART_HandleTypeDef UartHandle; - -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, Button - __HAL_RCC_GPIOD_CLK_ENABLE(); // LED - __HAL_RCC_USART2_CLK_ENABLE(); // Uart module -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 168000000 - * HCLK(Hz) = 168000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 4 - * APB2 Prescaler = 2 - * HSE Frequency(Hz) = 8000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 336 - * PLL_P = 2 - * PLL_Q = 7 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 5 - * @param None - * @retval None - */ -static void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 336; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 7; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 - clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); -} - -void board_init(void) -{ - SystemClock_Config(); - all_rcc_clk_enable(); - -#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 - - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - board_led_write(false); - - // Button - GPIO_InitStruct.Pin = BUTTON_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_PULLDOWN; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - // USB Pin Init - // PA9- VUSB, PA10- ID, PA11- DM, PA12- DP - /* Configure DM DP Pins */ - GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure VBUS Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_9; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* This for ID line debug */ - GPIO_InitStruct.Pin = GPIO_PIN_10; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = UART_GPIO_AF; - HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); - - UartHandle = (UART_HandleTypeDef){ - .Instance = UARTx, - .Init.BaudRate = CFG_BOARD_UART_BAUDRATE, - .Init.WordLength = UART_WORDLENGTH_8B, - .Init.StopBits = UART_STOPBITS_1, - .Init.Parity = UART_PARITY_NONE, - .Init.HwFlowCtl = UART_HWCONTROL_NONE, - .Init.Mode = UART_MODE_TX_RX, - .Init.OverSampling = UART_OVERSAMPLING_16 - }; - HAL_UART_Init(&UartHandle); - - // Enable USB OTG clock - __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - - // Enable VBUS sense (B device) via pin PA9 - USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS; - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN; -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); -} - -uint32_t board_button_read(void) -{ - return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - (void) buf; (void) len; - return 0; -} - -int board_uart_write(void const * buf, int len) -{ - HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); - return len; -} - -#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 - -void HardFault_Handler (void) -{ - asm("bkpt"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} diff --git a/hw/bsp/stm32f411blackpill/board.mk b/hw/bsp/stm32f411blackpill/board.mk deleted file mode 100644 index 5800331d9..000000000 --- a/hw/bsp/stm32f411blackpill/board.mk +++ /dev/null @@ -1,47 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m4 \ - -mfloat-abi=hard \ - -mfpu=fpv4-sp-d16 \ - -nostdlib -nostartfiles \ - -DSTM32F411xE \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F4 - -ST_FAMILY = f4 -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F411CEUx_FLASH.ld - -SRC_C += \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f411xe.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For TinyUSB port source -VENDOR = st -CHIP_FAMILY = synopsys - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM4F - -# For flash-jlink target -JLINK_DEVICE = stm32f411ce - -# flash target ROM bootloader -flash: $(BUILD)/$(BOARD)-firmware.bin - dfu-util -R -a 0 --dfuse-address 0x08000000 -D $< diff --git a/hw/bsp/stm32f411blackpill/stm32f411blackpill.c b/hw/bsp/stm32f411blackpill/stm32f411blackpill.c deleted file mode 100644 index af1cf70ed..000000000 --- a/hw/bsp/stm32f411blackpill/stm32f411blackpill.c +++ /dev/null @@ -1,225 +0,0 @@ -/* - * 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 "../board.h" - -#include "stm32f4xx_hal.h" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ - -#define LED_PORT GPIOC -#define LED_PIN GPIO_PIN_13 -#define LED_STATE_ON 1 - -#define BUTTON_PORT GPIOA -#define BUTTON_PIN GPIO_PIN_0 -#define BUTTON_STATE_ACTIVE 0 - -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, Button - __HAL_RCC_GPIOC_CLK_ENABLE(); // LED -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 84000000 - * HCLK(Hz) = 84000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 2 - * APB2 Prescaler = 1 - * HSE Frequency(Hz) = 25000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 336 - * PLL_P = 4 - * PLL_Q = 7 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale2 mode - * Flash Latency(WS) = 2 - * @param None - * @retval None - */ -static void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 336; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; - RCC_OscInitStruct.PLL.PLLQ = 7; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 - clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2); -} - -void board_init(void) -{ - SystemClock_Config(); - all_rcc_clk_enable(); - -#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 - - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - board_led_write(false); - - // Button - GPIO_InitStruct.Pin = BUTTON_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = BUTTON_STATE_ACTIVE ? GPIO_PULLDOWN : GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - /* Configure USB FS GPIOs */ - /* Configure USB D+ D- Pins */ - GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure VBUS Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_9; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* This for ID line debug */ - GPIO_InitStruct.Pin = GPIO_PIN_10; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - // Enable USB OTG clock - __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - - // Blackpill doens't use VBUS sense (B device) - // explicitly disable it - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS; - USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN; - USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN; -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); -} - -uint32_t board_button_read(void) -{ - return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN); -} - -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 - -void HardFault_Handler (void) -{ - asm("bkpt"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} diff --git a/hw/bsp/stm32f411disco/board.mk b/hw/bsp/stm32f411disco/board.mk deleted file mode 100644 index e13bf641e..000000000 --- a/hw/bsp/stm32f411disco/board.mk +++ /dev/null @@ -1,50 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m4 \ - -mfloat-abi=hard \ - -mfpu=fpv4-sp-d16 \ - -nostdlib -nostartfiles \ - -DSTM32F411xE \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F4 - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=cast-align - -ST_FAMILY = f4 -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F411VETx_FLASH.ld - -SRC_C += \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f411xe.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For TinyUSB port source -VENDOR = st -CHIP_FAMILY = synopsys - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM4F - -# For flash-jlink target -JLINK_DEVICE = stm32f411ve - -# flash target using on-board stlink -flash: flash-stlink diff --git a/hw/bsp/stm32f412disco/stm32f412disco.c b/hw/bsp/stm32f412disco/stm32f412disco.c deleted file mode 100644 index 669891d68..000000000 --- a/hw/bsp/stm32f412disco/stm32f412disco.c +++ /dev/null @@ -1,277 +0,0 @@ -/* - * 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 "../board.h" - -#include "stm32f4xx_hal.h" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ - -#define LED_PORT GPIOE -#define LED_PIN GPIO_PIN_2 -#define LED_STATE_ON 0 - -#define BUTTON_PORT GPIOA -#define BUTTON_PIN GPIO_PIN_0 -#define BUTTON_STATE_ACTIVE 1 - -// Enable PA2 as the debug log UART -#define UARTx USART2 -#define UART_GPIO_PORT GPIOA -#define UART_GPIO_AF GPIO_AF7_USART2 -#define UART_TX_PIN GPIO_PIN_2 -#define UART_RX_PIN GPIO_PIN_3 - -UART_HandleTypeDef UartHandle; - -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, Button - __HAL_RCC_GPIOE_CLK_ENABLE(); // LED - __HAL_RCC_USART2_CLK_ENABLE(); // Uart module -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 100000000 - * HCLK(Hz) = 100000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 2 - * APB2 Prescaler = 1 - * HSE Frequency(Hz) = 8000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 200 - * PLL_P = 2 - * PLL_Q = 7 - * PLL_R = 2 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 3 - * The USB clock configuration from PLLI2S: - * PLLI2SM = 8 - * PLLI2SN = 192 - * PLLI2SQ = 4 - * @param None - * @retval None - */ -static void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the - * device is clocked below the maximum system frequency, to update the - * voltage scaling value regarding system frequency refer to product - * datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 200; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 7; - RCC_OscInitStruct.PLL.PLLR = 2; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Select PLLSAI output as USB clock source */ - PeriphClkInitStruct.PLLI2S.PLLI2SM = 8; - PeriphClkInitStruct.PLLI2S.PLLI2SQ = 4; - PeriphClkInitStruct.PLLI2S.PLLI2SN = 192; - PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CK48; - PeriphClkInitStruct.Clk48ClockSelection = RCC_CK48CLKSOURCE_PLLI2SQ; - PeriphClkInitStruct.PLLI2SSelection = RCC_PLLI2SCLKSOURCE_PLLSRC; - PeriphClkInitStruct.PLLI2S.PLLI2SR = 7; - HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 - * clocks dividers */ - RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | - RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; - - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3); -} - -void board_init(void) -{ - SystemClock_Config(); - all_rcc_clk_enable(); - -#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 - - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - board_led_write(false); - - // Button - GPIO_InitStruct.Pin = BUTTON_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_PULLDOWN; - GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - /* Configure USB FS GPIOs */ - /* Configure USB D+ D- Pins */ - GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure VBUS Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_9; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* ID Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_10; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure POWER_SWITCH IO pin */ - __HAL_RCC_GPIOG_CLK_ENABLE(); - GPIO_InitStruct.Pin = GPIO_PIN_8; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_OD; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOG, &GPIO_InitStruct); - GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = UART_GPIO_AF; - HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); - - UartHandle = (UART_HandleTypeDef){ - .Instance = UARTx, - .Init.BaudRate = CFG_BOARD_UART_BAUDRATE, - .Init.WordLength = UART_WORDLENGTH_8B, - .Init.StopBits = UART_STOPBITS_1, - .Init.Parity = UART_PARITY_NONE, - .Init.HwFlowCtl = UART_HWCONTROL_NONE, - .Init.Mode = UART_MODE_TX_RX, - .Init.OverSampling = UART_OVERSAMPLING_16 - }; - HAL_UART_Init(&UartHandle); - - // Enable USB OTG clock - __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - - // Enable VBUS sense (B device) via pin PA9 - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); -} - -uint32_t board_button_read(void) -{ - return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - (void) buf; (void) len; - return 0; -} - -int board_uart_write(void const * buf, int len) -{ - HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); - return len; -} - -#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 - -void HardFault_Handler (void) -{ - asm("bkpt"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} diff --git a/hw/bsp/stlinkv3mini/STM32F723xE_FLASH.ld b/hw/bsp/stm32f7/boards/stlinkv3mini/STM32F723xE_FLASH.ld similarity index 100% rename from hw/bsp/stlinkv3mini/STM32F723xE_FLASH.ld rename to hw/bsp/stm32f7/boards/stlinkv3mini/STM32F723xE_FLASH.ld diff --git a/hw/bsp/stm32f7/boards/stlinkv3mini/board.h b/hw/bsp/stm32f7/boards/stlinkv3mini/board.h new file mode 100644 index 000000000..d0ef6625f --- /dev/null +++ b/hw/bsp/stm32f7/boards/stlinkv3mini/board.h @@ -0,0 +1,101 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2021, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define LED_PORT GPIOA +#define LED_PIN GPIO_PIN_10 +#define LED_STATE_ON 1 + +// No physical button is populated +#define BUTTON_PORT GPIOA +#define BUTTON_PIN GPIO_PIN_0 +#define BUTTON_STATE_ACTIVE 1 + +#define UART_DEV USART6 +#define UART_CLK_EN __HAL_RCC_USART6_CLK_ENABLE +#define UART_GPIO_AF GPIO_AF8_USART6 + +#define UART_TX_PORT GPIOG +#define UART_TX_PIN GPIO_PIN_9 + +#define UART_RX_PORT GPIOG +#define UART_RX_PIN GPIO_PIN_14 + +// VBUS Sense detection +#define OTG_FS_VBUS_SENSE 1 +#define OTG_HS_VBUS_SENSE 0 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 432; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 9; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Activate the OverDrive to reach the 216 MHz Frequency */ + HAL_PWREx_EnableOverDrive(); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); +} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f7/boards/stlinkv3mini/board.mk b/hw/bsp/stm32f7/boards/stlinkv3mini/board.mk new file mode 100644 index 000000000..a18b3231d --- /dev/null +++ b/hw/bsp/stm32f7/boards/stlinkv3mini/board.mk @@ -0,0 +1,14 @@ +# Only OTG-HS has a connector on this board +PORT ?= 1 +SPEED ?= high + +CFLAGS += \ + -DSTM32F723xx \ + -DHSE_VALUE=25000000 \ + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/STM32F723xE_FLASH.ld +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f723xx.s + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h b/hw/bsp/stm32f7/boards/stlinkv3mini/stm32f7xx_hal_conf.h similarity index 100% rename from hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h rename to hw/bsp/stm32f7/boards/stlinkv3mini/stm32f7xx_hal_conf.h diff --git a/hw/bsp/stm32f723disco/STM32F723xE_FLASH.ld b/hw/bsp/stm32f7/boards/stm32f723disco/STM32F723xE_FLASH.ld similarity index 100% rename from hw/bsp/stm32f723disco/STM32F723xE_FLASH.ld rename to hw/bsp/stm32f7/boards/stm32f723disco/STM32F723xE_FLASH.ld diff --git a/hw/bsp/stm32f7/boards/stm32f723disco/board.h b/hw/bsp/stm32f7/boards/stm32f723disco/board.h new file mode 100644 index 000000000..93d83efc6 --- /dev/null +++ b/hw/bsp/stm32f7/boards/stm32f723disco/board.h @@ -0,0 +1,105 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2021, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define LED_PORT GPIOB +#define LED_PIN GPIO_PIN_1 +#define LED_STATE_ON 1 + +#define BUTTON_PORT GPIOA +#define BUTTON_PIN GPIO_PIN_0 +#define BUTTON_STATE_ACTIVE 1 + +#define UART_DEV USART6 +#define UART_CLK_EN __HAL_RCC_USART6_CLK_ENABLE +#define UART_GPIO_AF GPIO_AF8_USART6 + +#define UART_TX_PORT GPIOC +#define UART_TX_PIN GPIO_PIN_6 + +#define UART_RX_PORT GPIOC +#define UART_RX_PIN GPIO_PIN_7 + +// VBUS Sense detection +#define OTG_FS_VBUS_SENSE 1 +#define OTG_HS_VBUS_SENSE 0 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 432; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 9; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Activate the OverDrive to reach the 216 MHz Frequency */ + HAL_PWREx_EnableOverDrive(); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); +} + +//static inline void board_vbus_sense_init(void) +//{ +// +//} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f7/boards/stm32f723disco/board.mk b/hw/bsp/stm32f7/boards/stm32f723disco/board.mk new file mode 100644 index 000000000..8f05199d0 --- /dev/null +++ b/hw/bsp/stm32f7/boards/stm32f723disco/board.mk @@ -0,0 +1,12 @@ +PORT ?= 1 +SPEED ?= high + +CFLAGS += \ + -DSTM32F723xx \ + -DHSE_VALUE=25000000 \ + +LD_FILE = $(BOARD_PATH)/STM32F723xE_FLASH.ld +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f723xx.s + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32f723disco/stm32f7xx_hal_conf.h b/hw/bsp/stm32f7/boards/stm32f723disco/stm32f7xx_hal_conf.h similarity index 100% rename from hw/bsp/stm32f723disco/stm32f7xx_hal_conf.h rename to hw/bsp/stm32f7/boards/stm32f723disco/stm32f7xx_hal_conf.h diff --git a/hw/bsp/stm32f746disco/STM32F746ZGTx_FLASH.ld b/hw/bsp/stm32f7/boards/stm32f746disco/STM32F746ZGTx_FLASH.ld similarity index 100% rename from hw/bsp/stm32f746disco/STM32F746ZGTx_FLASH.ld rename to hw/bsp/stm32f7/boards/stm32f746disco/STM32F746ZGTx_FLASH.ld diff --git a/hw/bsp/stm32f7/boards/stm32f746disco/board.h b/hw/bsp/stm32f7/boards/stm32f746disco/board.h new file mode 100644 index 000000000..ee342b9f5 --- /dev/null +++ b/hw/bsp/stm32f7/boards/stm32f746disco/board.h @@ -0,0 +1,100 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2021, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define LED_PORT GPIOI +#define LED_PIN GPIO_PIN_1 +#define LED_STATE_ON 1 + +#define BUTTON_PORT GPIOI +#define BUTTON_PIN GPIO_PIN_11 +#define BUTTON_STATE_ACTIVE 1 + +#define UART_DEV USART1 +#define UART_CLK_EN __HAL_RCC_USART1_CLK_ENABLE +#define UART_GPIO_AF GPIO_AF7_USART1 + +#define UART_TX_PORT GPIOA +#define UART_TX_PIN GPIO_PIN_9 + +#define UART_RX_PORT GPIOB +#define UART_RX_PIN GPIO_PIN_7 + +// VBUS Sense detection +#define OTG_FS_VBUS_SENSE 0 +#define OTG_HS_VBUS_SENSE 0 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 432; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 9; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Activate the OverDrive to reach the 216 MHz Frequency */ + HAL_PWREx_EnableOverDrive(); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); +} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f7/boards/stm32f746disco/board.mk b/hw/bsp/stm32f7/boards/stm32f746disco/board.mk new file mode 100644 index 000000000..2ba59f67a --- /dev/null +++ b/hw/bsp/stm32f7/boards/stm32f746disco/board.mk @@ -0,0 +1,12 @@ +PORT ?= 1 +SPEED ?= high + +CFLAGS += \ + -DSTM32F746xx \ + -DHSE_VALUE=25000000 + +LD_FILE = $(BOARD_PATH)/STM32F746ZGTx_FLASH.ld +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f746xx.s + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32f746disco/stm32f7xx_hal_conf.h b/hw/bsp/stm32f7/boards/stm32f746disco/stm32f7xx_hal_conf.h similarity index 100% rename from hw/bsp/stm32f746disco/stm32f7xx_hal_conf.h rename to hw/bsp/stm32f7/boards/stm32f746disco/stm32f7xx_hal_conf.h diff --git a/hw/bsp/stm32f746nucleo/STM32F746ZGTx_FLASH.ld b/hw/bsp/stm32f7/boards/stm32f746nucleo/STM32F746ZGTx_FLASH.ld similarity index 100% rename from hw/bsp/stm32f746nucleo/STM32F746ZGTx_FLASH.ld rename to hw/bsp/stm32f7/boards/stm32f746nucleo/STM32F746ZGTx_FLASH.ld diff --git a/hw/bsp/stm32f7/boards/stm32f746nucleo/board.h b/hw/bsp/stm32f7/boards/stm32f746nucleo/board.h new file mode 100644 index 000000000..093445ede --- /dev/null +++ b/hw/bsp/stm32f7/boards/stm32f746nucleo/board.h @@ -0,0 +1,96 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2021, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define LED_PORT GPIOB +#define LED_PIN GPIO_PIN_14 +#define LED_STATE_ON 1 + +#define BUTTON_PORT GPIOC +#define BUTTON_PIN GPIO_PIN_13 +#define BUTTON_STATE_ACTIVE 1 + +#define UART_DEV USART3 +#define UART_CLK_EN __HAL_RCC_USART3_CLK_ENABLE +#define UART_GPIO_AF GPIO_AF7_USART3 + +#define UART_TX_PORT GPIOD +#define UART_TX_PIN GPIO_PIN_8 +#define UART_RX_PORT GPIOD +#define UART_RX_PIN GPIO_PIN_9 + +// VBUS Sense detection +#define OTG_FS_VBUS_SENSE 1 +#define OTG_HS_VBUS_SENSE 0 + +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 432; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 9; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Activate the OverDrive to reach the 216 MHz Frequency */ + HAL_PWREx_EnableOverDrive(); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); +} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f7/boards/stm32f746nucleo/board.mk b/hw/bsp/stm32f7/boards/stm32f746nucleo/board.mk new file mode 100644 index 000000000..3dcf4817e --- /dev/null +++ b/hw/bsp/stm32f7/boards/stm32f746nucleo/board.mk @@ -0,0 +1,12 @@ +PORT ?= 0 +SPEED ?= full + +CFLAGS += \ + -DSTM32F746xx \ + -DHSE_VALUE=8000000 + +LD_FILE = $(BOARD_PATH)/STM32F746ZGTx_FLASH.ld +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f746xx.s + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32f746nucleo/stm32f7xx_hal_conf.h b/hw/bsp/stm32f7/boards/stm32f746nucleo/stm32f7xx_hal_conf.h similarity index 100% rename from hw/bsp/stm32f746nucleo/stm32f7xx_hal_conf.h rename to hw/bsp/stm32f7/boards/stm32f746nucleo/stm32f7xx_hal_conf.h diff --git a/hw/bsp/stm32f767nucleo/STM32F767ZITx_FLASH.ld b/hw/bsp/stm32f7/boards/stm32f767nucleo/STM32F767ZITx_FLASH.ld similarity index 100% rename from hw/bsp/stm32f767nucleo/STM32F767ZITx_FLASH.ld rename to hw/bsp/stm32f7/boards/stm32f767nucleo/STM32F767ZITx_FLASH.ld diff --git a/hw/bsp/stm32f7/boards/stm32f767nucleo/board.h b/hw/bsp/stm32f7/boards/stm32f767nucleo/board.h new file mode 100644 index 000000000..1283f2313 --- /dev/null +++ b/hw/bsp/stm32f7/boards/stm32f767nucleo/board.h @@ -0,0 +1,102 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2021, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define LED_PORT GPIOB +#define LED_PIN GPIO_PIN_14 +#define LED_STATE_ON 1 + +#define BUTTON_PORT GPIOC +#define BUTTON_PIN GPIO_PIN_13 +#define BUTTON_STATE_ACTIVE 1 + +#define UART_DEV USART3 +#define UART_CLK_EN __HAL_RCC_USART3_CLK_ENABLE +#define UART_GPIO_AF GPIO_AF7_USART3 + +#define UART_TX_PORT GPIOD +#define UART_TX_PIN GPIO_PIN_8 + +#define UART_RX_PORT GPIOD +#define UART_RX_PIN GPIO_PIN_9 + +// VBUS Sense detection +#define OTG_FS_VBUS_SENSE 1 +#define OTG_HS_VBUS_SENSE 0 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 432; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 9; + RCC_OscInitStruct.PLL.PLLR = 7; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Activate the OverDrive to reach the 216 MHz Frequency */ + HAL_PWREx_EnableOverDrive(); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); +} + + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f7/boards/stm32f767nucleo/board.mk b/hw/bsp/stm32f7/boards/stm32f767nucleo/board.mk new file mode 100644 index 000000000..2400a4ba7 --- /dev/null +++ b/hw/bsp/stm32f7/boards/stm32f767nucleo/board.mk @@ -0,0 +1,12 @@ +PORT ?= 0 +SPEED ?= full + +CFLAGS += \ + -DSTM32F767xx \ + -DHSE_VALUE=8000000 \ + +LD_FILE = $(BOARD_PATH)/STM32F767ZITx_FLASH.ld +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f767xx.s + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32f767nucleo/stm32f7xx_hal_conf.h b/hw/bsp/stm32f7/boards/stm32f767nucleo/stm32f7xx_hal_conf.h similarity index 100% rename from hw/bsp/stm32f767nucleo/stm32f7xx_hal_conf.h rename to hw/bsp/stm32f7/boards/stm32f767nucleo/stm32f7xx_hal_conf.h diff --git a/hw/bsp/stm32f769disco/STM32F769ZITx_FLASH.ld b/hw/bsp/stm32f7/boards/stm32f769disco/STM32F769ZITx_FLASH.ld similarity index 100% rename from hw/bsp/stm32f769disco/STM32F769ZITx_FLASH.ld rename to hw/bsp/stm32f7/boards/stm32f769disco/STM32F769ZITx_FLASH.ld diff --git a/hw/bsp/stm32f7/boards/stm32f769disco/board.h b/hw/bsp/stm32f7/boards/stm32f769disco/board.h new file mode 100644 index 000000000..5ec217f5f --- /dev/null +++ b/hw/bsp/stm32f7/boards/stm32f769disco/board.h @@ -0,0 +1,101 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2021, 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define LED_PORT GPIOJ +#define LED_PIN GPIO_PIN_12 +#define LED_STATE_ON 5 + +#define BUTTON_PORT GPIOA +#define BUTTON_PIN GPIO_PIN_0 +#define BUTTON_STATE_ACTIVE 1 + +#define UART_DEV USART1 +#define UART_CLK_EN __HAL_RCC_USART1_CLK_ENABLE +#define UART_GPIO_AF GPIO_AF7_USART1 + +#define UART_TX_PORT GPIOA +#define UART_TX_PIN GPIO_PIN_9 + +#define UART_RX_PORT GPIOA +#define UART_RX_PIN GPIO_PIN_10 + +// VBUS Sense detection +#define OTG_FS_VBUS_SENSE 1 +#define OTG_HS_VBUS_SENSE 0 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 432; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 9; + RCC_OscInitStruct.PLL.PLLR = 7; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Activate the OverDrive to reach the 216 MHz Frequency */ + HAL_PWREx_EnableOverDrive(); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); +} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f7/boards/stm32f769disco/board.mk b/hw/bsp/stm32f7/boards/stm32f769disco/board.mk new file mode 100644 index 000000000..45b4a78c7 --- /dev/null +++ b/hw/bsp/stm32f7/boards/stm32f769disco/board.mk @@ -0,0 +1,13 @@ +# Only OTG-HS has a connector on this board +PORT ?= 1 +SPEED ?= high + +CFLAGS += \ + -DSTM32F769xx \ + -DHSE_VALUE=25000000 \ + +LD_FILE = $(BOARD_PATH)/STM32F769ZITx_FLASH.ld +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f769xx.s + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32f769disco/stm32f7xx_hal_conf.h b/hw/bsp/stm32f7/boards/stm32f769disco/stm32f7xx_hal_conf.h similarity index 100% rename from hw/bsp/stm32f769disco/stm32f7xx_hal_conf.h rename to hw/bsp/stm32f7/boards/stm32f769disco/stm32f7xx_hal_conf.h diff --git a/hw/bsp/stm32f723disco/stm32f723disco.c b/hw/bsp/stm32f7/family.c similarity index 54% rename from hw/bsp/stm32f723disco/stm32f723disco.c rename to hw/bsp/stm32f7/family.c index eeedd2a66..1649e935f 100644 --- a/hw/bsp/stm32f723disco/stm32f723disco.c +++ b/hw/bsp/stm32f7/family.c @@ -1,7 +1,8 @@ /* * The MIT License (MIT) * - * Copyright (c) 2020 Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de), + * Copyright (c) 2019 William D. Jones (thor0505@comcast.net), + * Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de), * Ha Thach (tinyusb.org) * * Permission is hereby granted, free of charge, to any person obtaining a copy @@ -25,9 +26,9 @@ * This file is part of the TinyUSB stack. */ -#include "../board.h" - #include "stm32f7xx_hal.h" +#include "bsp/board.h" +#include "board.h" //--------------------------------------------------------------------+ // Forward USB interrupt events to TinyUSB IRQ Handler @@ -44,104 +45,30 @@ void OTG_HS_IRQHandler(void) tud_int_handler(1); } - //--------------------------------------------------------------------+ // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ -#define LED_PORT GPIOB -#define LED_PIN GPIO_PIN_1 -#define LED_STATE_ON 1 - -#define BUTTON_PORT GPIOA -#define BUTTON_PIN GPIO_PIN_0 -#define BUTTON_STATE_ACTIVE 1 - -#define UARTx USART6 -#define UART_GPIO_PORT GPIOC -#define UART_GPIO_AF GPIO_AF8_USART6 -#define UART_TX_PIN GPIO_PIN_6 -#define UART_RX_PIN GPIO_PIN_7 - UART_HandleTypeDef UartHandle; -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D- - __HAL_RCC_GPIOB_CLK_ENABLE(); // LED, OTG_HS - __HAL_RCC_GPIOC_CLK_ENABLE(); // Button - __HAL_RCC_GPIOD_CLK_ENABLE(); // Uart tx, rx - __HAL_RCC_USART6_CLK_ENABLE(); // Uart module -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 216000000 - * HCLK(Hz) = 216000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 4 - * APB2 Prescaler = 2 - * HSE Frequency(Hz) = 25000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 432 - * PLL_P = 2 - * PLL_Q = 9 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 7 - * The USB clock configuration from PLLSAI: - * PLLSAIP = 8 - * PLLSAIN = 384 - * PLLSAIQ = 7 - * @param None - * @retval None - */ -void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 432; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 9; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Activate the OverDrive to reach the 216 MHz Frequency */ - HAL_PWREx_EnableOverDrive(); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); -} - void board_init(void) { + board_clock_init(); + // Enable peripherals clocks + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOB_CLK_ENABLE(); + __HAL_RCC_GPIOC_CLK_ENABLE(); + __HAL_RCC_GPIOD_CLK_ENABLE(); + __HAL_RCC_GPIOG_CLK_ENABLE(); + __HAL_RCC_GPIOH_CLK_ENABLE(); // ULPI NXT + __HAL_RCC_GPIOI_CLK_ENABLE(); // ULPI NXT - SystemClock_Config(); - all_rcc_clk_enable(); +#ifdef __HAL_RCC_GPIOJ_CLK_ENABLE + __HAL_RCC_GPIOJ_CLK_ENABLE(); +#endif + + UART_CLK_EN(); #if CFG_TUSB_OS == OPT_OS_NONE // 1ms tick timer @@ -164,26 +91,35 @@ void board_init(void) GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - // Uart - GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; + // Uart TX + GPIO_InitStruct.Pin = UART_TX_PIN; GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Pull = GPIO_PULLUP; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; GPIO_InitStruct.Alternate = UART_GPIO_AF; - HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); + HAL_GPIO_Init(UART_TX_PORT, &GPIO_InitStruct); - UartHandle.Instance = UARTx; - UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; - UartHandle.Init.WordLength = UART_WORDLENGTH_8B; - UartHandle.Init.StopBits = UART_STOPBITS_1; - UartHandle.Init.Parity = UART_PARITY_NONE; - UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; - UartHandle.Init.Mode = UART_MODE_TX_RX; + // Uart RX + GPIO_InitStruct.Pin = UART_RX_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = UART_GPIO_AF; + HAL_GPIO_Init(UART_RX_PORT, &GPIO_InitStruct); + + UartHandle.Instance = UART_DEV; + UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; + UartHandle.Init.WordLength = UART_WORDLENGTH_8B; + UartHandle.Init.StopBits = UART_STOPBITS_1; + UartHandle.Init.Parity = UART_PARITY_NONE; + UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; + UartHandle.Init.Mode = UART_MODE_TX_RX; UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; HAL_UART_Init(&UartHandle); #if BOARD_DEVICE_RHPORT_NUM == 0 - /* Configure USB FS GPIOs */ + // OTG_FS + /* Configure DM DP Pins */ GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; @@ -192,12 +128,6 @@ void board_init(void) GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - /* Configure VBUS Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_9; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - /* Configure OTG-FS ID pin */ GPIO_InitStruct.Pin = GPIO_PIN_10; GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; @@ -208,16 +138,35 @@ void board_init(void) /* Enable USB FS Clocks */ __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); +#if OTG_FS_VBUS_SENSE + /* Configure VBUS Pin */ + GPIO_InitStruct.Pin = GPIO_PIN_9; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + // Enable VBUS sense (B device) via pin PA9 USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; +#else + // Disable VBUS sense (B device) via pin PA9 + USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; + + // B-peripheral session valid override enable + USB_OTG_FS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; + USB_OTG_FS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; +#endif #else - /* Configure USB HS GPIOs */ + // OTG_HS + + #ifdef USB_HS_PHYC + // MCU with built-in HS PHY such as F723, F733, F730 + /* Configure DM DP Pins */ - GPIO_InitStruct.Pin = (GPIO_PIN_14 | GPIO_PIN_15); - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Pin = (GPIO_PIN_14 | GPIO_PIN_15); + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); @@ -225,31 +174,84 @@ void board_init(void) USB_OTG_HS->GCCFG |= USB_OTG_GCCFG_VBDEN; /* Configure OTG-HS ID pin */ - GPIO_InitStruct.Pin = GPIO_PIN_13; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Pin = GPIO_PIN_13; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); /* Enable PHYC Clocks */ __HAL_RCC_OTGPHYC_CLK_ENABLE(); - /* Enable USB HS Clocks */ - __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); - __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); + #else + // MUC with external ULPI PHY - // Enable VBUS sense (B device) via pin PA9 + /* ULPI CLK */ + GPIO_InitStruct.Pin = GPIO_PIN_5; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* ULPI D0 */ + GPIO_InitStruct.Pin = GPIO_PIN_3; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* ULPI D1 D2 D3 D4 D5 D6 D7 */ + GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13 | GPIO_PIN_5; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /* ULPI STP */ + GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_2; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + /* NXT */ + GPIO_InitStruct.Pin = GPIO_PIN_4; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOH, &GPIO_InitStruct); + + /* ULPI DIR */ + GPIO_InitStruct.Pin = GPIO_PIN_11; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOI, &GPIO_InitStruct); + #endif // USB_HS_PHYC + + /* Enable USB HS & ULPI Clocks */ + __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); + __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); + +#if OTG_HS_VBUS_SENSE + #error OTG HS VBUS Sense enabled is not implemented +#else + // No VBUS sense USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; // B-peripheral session valid override enable USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; +#endif // Force device mode USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; -#endif +#endif // BOARD_DEVICE_RHPORT_NUM + } //--------------------------------------------------------------------+ diff --git a/hw/bsp/stm32f723disco/board.mk b/hw/bsp/stm32f7/family.mk similarity index 82% rename from hw/bsp/stm32f723disco/board.mk rename to hw/bsp/stm32f7/family.mk index b784c3742..b5f58cf93 100644 --- a/hw/bsp/stm32f723disco/board.mk +++ b/hw/bsp/stm32f7/family.mk @@ -1,5 +1,4 @@ -PORT ?= 1 -SPEED ?= high +include $(TOP)/$(BOARD_PATH)/board.mk CFLAGS += \ -flto \ @@ -9,8 +8,6 @@ CFLAGS += \ -mfloat-abi=hard \ -mfpu=fpv5-d16 \ -nostdlib -nostartfiles \ - -DSTM32F723xx \ - -DHSE_VALUE=25000000 \ -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ -DBOARD_DEVICE_RHPORT_NUM=$(PORT) @@ -33,9 +30,6 @@ ST_FAMILY = f7 ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F723xE_FLASH.ld - SRC_C += \ $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ @@ -46,10 +40,8 @@ SRC_C += \ $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c \ $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_pwr_ex.c -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f723xx.s - INC += \ + $(TOP)/$(BOARD_PATH) \ $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ $(TOP)/$(ST_CMSIS)/Include \ $(TOP)/$(ST_HAL_DRIVER)/Inc \ @@ -61,6 +53,3 @@ CHIP_FAMILY = synopsys # For freeRTOS port source FREERTOS_PORT = ARM_CM7/r0p1 - -# flash target using on-board stlink -flash: flash-stlink diff --git a/hw/bsp/stm32f746disco/board.mk b/hw/bsp/stm32f746disco/board.mk deleted file mode 100644 index e02dbc3f5..000000000 --- a/hw/bsp/stm32f746disco/board.mk +++ /dev/null @@ -1,66 +0,0 @@ -PORT ?= 0 -SPEED ?= high - -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m7 \ - -mfloat-abi=hard \ - -mfpu=fpv5-d16 \ - -nostdlib -nostartfiles \ - -DSTM32F746xx \ - -DHSE_VALUE=25000000 \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ - -DBOARD_DEVICE_RHPORT_NUM=$(PORT) - -ifeq ($(PORT), 1) - ifeq ($(SPEED), high) - CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED - $(info "Using OTG_HS in HighSpeed mode") - else - CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED - $(info "Using OTG_HS in FullSpeed mode") - endif -else - $(info "Using OTG_FS") -endif - -# mcu driver cause following warnings -CFLAGS += -Wno-error=shadow -Wno-error=cast-align - -ST_FAMILY = f7 -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F746ZGTx_FLASH.ld - -SRC_C += \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc_ex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_pwr_ex.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f746xx.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For TinyUSB port source -VENDOR = st -CHIP_FAMILY = synopsys - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM7/r0p1 - -# flash target using on-board stlink -flash: flash-stlink diff --git a/hw/bsp/stm32f746disco/stm32f746disco.c b/hw/bsp/stm32f746disco/stm32f746disco.c deleted file mode 100644 index c90182fcf..000000000 --- a/hw/bsp/stm32f746disco/stm32f746disco.c +++ /dev/null @@ -1,353 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2020 Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de), - * 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 "../board.h" - -#include "stm32f7xx_hal.h" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ - -// Despite being call USB2_OTG -// OTG_FS is marked as RHPort0 by TinyUSB to be consistent across stm32 port -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -// Despite being call USB2_OTG -// OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port -void OTG_HS_IRQHandler(void) -{ - tud_int_handler(1); -} - - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ - -#define LED_PORT GPIOI -#define LED_PIN GPIO_PIN_1 -#define LED_STATE_ON 1 - -#define BUTTON_PORT GPIOI -#define BUTTON_PIN GPIO_PIN_11 -#define BUTTON_STATE_ACTIVE 1 - -#define UARTx USART1 -#define UART_TX_GPIO_PORT GPIOA -#define UART_RX_GPIO_PORT GPIOB -#define UART_TX_GPIO_AF GPIO_AF7_USART1 -#define UART_RX_GPIO_AF GPIO_AF7_USART1 -#define UART_TX_PIN GPIO_PIN_9 -#define UART_RX_PIN GPIO_PIN_7 - -UART_HandleTypeDef UartHandle; - -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D- - __HAL_RCC_GPIOB_CLK_ENABLE(); // Uart rx - __HAL_RCC_GPIOI_CLK_ENABLE(); // Button - __HAL_RCC_USART1_CLK_ENABLE(); // Uart module -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 216000000 - * HCLK(Hz) = 216000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 4 - * APB2 Prescaler = 2 - * HSE Frequency(Hz) = 25000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 432 - * PLL_P = 2 - * PLL_Q = 9 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 7 - * The USB clock configuration from PLLSAI: - * PLLSAIP = 8 - * PLLSAIN = 384 - * PLLSAIQ = 7 - * @param None - * @retval None - */ -void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 432; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 9; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Activate the OverDrive to reach the 216 MHz Frequency */ - HAL_PWREx_EnableOverDrive(); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); -} - -void board_init(void) -{ - - - SystemClock_Config(); - all_rcc_clk_enable(); - -#if CFG_TUSB_OS == OPT_OS_NONE - // 1ms tick timer - SysTick_Config(SystemCoreClock / 1000); -#endif - - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - // Button - GPIO_InitStruct.Pin = BUTTON_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - // Uart TX - GPIO_InitStruct.Pin = UART_TX_PIN ; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = UART_TX_GPIO_AF; - HAL_GPIO_Init(UART_TX_GPIO_PORT, &GPIO_InitStruct); - - // Uart RX - GPIO_InitStruct.Pin = UART_RX_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = UART_RX_GPIO_AF; - HAL_GPIO_Init(UART_RX_GPIO_PORT, &GPIO_InitStruct); - - UartHandle.Instance = UARTx; - UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; - UartHandle.Init.WordLength = UART_WORDLENGTH_8B; - UartHandle.Init.StopBits = UART_STOPBITS_1; - UartHandle.Init.Parity = UART_PARITY_NONE; - UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; - UartHandle.Init.Mode = UART_MODE_TX_RX; - UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; - HAL_UART_Init(&UartHandle); - -#if BOARD_DEVICE_RHPORT_NUM == 0 - // Despite being call USB2_OTG - // OTG_FS is marked as RHPort0 by TinyUSB to be consistent across stm32 port - // PA9 VUSB, PA10 ID, PA11 DM, PA12 DP - - /* Configure USB FS GPIOs */ - /* Configure DM DP Pins */ - GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure VBUS Pin collides with USART TX*/ -// GPIO_InitStruct.Pin = GPIO_PIN_9; -// GPIO_InitStruct.Mode = GPIO_MODE_INPUT; -// GPIO_InitStruct.Pull = GPIO_NOPULL; -// HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure OTG-FS ID pin */ - GPIO_InitStruct.Pin = GPIO_PIN_10; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Enable USB FS Clocks */ - __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - - // Enable VBUS sense (B device) via pin PA9 -// USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; -#define DEVICE_BASE (USB_OTG_DeviceTypeDef *) (USB_OTG_FS_PERIPH_BASE + USB_OTG_DEVICE_BASE) - USB_OTG_DeviceTypeDef * dev = DEVICE_BASE; - dev->DCTL |= USB_OTG_DCTL_SDIS; - - /* Deactivate VBUS Sensing B */ - USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; - - /* B-peripheral session valid override enable */ - USB_OTG_FS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; - USB_OTG_FS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; -#elif BOARD_DEVICE_RHPORT_NUM == 1 - // Despite being call USB2_OTG - // OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port - __GPIOA_CLK_ENABLE(); - __GPIOB_CLK_ENABLE(); - __GPIOC_CLK_ENABLE(); - __GPIOH_CLK_ENABLE(); - - /* ULPI CK */ - GPIO_InitStruct.Pin = GPIO_PIN_5; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* ULPI D0 */ - GPIO_InitStruct.Pin = GPIO_PIN_3; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* ULPI D1 D2 D3 D4 D5 D6 D7 */ - GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13 | GPIO_PIN_5; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); - - /* ULPI STP DIR */ - GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_2; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - - /* NXT */ - GPIO_InitStruct.Pin = GPIO_PIN_4; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOH, &GPIO_InitStruct); - - // Enable ULPI clock - __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); - - /* Enable USB HS Clocks */ - __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); - - // No VBUS sense - USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; - - // B-peripheral session valid override enable - USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; - USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; - - // Force device mode - USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; - USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; - -#endif // rhport = 1 -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); -} - -uint32_t board_button_read(void) -{ - return HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - (void) buf; (void) len; - return 0; -} - -int board_uart_write(void const * buf, int len) -{ - HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); - return len; -} - -#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 - -void HardFault_Handler (void) -{ - asm("bkpt"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} diff --git a/hw/bsp/stm32f746nucleo/board.mk b/hw/bsp/stm32f746nucleo/board.mk deleted file mode 100644 index e7b240240..000000000 --- a/hw/bsp/stm32f746nucleo/board.mk +++ /dev/null @@ -1,49 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m7 \ - -mfloat-abi=hard \ - -mfpu=fpv5-d16 \ - -nostdlib -nostartfiles \ - -DSTM32F746xx \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F7 - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=cast-align -Wno-error=shadow - -ST_FAMILY = f7 -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F746ZGTx_FLASH.ld - -SRC_C += \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc_ex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_pwr_ex.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f746xx.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For TinyUSB port source -VENDOR = st -CHIP_FAMILY = synopsys - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM7/r0p1 - -# flash target using on-board stlink -flash: flash-stlink diff --git a/hw/bsp/stm32f746nucleo/stm32f746nucleo.c b/hw/bsp/stm32f746nucleo/stm32f746nucleo.c deleted file mode 100644 index 8e0cb78e3..000000000 --- a/hw/bsp/stm32f746nucleo/stm32f746nucleo.c +++ /dev/null @@ -1,255 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2019 William D. Jones (thor0505@comcast.net), - * 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 "../board.h" - -#include "stm32f7xx_hal.h" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ - -#define LED_PORT GPIOB -#define LED_PIN GPIO_PIN_14 -#define LED_STATE_ON 1 - -#define BUTTON_PORT GPIOC -#define BUTTON_PIN GPIO_PIN_13 -#define BUTTON_STATE_ACTIVE 1 - -#define UARTx USART3 -#define UART_GPIO_PORT GPIOD -#define UART_GPIO_AF GPIO_AF7_USART3 -#define UART_TX_PIN GPIO_PIN_8 -#define UART_RX_PIN GPIO_PIN_9 - -UART_HandleTypeDef UartHandle; - -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D- - __HAL_RCC_GPIOB_CLK_ENABLE(); // LED - __HAL_RCC_GPIOC_CLK_ENABLE(); // Button - __HAL_RCC_GPIOD_CLK_ENABLE(); // Uart tx, rx - __HAL_RCC_USART3_CLK_ENABLE(); // Uart module -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 216000000 - * HCLK(Hz) = 216000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 4 - * APB2 Prescaler = 2 - * HSE Frequency(Hz) = 8000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 432 - * PLL_P = 2 - * PLL_Q = 9 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 7 - * The USB clock configuration from PLLSAI: - * PLLSAIP = 8 - * PLLSAIN = 384 - * PLLSAIQ = 7 - * @param None - * @retval None - */ -void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 432; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 9; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Activate the OverDrive to reach the 216 MHz Frequency */ - HAL_PWREx_EnableOverDrive(); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); -} - -void board_init(void) -{ - - - SystemClock_Config(); - all_rcc_clk_enable(); - -#if CFG_TUSB_OS == OPT_OS_NONE - // 1ms tick timer - SysTick_Config(SystemCoreClock / 1000); -#endif - - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - // Button - GPIO_InitStruct.Pin = BUTTON_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - // Uart - GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Alternate = UART_GPIO_AF; - HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); - - UartHandle.Instance = UARTx; - UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; - UartHandle.Init.WordLength = UART_WORDLENGTH_8B; - UartHandle.Init.StopBits = UART_STOPBITS_1; - UartHandle.Init.Parity = UART_PARITY_NONE; - UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; - UartHandle.Init.Mode = UART_MODE_TX_RX; - UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; - HAL_UART_Init(&UartHandle); - - /* Configure USB FS GPIOs */ - /* Configure DM DP Pins */ - GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure VBUS Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_9; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure ID pin */ - GPIO_InitStruct.Pin = GPIO_PIN_10; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Enable USB FS Clocks */ - __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - - // Enable VBUS sense (B device) via pin PA9 - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); -} - -uint32_t board_button_read(void) -{ - return HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - (void) buf; (void) len; - return 0; -} - -int board_uart_write(void const * buf, int len) -{ - HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); - return len; -} - -#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 - -void HardFault_Handler (void) -{ - asm("bkpt"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} diff --git a/hw/bsp/stm32f767nucleo/board.mk b/hw/bsp/stm32f767nucleo/board.mk deleted file mode 100644 index 9a6bada05..000000000 --- a/hw/bsp/stm32f767nucleo/board.mk +++ /dev/null @@ -1,49 +0,0 @@ -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m7 \ - -mfloat-abi=hard \ - -mfpu=fpv5-d16 \ - -nostdlib -nostartfiles \ - -DSTM32F767xx \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F7 - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=cast-align -Wno-error=shadow - -ST_FAMILY = f7 -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F767ZITx_FLASH.ld - -SRC_C += \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc_ex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_pwr_ex.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f767xx.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For TinyUSB port source -VENDOR = st -CHIP_FAMILY = synopsys - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM7/r0p1 - -# flash target using on-board stlink -flash: flash-stlink diff --git a/hw/bsp/stm32f767nucleo/stm32f767nucleo.c b/hw/bsp/stm32f767nucleo/stm32f767nucleo.c deleted file mode 100644 index 8328c361a..000000000 --- a/hw/bsp/stm32f767nucleo/stm32f767nucleo.c +++ /dev/null @@ -1,257 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2019 William D. Jones (thor0505@comcast.net), - * 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 "../board.h" - -#include "stm32f7xx_hal.h" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ - -#define LED_PORT GPIOB -#define LED_PIN GPIO_PIN_14 -#define LED_STATE_ON 1 - -#define BUTTON_PORT GPIOC -#define BUTTON_PIN GPIO_PIN_13 -#define BUTTON_STATE_ACTIVE 1 - -#define UARTx USART3 -#define UART_GPIO_PORT GPIOD -#define UART_GPIO_AF GPIO_AF7_USART3 -#define UART_TX_PIN GPIO_PIN_8 -#define UART_RX_PIN GPIO_PIN_9 - -UART_HandleTypeDef UartHandle; - -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D- - __HAL_RCC_GPIOB_CLK_ENABLE(); // LED - __HAL_RCC_GPIOC_CLK_ENABLE(); // Button - __HAL_RCC_GPIOD_CLK_ENABLE(); // Uart tx, rx - __HAL_RCC_USART3_CLK_ENABLE(); // Uart module -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 216000000 - * HCLK(Hz) = 216000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 4 - * APB2 Prescaler = 2 - * HSE Frequency(Hz) = 8000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 432 - * PLL_P = 2 - * PLL_Q = 9 - * PLL_R = 7 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 7 - * The USB clock configuration from PLLSAI: - * PLLSAIP = 8 - * PLLSAIN = 384 - * PLLSAIQ = 7 - * @param None - * @retval None - */ -void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 432; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 9; - RCC_OscInitStruct.PLL.PLLR = 7; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Activate the OverDrive to reach the 216 MHz Frequency */ - HAL_PWREx_EnableOverDrive(); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); -} - -void board_init(void) -{ - - - SystemClock_Config(); - all_rcc_clk_enable(); - -#if CFG_TUSB_OS == OPT_OS_NONE - // 1ms tick timer - SysTick_Config(SystemCoreClock / 1000); -#endif - - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - // Button - GPIO_InitStruct.Pin = BUTTON_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - // Uart - GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Alternate = UART_GPIO_AF; - HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); - - UartHandle.Instance = UARTx; - UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; - UartHandle.Init.WordLength = UART_WORDLENGTH_8B; - UartHandle.Init.StopBits = UART_STOPBITS_1; - UartHandle.Init.Parity = UART_PARITY_NONE; - UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; - UartHandle.Init.Mode = UART_MODE_TX_RX; - UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; - HAL_UART_Init(&UartHandle); - - /* Configure USB FS GPIOs */ - /* Configure DM DP Pins */ - GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure VBUS Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_9; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure ID pin */ - GPIO_InitStruct.Pin = GPIO_PIN_10; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Enable USB FS Clocks */ - __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - - // Enable VBUS sense (B device) via pin PA9 - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); -} - -uint32_t board_button_read(void) -{ - return HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - (void) buf; (void) len; - return 0; -} - -int board_uart_write(void const * buf, int len) -{ - HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); - return len; -} - -#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 - -void HardFault_Handler (void) -{ - asm("bkpt"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} diff --git a/hw/bsp/stm32f769disco/board.mk b/hw/bsp/stm32f769disco/board.mk deleted file mode 100644 index a963b905b..000000000 --- a/hw/bsp/stm32f769disco/board.mk +++ /dev/null @@ -1,63 +0,0 @@ -# Only OTG-HS has a connector on this board - -SPEED ?= high - -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m7 \ - -mfloat-abi=hard \ - -mfpu=fpv5-d16 \ - -nostdlib -nostartfiles \ - -DSTM32F769xx \ - -DHSE_VALUE=25000000 \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ - -DBOARD_DEVICE_RHPORT_NUM=1 \ - -ifeq ($(SPEED), high) - CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED - $(info "Using OTG_HS in HighSpeed mode") -else - CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED - $(info "Using OTG_HS in FullSpeed mode") -endif - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=cast-align -Wno-error=shadow - -ST_FAMILY = f7 -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F769ZITx_FLASH.ld - -SRC_C += \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc_ex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_pwr_ex.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f769xx.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For TinyUSB port source -VENDOR = st -CHIP_FAMILY = synopsys - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM7/r0p1 - -# flash target using on-board stlink -flash: flash-stlink diff --git a/hw/bsp/stm32f769disco/stm32f769disco.c b/hw/bsp/stm32f769disco/stm32f769disco.c deleted file mode 100644 index 2664fe0e0..000000000 --- a/hw/bsp/stm32f769disco/stm32f769disco.c +++ /dev/null @@ -1,297 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2020 Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de), - * 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 "../board.h" - -#include "stm32f7xx_hal.h" - -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void OTG_HS_IRQHandler(void) -{ - tud_int_handler(1); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ - -#define LED_PORT GPIOJ -#define LED_PIN GPIO_PIN_12 -#define LED_STATE_ON 5 - -#define BUTTON_PORT GPIOA -#define BUTTON_PIN GPIO_PIN_0 -#define BUTTON_STATE_ACTIVE 1 - -#define UARTx USART1 -#define UART_GPIO_PORT GPIOA -#define UART_GPIO_AF GPIO_AF7_USART1 -#define UART_TX_PIN GPIO_PIN_9 -#define UART_RX_PIN GPIO_PIN_10 - -UART_HandleTypeDef UartHandle; - -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // Button, UART, ULPI CLK|D0 - __HAL_RCC_GPIOB_CLK_ENABLE(); // ULPI D1-7 - __HAL_RCC_GPIOC_CLK_ENABLE(); // ULPI STP - __HAL_RCC_GPIOH_CLK_ENABLE(); // ULPI NXT - __HAL_RCC_GPIOI_CLK_ENABLE(); // ULPI NXT - __HAL_RCC_GPIOJ_CLK_ENABLE(); // LED - __HAL_RCC_USART1_CLK_ENABLE(); // Uart module -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 216000000 - * HCLK(Hz) = 216000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 4 - * APB2 Prescaler = 2 - * HSE Frequency(Hz) = 25000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 432 - * PLL_P = 2 - * PLL_Q = 9 - * PLL_R = 7 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 7 - * The USB clock configuration from PLLSAI: - * PLLSAIP = 8 - * PLLSAIN = 384 - * PLLSAIQ = 7 - * @param None - * @retval None - */ -void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 432; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 9; - RCC_OscInitStruct.PLL.PLLR = 7; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Activate the OverDrive to reach the 216 MHz Frequency */ - HAL_PWREx_EnableOverDrive(); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); -} - -void board_init(void) -{ - SystemClock_Config(); - all_rcc_clk_enable(); - -#if CFG_TUSB_OS == OPT_OS_NONE - // 1ms tick timer - SysTick_Config(SystemCoreClock / 1000); -#endif - - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - // Button - GPIO_InitStruct.Pin = BUTTON_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - // Uart - GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Alternate = UART_GPIO_AF; - HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); - - UartHandle.Instance = UARTx; - UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; - UartHandle.Init.WordLength = UART_WORDLENGTH_8B; - UartHandle.Init.StopBits = UART_STOPBITS_1; - UartHandle.Init.Parity = UART_PARITY_NONE; - UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; - UartHandle.Init.Mode = UART_MODE_TX_RX; - UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; - HAL_UART_Init(&UartHandle); - - /* Configure USB HS GPIOs */ - /* ULPI CLK */ - GPIO_InitStruct.Pin = GPIO_PIN_5; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* D0 */ - GPIO_InitStruct.Pin = GPIO_PIN_3; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* D1 D2 D3 D4 D5 D6 D7 */ - GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13 | GPIO_PIN_5; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); - - /* STP */ - GPIO_InitStruct.Pin = GPIO_PIN_0; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - - /* NXT */ - GPIO_InitStruct.Pin = GPIO_PIN_4; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOH, &GPIO_InitStruct); - - /* DIR */ - GPIO_InitStruct.Pin = GPIO_PIN_11; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOI, &GPIO_InitStruct); - - // Enable ULPI clock - __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); - - /* Enable USB HS Clocks */ - __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); - - // No VBUS sense - USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; - - // B-peripheral session valid override enable - USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; - USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; - - // Force device mode - USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; - USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; - -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); -} - -uint32_t board_button_read(void) -{ - return HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - (void) buf; (void) len; - return 0; -} - -int board_uart_write(void const * buf, int len) -{ - HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); - return len; -} - -#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 - -void HardFault_Handler (void) -{ - asm("bkpt"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} diff --git a/hw/bsp/teensy_40/board.mk b/hw/bsp/teensy_40/board.mk deleted file mode 100644 index e49f13a1f..000000000 --- a/hw/bsp/teensy_40/board.mk +++ /dev/null @@ -1,52 +0,0 @@ -CFLAGS += \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m7 \ - -mfloat-abi=hard \ - -mfpu=fpv5-d16 \ - -D__ARMVFP__=0 -D__ARMFPV5__=0\ - -DCPU_MIMXRT1062DVL6A \ - -DXIP_EXTERNAL_FLASH=1 \ - -DXIP_BOOT_HEADER_ENABLE=1 \ - -DCFG_TUSB_MCU=OPT_MCU_MIMXRT10XX - -# mcu driver cause following warnings -CFLAGS += -Wno-error=unused-parameter - -MCU_DIR = hw/mcu/nxp/sdk/devices/MIMXRT1062 - -# All source paths should be relative to the top level. -LD_FILE = $(MCU_DIR)/gcc/MIMXRT1062xxxxx_flexspi_nor.ld - -SRC_C += \ - $(MCU_DIR)/system_MIMXRT1062.c \ - $(MCU_DIR)/xip/fsl_flexspi_nor_boot.c \ - $(MCU_DIR)/project_template/clock_config.c \ - $(MCU_DIR)/drivers/fsl_clock.c \ - $(MCU_DIR)/drivers/fsl_gpio.c \ - $(MCU_DIR)/drivers/fsl_common.c \ - $(MCU_DIR)/drivers/fsl_lpuart.c - -INC += \ - $(TOP)/hw/bsp/$(BOARD) \ - $(TOP)/$(MCU_DIR)/../../CMSIS/Include \ - $(TOP)/$(MCU_DIR) \ - $(TOP)/$(MCU_DIR)/drivers \ - $(TOP)/$(MCU_DIR)/project_template \ - -SRC_S += $(MCU_DIR)/gcc/startup_MIMXRT1062.S - -# For TinyUSB port source -VENDOR = nxp -CHIP_FAMILY = transdimension - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM7/r0p1 - -# For flash-jlink target -JLINK_DEVICE = MIMXRT1062xxx6A - -# flash by using teensy_loader_cli https://github.com/PaulStoffregen/teensy_loader_cli -# Make sure it is in your PATH -flash: $(BUILD)/$(BOARD)-firmware.hex - teensy_loader_cli --mcu=imxrt1062 -v -w $< diff --git a/hw/bsp/teensy_40/teensy40.c b/hw/bsp/teensy_40/teensy40.c deleted file mode 100644 index 85501df11..000000000 --- a/hw/bsp/teensy_40/teensy40.c +++ /dev/null @@ -1,186 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2018, hathach (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 "../board.h" -#include "fsl_device_registers.h" -#include "fsl_gpio.h" -#include "fsl_iomuxc.h" -#include "fsl_clock.h" -#include "fsl_lpuart.h" - -#include "clock_config.h" - -#define LED_PINMUX IOMUXC_GPIO_B0_03_GPIO2_IO03 // D13 -#define LED_PORT GPIO2 -#define LED_PIN 3 -#define LED_STATE_ON 0 - -// no button -#define BUTTON_PINMUX IOMUXC_GPIO_B0_01_GPIO2_IO01 // D12 -#define BUTTON_PORT GPIO2 -#define BUTTON_PIN 1 -#define BUTTON_STATE_ACTIVE 0 - -// UART -#define UART_PORT LPUART6 -#define UART_RX_PINMUX IOMUXC_GPIO_AD_B0_03_LPUART6_RX // D0 -#define UART_TX_PINMUX IOMUXC_GPIO_AD_B0_02_LPUART6_TX // D1 - -// needed by fsl_flexspi_nor_boot -const uint8_t dcd_data[] = { 0x00 }; - -void board_init(void) -{ - // Init clock - BOARD_BootClockRUN(); - SystemCoreClockUpdate(); - - // Enable IOCON clock - CLOCK_EnableClock(kCLOCK_Iomuxc); - -#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 - - // LED - IOMUXC_SetPinMux( LED_PINMUX, 0U); - IOMUXC_SetPinConfig( LED_PINMUX, 0x10B0U); - - gpio_pin_config_t led_config = { kGPIO_DigitalOutput, 0, kGPIO_NoIntmode }; - GPIO_PinInit(LED_PORT, LED_PIN, &led_config); - board_led_write(true); - - // Button - IOMUXC_SetPinMux( BUTTON_PINMUX, 0U); - IOMUXC_SetPinConfig(BUTTON_PINMUX, 0x01B0A0U); - gpio_pin_config_t button_config = { kGPIO_DigitalInput, 0, kGPIO_NoIntmode }; - GPIO_PinInit(BUTTON_PORT, BUTTON_PIN, &button_config); - - // UART - IOMUXC_SetPinMux( UART_TX_PINMUX, 0U); - IOMUXC_SetPinMux( UART_RX_PINMUX, 0U); - IOMUXC_SetPinConfig( UART_TX_PINMUX, 0x10B0u); - IOMUXC_SetPinConfig( UART_RX_PINMUX, 0x10B0u); - - lpuart_config_t uart_config; - LPUART_GetDefaultConfig(&uart_config); - uart_config.baudRate_Bps = CFG_BOARD_UART_BAUDRATE; - uart_config.enableTx = true; - uart_config.enableRx = true; - LPUART_Init(UART_PORT, &uart_config, (CLOCK_GetPllFreq(kCLOCK_PllUsb1) / 6U) / (CLOCK_GetDiv(kCLOCK_UartDiv) + 1U)); - - //------------- USB0 -------------// - // Clock - CLOCK_EnableUsbhs0PhyPllClock(kCLOCK_Usbphy480M, 480000000U); - CLOCK_EnableUsbhs0Clock(kCLOCK_Usb480M, 480000000U); - - USBPHY_Type* usb_phy = USBPHY1; - - // Enable PHY support for Low speed device + LS via FS Hub - usb_phy->CTRL |= USBPHY_CTRL_SET_ENUTMILEVEL2_MASK | USBPHY_CTRL_SET_ENUTMILEVEL3_MASK; - - // Enable all power for normal operation - usb_phy->PWD = 0; - - // TX Timing - uint32_t phytx = usb_phy->TX; - phytx &= ~(USBPHY_TX_D_CAL_MASK | USBPHY_TX_TXCAL45DM_MASK | USBPHY_TX_TXCAL45DP_MASK); - phytx |= USBPHY_TX_D_CAL(0x0C) | USBPHY_TX_TXCAL45DP(0x06) | USBPHY_TX_TXCAL45DM(0x06); - usb_phy->TX = phytx; - - // USB1 -// CLOCK_EnableUsbhs1PhyPllClock(kCLOCK_Usbphy480M, 480000000U); -// CLOCK_EnableUsbhs1Clock(kCLOCK_Usb480M, 480000000U); -} - -//--------------------------------------------------------------------+ -// USB Interrupt Handler -//--------------------------------------------------------------------+ -void USB_OTG1_IRQHandler(void) -{ - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST - tuh_int_handler(0); - #endif - - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE - tud_int_handler(0); - #endif -} - -void USB_OTG2_IRQHandler(void) -{ - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST - tuh_int_handler(1); - #endif - - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE - tud_int_handler(1); - #endif -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - GPIO_PinWrite(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); -} - -uint32_t board_button_read(void) -{ - // active low - return BUTTON_STATE_ACTIVE == GPIO_PinRead(BUTTON_PORT, BUTTON_PIN); -} - -int board_uart_read(uint8_t* buf, int len) -{ - LPUART_ReadBlocking(UART_PORT, buf, len); - return len; -} - -int board_uart_write(void const * buf, int len) -{ - LPUART_WriteBlocking(UART_PORT, (uint8_t*)buf, len); - return len; -} - -#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/tools/build_all.py b/tools/build_all.py index 172cb2070..787011e26 100644 --- a/tools/build_all.py +++ b/tools/build_all.py @@ -40,8 +40,13 @@ all_examples.sort() all_boards = [] for entry in os.scandir("hw/bsp"): - if entry.is_dir(): - all_boards.append(entry.name) + if entry.is_dir() and entry.name != "esp32s2": + if os.path.isdir(entry.path + "/boards"): + # family directory + for subentry in os.scandir(entry.path + "/boards"): + if subentry.is_dir(): all_boards.append(subentry.name) + else: + all_boards.append(entry.name) if len(sys.argv) > 1: input_boards = list(set(all_boards).intersection(sys.argv)) @@ -67,15 +72,14 @@ def build_size(example, board): def skip_example(example, board): ex_dir = 'examples/' + example + board_mk = 'hw/bsp/{}/board.mk'.format(board) + if not os.path.exists(board_mk): + board_mk = list(glob.iglob('hw/bsp/*/boards/{}/../../family.mk'.format(board)))[0] with open(board_mk) as mk: mk_contents = mk.read() - # Skip all ESP32-S2 board for CI - if 'CROSS_COMPILE = xtensa-esp32s2-elf-' in mk_contents: - return 1 - # Skip all OPT_MCU_NONE these are WIP port if '-DCFG_TUSB_MCU=OPT_MCU_NONE' in mk_contents: return 1 diff --git a/tools/build_esp32s.py b/tools/build_esp32s.py index 44364806b..c63bbf6d2 100644 --- a/tools/build_esp32s.py +++ b/tools/build_esp32s.py @@ -34,12 +34,9 @@ all_boards = [] if len(sys.argv) > 2: all_boards.append(sys.argv[2]) else: - for entry in os.scandir("hw/bsp"): + for entry in os.scandir("hw/bsp/esp32s2/boards"): if entry.is_dir(): - with open(entry.path + '/board.mk') as mk: - # Only includes ESP32-S2 board - if 'CROSS_COMPILE = xtensa-esp32s2-elf-' in mk.read(): - all_boards.append(entry.name) + all_boards.append(entry.name) all_boards.sort()