add support for SAMD11 devices / add samd11_xplained board
This commit is contained in:
		| @@ -32,7 +32,7 @@ The stack supports the following MCUs: | |||||||
|  |  | ||||||
| - **Espressif:** ESP32-S2 | - **Espressif:** ESP32-S2 | ||||||
| - **Dialog:** DA1469x | - **Dialog:** DA1469x | ||||||
| - **MicroChip:** SAMD21, SAMD51, SAME5x (device only) | - **MicroChip:** SAMD11, SAMD21, SAMD51, SAME5x (device only) | ||||||
| - **NordicSemi:** nRF52833, nRF52840 | - **NordicSemi:** nRF52833, nRF52840 | ||||||
| - **Nuvoton:** NUC120, NUC121/NUC125, NUC126, NUC505 | - **Nuvoton:** NUC120, NUC121/NUC125, NUC126, NUC505 | ||||||
| - **NXP:**  | - **NXP:**  | ||||||
|   | |||||||
| @@ -28,6 +28,7 @@ This code base already had supported for a handful of following boards (sorted a | |||||||
| - [Adafruit ItsyBitsy M4 Express](https://www.adafruit.com/product/3800) | - [Adafruit ItsyBitsy M4 Express](https://www.adafruit.com/product/3800) | ||||||
| - [Adafruit Metro M0 Express](https://www.adafruit.com/product/3505) | - [Adafruit Metro M0 Express](https://www.adafruit.com/product/3505) | ||||||
| - [Adafruit Metro M4 Express](https://www.adafruit.com/product/3382) | - [Adafruit Metro M4 Express](https://www.adafruit.com/product/3382) | ||||||
|  | - [Microchip SAMD11 Xplained](https://www.microchip.com/developmenttools/ProductDetails/atsamd11-xpro) | ||||||
| - [Seeeduino Xiao](https://www.seeedstudio.com/Seeeduino-XIAO-Arduino-Microcontroller-SAMD21-Cortex-M0+-p-4426.html) | - [Seeeduino Xiao](https://www.seeedstudio.com/Seeeduino-XIAO-Arduino-Microcontroller-SAMD21-Cortex-M0+-p-4426.html) | ||||||
| - [Great Scott Gadgets LUNA](https://greatscottgadgets.com/luna/) | - [Great Scott Gadgets LUNA](https://greatscottgadgets.com/luna/) | ||||||
|  |  | ||||||
|   | |||||||
							
								
								
									
										53
									
								
								hw/bsp/samd11_xplained/board.mk
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										53
									
								
								hw/bsp/samd11_xplained/board.mk
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,53 @@ | |||||||
|  | CFLAGS += \ | ||||||
|  |   -ffunction-sections \ | ||||||
|  |   -fdata-sections \ | ||||||
|  |   -Wl,--gc-sections \ | ||||||
|  |   -mthumb \ | ||||||
|  |   -mabi=aapcs-linux \ | ||||||
|  |   -mcpu=cortex-m0plus \ | ||||||
|  |   -nostdlib -nostartfiles \ | ||||||
|  |   -D__SAMD11D14AM__ \ | ||||||
|  |   -DCONF_DFLL_OVERWRITE_CALIBRATION=0 \ | ||||||
|  |   -DOSC32K_OVERWRITE_CALIBRATION=0 \ | ||||||
|  |   -DCFG_TUSB_MCU=OPT_MCU_SAMD21 \ | ||||||
|  |   -fshort-enums \ | ||||||
|  |   -Os | ||||||
|  |  | ||||||
|  | # All source paths should be relative to the top level. | ||||||
|  | LD_FILE = hw/bsp/$(BOARD)/samd11d14am_flash.ld | ||||||
|  |  | ||||||
|  | SRC_C += \ | ||||||
|  | 	hw/mcu/microchip/samd11/gcc/gcc/startup_samd11.c \ | ||||||
|  | 	hw/mcu/microchip/samd11/gcc/system_samd11.c \ | ||||||
|  | 	hw/mcu/microchip/samd11/hpl/gclk/hpl_gclk.c \ | ||||||
|  | 	hw/mcu/microchip/samd11/hpl/pm/hpl_pm.c \ | ||||||
|  | 	hw/mcu/microchip/samd11/hpl/sysctrl/hpl_sysctrl.c \ | ||||||
|  | 	hw/mcu/microchip/samd11/hal/src/hal_atomic.c | ||||||
|  |  | ||||||
|  | INC += \ | ||||||
|  | 	$(TOP)/hw/mcu/microchip/samd11/ \ | ||||||
|  | 	$(TOP)/hw/mcu/microchip/samd11/config \ | ||||||
|  | 	$(TOP)/hw/mcu/microchip/samd11/include \ | ||||||
|  | 	$(TOP)/hw/mcu/microchip/samd11/hal/include \ | ||||||
|  | 	$(TOP)/hw/mcu/microchip/samd11/hal/utils/include \ | ||||||
|  | 	$(TOP)/hw/mcu/microchip/samd11/hpl/pm/ \ | ||||||
|  | 	$(TOP)/hw/mcu/microchip/samd11/hpl/port \ | ||||||
|  | 	$(TOP)/hw/mcu/microchip/samd11/hri \ | ||||||
|  | 	$(TOP)/hw/mcu/microchip/samd11/CMSIS/Include \ | ||||||
|  | 	$(TOP)/hw/mcu/microchip/samd11/CMSIS/Core/Include | ||||||
|  |  | ||||||
|  | # For TinyUSB port source | ||||||
|  | VENDOR = microchip | ||||||
|  | CHIP_FAMILY = samd | ||||||
|  |  | ||||||
|  | # For freeRTOS port source | ||||||
|  | FREERTOS_PORT = ARM_CM0 | ||||||
|  |  | ||||||
|  | # For flash-jlink target | ||||||
|  | JLINK_DEVICE = ATSAMD11D14 | ||||||
|  | JLINK_IF = swd | ||||||
|  |  | ||||||
|  | # flash using edbg | ||||||
|  | flash: $(BUILD)/$(BOARD)-firmware.bin | ||||||
|  | 	edbg -b -t samd11 -e -pv -f $< | ||||||
|  |  | ||||||
							
								
								
									
										152
									
								
								hw/bsp/samd11_xplained/samd11_xplained.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										152
									
								
								hw/bsp/samd11_xplained/samd11_xplained.c
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,152 @@ | |||||||
|  | /* | ||||||
|  |  * 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 "bsp/board.h" | ||||||
|  |  | ||||||
|  | #include "sam.h" | ||||||
|  | #include "hal/include/hal_gpio.h" | ||||||
|  | #include "hal/include/hal_init.h" | ||||||
|  | #include "hri/hri_nvmctrl_d11.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_PA16 // pin PA22 | ||||||
|  | #define BUTTON_PIN   PIN_PA14 // 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; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void _init(void) | ||||||
|  | { | ||||||
|  |   // This _init() standin makes certain GCC environments happier. | ||||||
|  |   // They expect the main binary to have a constructor called _init; but don't provide a weak default. | ||||||
|  |   // Providing an empty constructor satisfies this odd case, and doesn't harm anything. | ||||||
|  | } | ||||||
|  |  | ||||||
|  |  | ||||||
|  | #endif | ||||||
							
								
								
									
										143
									
								
								hw/bsp/samd11_xplained/samd11d14am_flash.ld
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										143
									
								
								hw/bsp/samd11_xplained/samd11d14am_flash.ld
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,143 @@ | |||||||
|  | /** | ||||||
|  |  * \file | ||||||
|  |  * | ||||||
|  |  * \brief Linker script for running in internal FLASH on the SAMD11D14AM | ||||||
|  |  * | ||||||
|  |  * Copyright (c) 2018 Microchip Technology Inc. | ||||||
|  |  * | ||||||
|  |  * \asf_license_start | ||||||
|  |  * | ||||||
|  |  * \page License | ||||||
|  |  * | ||||||
|  |  * SPDX-License-Identifier: Apache-2.0 | ||||||
|  |  * | ||||||
|  |  * Licensed under the Apache License, Version 2.0 (the "License"); you may | ||||||
|  |  * not use this file except in compliance with the License. | ||||||
|  |  * You may obtain a copy of the Licence at | ||||||
|  |  *  | ||||||
|  |  * http://www.apache.org/licenses/LICENSE-2.0 | ||||||
|  |  *  | ||||||
|  |  * Unless required by applicable law or agreed to in writing, software | ||||||
|  |  * distributed under the License is distributed on an AS IS BASIS, WITHOUT | ||||||
|  |  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||||||
|  |  * See the License for the specific language governing permissions and | ||||||
|  |  * limitations under the License. | ||||||
|  |  * | ||||||
|  |  * \asf_license_stop | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  |  | ||||||
|  | OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm") | ||||||
|  | OUTPUT_ARCH(arm) | ||||||
|  | SEARCH_DIR(.) | ||||||
|  |  | ||||||
|  | /* Memory Spaces Definitions */ | ||||||
|  | MEMORY | ||||||
|  | { | ||||||
|  |   rom      (rx)  : ORIGIN = 0x00000000, LENGTH = 0x00004000 | ||||||
|  |   ram      (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00001000 | ||||||
|  | } | ||||||
|  |  | ||||||
|  | /* The stack size used by the application. NOTE: you need to adjust according to your application. */ | ||||||
|  | STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : DEFINED(__stack_size__) ? __stack_size__ : 0x400; | ||||||
|  |  | ||||||
|  | /* Section Definitions */ | ||||||
|  | SECTIONS | ||||||
|  | { | ||||||
|  |     .text : | ||||||
|  |     { | ||||||
|  |         . = ALIGN(4); | ||||||
|  |         _sfixed = .; | ||||||
|  |         KEEP(*(.vectors .vectors.*)) | ||||||
|  |         *(.text .text.* .gnu.linkonce.t.*) | ||||||
|  |         *(.glue_7t) *(.glue_7) | ||||||
|  |         *(.rodata .rodata* .gnu.linkonce.r.*) | ||||||
|  |         *(.ARM.extab* .gnu.linkonce.armextab.*) | ||||||
|  |  | ||||||
|  |         /* Support C constructors, and C destructors in both user code | ||||||
|  |            and the C library. This also provides support for C++ code. */ | ||||||
|  |         . = ALIGN(4); | ||||||
|  |         KEEP(*(.init)) | ||||||
|  |         . = ALIGN(4); | ||||||
|  |         __preinit_array_start = .; | ||||||
|  |         KEEP (*(.preinit_array)) | ||||||
|  |         __preinit_array_end = .; | ||||||
|  |  | ||||||
|  |         . = ALIGN(4); | ||||||
|  |         __init_array_start = .; | ||||||
|  |         KEEP (*(SORT(.init_array.*))) | ||||||
|  |         KEEP (*(.init_array)) | ||||||
|  |         __init_array_end = .; | ||||||
|  |  | ||||||
|  |         . = ALIGN(4); | ||||||
|  |         KEEP (*crtbegin.o(.ctors)) | ||||||
|  |         KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors)) | ||||||
|  |         KEEP (*(SORT(.ctors.*))) | ||||||
|  |         KEEP (*crtend.o(.ctors)) | ||||||
|  |  | ||||||
|  |         . = ALIGN(4); | ||||||
|  |         KEEP(*(.fini)) | ||||||
|  |  | ||||||
|  |         . = ALIGN(4); | ||||||
|  |         __fini_array_start = .; | ||||||
|  |         KEEP (*(.fini_array)) | ||||||
|  |         KEEP (*(SORT(.fini_array.*))) | ||||||
|  |         __fini_array_end = .; | ||||||
|  |  | ||||||
|  |         KEEP (*crtbegin.o(.dtors)) | ||||||
|  |         KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors)) | ||||||
|  |         KEEP (*(SORT(.dtors.*))) | ||||||
|  |         KEEP (*crtend.o(.dtors)) | ||||||
|  |  | ||||||
|  |         . = ALIGN(4); | ||||||
|  |         _efixed = .;            /* End of text section */ | ||||||
|  |     } > rom | ||||||
|  |  | ||||||
|  |     /* .ARM.exidx is sorted, so has to go in its own output section.  */ | ||||||
|  |     PROVIDE_HIDDEN (__exidx_start = .); | ||||||
|  |     .ARM.exidx : | ||||||
|  |     { | ||||||
|  |       *(.ARM.exidx* .gnu.linkonce.armexidx.*) | ||||||
|  |     } > rom | ||||||
|  |     PROVIDE_HIDDEN (__exidx_end = .); | ||||||
|  |  | ||||||
|  |     . = ALIGN(4); | ||||||
|  |     _etext = .; | ||||||
|  |  | ||||||
|  |     .relocate : AT (_etext) | ||||||
|  |     { | ||||||
|  |         . = ALIGN(4); | ||||||
|  |         _srelocate = .; | ||||||
|  |         *(.ramfunc .ramfunc.*); | ||||||
|  |         *(.data .data.*); | ||||||
|  |         . = ALIGN(4); | ||||||
|  |         _erelocate = .; | ||||||
|  |     } > ram | ||||||
|  |  | ||||||
|  |     /* .bss section which is used for uninitialized data */ | ||||||
|  |     .bss (NOLOAD) : | ||||||
|  |     { | ||||||
|  |         . = ALIGN(4); | ||||||
|  |         _sbss = . ; | ||||||
|  |         _szero = .; | ||||||
|  |         *(.bss .bss.*) | ||||||
|  |         *(COMMON) | ||||||
|  |         . = ALIGN(4); | ||||||
|  |         _ebss = . ; | ||||||
|  |         _ezero = .; | ||||||
|  |     } > ram | ||||||
|  |  | ||||||
|  |     /* stack section */ | ||||||
|  |     .stack (NOLOAD): | ||||||
|  |     { | ||||||
|  |         . = ALIGN(8); | ||||||
|  |         _sstack = .; | ||||||
|  |         . = . + STACK_SIZE; | ||||||
|  |         . = ALIGN(8); | ||||||
|  |         _estack = .; | ||||||
|  |     } > ram | ||||||
|  |  | ||||||
|  |     . = ALIGN(4); | ||||||
|  |     _end = . ; | ||||||
|  | } | ||||||
		Reference in New Issue
	
	Block a user
	 Katherine Temkin
					Katherine Temkin