samd: Add new port to Microchip SAMDxx microcontrollers.

Initially supporting SAMD21 and SAMD51.
pull/1/head
Damien George 2019-06-22 23:03:41 +10:00
parent f073f2b543
commit 5f9bd11527
22 changed files with 1335 additions and 0 deletions

100
ports/samd/Makefile 100644
View File

@ -0,0 +1,100 @@
BOARD ?= ADAFRUIT_ITSYBITSY_M4_EXPRESS
BOARD_DIR ?= boards/$(BOARD)
BUILD ?= build-$(BOARD)
CROSS_COMPILE ?= arm-none-eabi-
UF2CONV ?= $(TOP)/tools/uf2conv.py
ifeq ($(wildcard $(BOARD_DIR)/.),)
$(error Invalid BOARD specified: $(BOARD_DIR))
endif
include ../../py/mkenv.mk
include $(BOARD_DIR)/board.mk
# Qstr definitions (must come before including py.mk)
QSTR_DEFS = qstrdefsport.h
QSTR_GLOBAL_DEPENDENCIES = $(BOARD_DIR)/mpconfigboard.h
# Include py core make definitions
include $(TOP)/py/py.mk
INC += -I.
INC += -I$(TOP)
INC += -I$(BUILD)
INC += -I$(BOARD_DIR)
INC += -I$(TOP)/lib/cmsis/inc
INC += -I$(TOP)/lib/asf4/$(shell echo $(MCU_SERIES) | tr '[:upper:]' '[:lower:]')/include
INC += -I$(TOP)/lib/tinyusb/src
CFLAGS_MCU_SAMD21 = -mtune=cortex-m0plus -mcpu=cortex-m0plus -msoft-float
CFLAGS_MCU_SAMD51 = -mtune=cortex-m4 -mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard
CFLAGS = $(INC) -Wall -Werror -std=c99 -nostdlib -mthumb $(CFLAGS_MCU_$(MCU_SERIES)) -fsingle-precision-constant -Wdouble-promotion
CFLAGS += -DMCU_$(MCU_SERIES) -D__$(CMSIS_MCU)__
LDFLAGS = -nostdlib $(addprefix -T,$(LD_FILES)) -Map=$@.map --cref
LIBS = $(shell $(CC) $(CFLAGS) -print-libgcc-file-name)
# Tune for Debugging or Optimization
ifeq ($(DEBUG),1)
CFLAGS += -O0 -ggdb
else
CFLAGS += -Os -DNDEBUG
LDFLAGS += --gc-sections
CFLAGS += -fdata-sections -ffunction-sections
endif
SRC_C = \
main.c \
modutime.c \
modmachine.c \
mphalport.c \
samd_isr.c \
samd_soc.c \
tusb_port.c \
lib/libc/string0.c \
lib/libm/ef_sqrt.c \
lib/libm/fmodf.c \
lib/libm/math.c \
lib/libm/nearbyintf.c \
lib/mp-readline/readline.c \
lib/tinyusb/src/class/cdc/cdc_device.c \
lib/tinyusb/src/common/tusb_fifo.c \
lib/tinyusb/src/device/usbd.c \
lib/tinyusb/src/device/usbd_control.c \
lib/tinyusb/src/tusb.c \
lib/utils/printf.c \
lib/utils/pyexec.c \
lib/utils/stdout_helpers.c \
ifeq ($(MCU_SERIES),SAMD21)
SRC_C += lib/tinyusb/src/portable/microchip/samd21/dcd_samd21.c
SRC_S = lib/utils/gchelper_m0.s
else
SRC_C += lib/tinyusb/src/portable/microchip/samd51/dcd_samd51.c
SRC_S = lib/utils/gchelper_m3.s
endif
# List of sources for qstr extraction
SRC_QSTR += modutime.c modmachine.c
OBJ += $(PY_O)
OBJ += $(addprefix $(BUILD)/, $(SRC_C:.c=.o))
OBJ += $(addprefix $(BUILD)/, $(SRC_S:.s=.o))
# Workaround for bug in older gcc, warning on "static usbd_device_t _usbd_dev = { 0 };"
$(BUILD)/lib/tinyusb/src/device/usbd.o: CFLAGS += -Wno-missing-braces
all: $(BUILD)/firmware.uf2
$(BUILD)/firmware.elf: $(OBJ)
$(ECHO) "LINK $@"
$(Q)$(LD) $(LDFLAGS) -o $@ $^ $(LIBS)
$(Q)$(SIZE) $@
$(BUILD)/firmware.bin: $(BUILD)/firmware.elf
$(Q)$(OBJCOPY) -O binary -j .isr_vector -j .text -j .data $^ $(BUILD)/firmware.bin
$(BUILD)/firmware.uf2: $(BUILD)/firmware.bin
$(Q)$(PYTHON) $(UF2CONV) -b $(TEXT0) -c -o $@ $<
include $(TOP)/py/mkrules.mk

View File

@ -0,0 +1,7 @@
Port of MicroPython to Microchip SAMD MCUs
==========================================
Supports SAMD21 and SAMD51.
Features:
- REPL over USB VCP

View File

@ -0,0 +1,4 @@
MCU_SERIES = SAMD51
CMSIS_MCU = SAMD51G19A
LD_FILES = $(BOARD_DIR)/link.ld sections.ld
TEXT0 = 0x4000

View File

@ -0,0 +1,17 @@
/*
GNU linker script for SAMD51
*/
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x00004000, LENGTH = 512K - 16K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 192K
}
/* Top end of the stack, with room for double-tap variable */
_estack = ORIGIN(RAM) + LENGTH(RAM) - 8;
_sstack = _estack - 16K;
_sheap = _ebss;
_eheap = _sstack;

View File

@ -0,0 +1,7 @@
#define MICROPY_HW_BOARD_NAME "ItsyBitsy M4 Express"
#define MICROPY_HW_MCU_NAME "SAMD51G19A"
#define MICROPY_FLOAT_IMPL (MICROPY_FLOAT_IMPL_FLOAT)
#define MICROPY_PY_BUILTINS_COMPLEX (0)
#define MICROPY_PY_MATH (0)
#define MICROPY_PY_CMATH (0)

View File

@ -0,0 +1,4 @@
MCU_SERIES = SAMD21
CMSIS_MCU = SAMD21E18A
LD_FILES = $(BOARD_DIR)/link.ld sections.ld
TEXT0 = 0x2000

View File

@ -0,0 +1,17 @@
/*
GNU linker script for SAMD21
*/
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x00002000, LENGTH = 256K - 8K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 32K
}
/* Top end of the stack, with room for double-tap variable */
_estack = ORIGIN(RAM) + LENGTH(RAM) - 8;
_sstack = _estack - 8K;
_sheap = _ebss;
_eheap = _sstack;

View File

@ -0,0 +1,2 @@
#define MICROPY_HW_BOARD_NAME "Trinket M0"
#define MICROPY_HW_MCU_NAME "SAMD21E18A"

98
ports/samd/main.c 100644
View File

@ -0,0 +1,98 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Damien P. George
*
* 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.
*/
#include "py/compile.h"
#include "py/runtime.h"
#include "py/gc.h"
#include "py/mperrno.h"
#include "py/stackctrl.h"
#include "lib/utils/gchelper.h"
#include "lib/utils/pyexec.h"
extern uint8_t _sstack, _estack, _sheap, _eheap;
void samd_main(void) {
mp_stack_set_top(&_estack);
mp_stack_set_limit(&_estack - &_sstack - 1024);
for (;;) {
gc_init(&_sheap, &_eheap);
mp_init();
mp_obj_list_init(MP_OBJ_TO_PTR(mp_sys_path), 0);
mp_obj_list_append(mp_sys_path, MP_OBJ_NEW_QSTR(MP_QSTR_));
mp_obj_list_init(MP_OBJ_TO_PTR(mp_sys_argv), 0);
for (;;) {
if (pyexec_mode_kind == PYEXEC_MODE_RAW_REPL) {
if (pyexec_raw_repl() != 0) {
break;
}
} else {
if (pyexec_friendly_repl() != 0) {
break;
}
}
}
mp_printf(MP_PYTHON_PRINTER, "MPY: soft reboot\n");
gc_sweep_all();
mp_deinit();
}
}
void gc_collect(void) {
gc_collect_start();
uintptr_t regs[10];
uintptr_t sp = gc_helper_get_regs_and_sp(regs);
gc_collect_root((void**)sp, ((uintptr_t)MP_STATE_THREAD(stack_top) - sp) / sizeof(uint32_t));
gc_collect_end();
}
mp_lexer_t *mp_lexer_new_from_file(const char *filename) {
mp_raise_OSError(MP_ENOENT);
}
mp_import_stat_t mp_import_stat(const char *path) {
return MP_IMPORT_STAT_NO_EXIST;
}
mp_obj_t mp_builtin_open(size_t n_args, const mp_obj_t *args, mp_map_t *kwargs) {
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_KW(mp_builtin_open_obj, 1, mp_builtin_open);
void nlr_jump_fail(void *val) {
for (;;) {
}
}
#ifndef NDEBUG
void MP_WEAK __assert_func(const char *file, int line, const char *func, const char *expr) {
mp_printf(MP_PYTHON_PRINTER, "Assertion '%s' failed, at file %s:%d\n", expr, file, line);
for(;;) {
}
}
#endif

View File

@ -0,0 +1,12 @@
#BOARD = TRINKET
UF2DEV = /dev/sdb
#UF2CONV = /home/damien/others/uf2/utils/uf2conv.py
include Makefile
deploy: $(BUILD)/firmware.uf2
$(ECHO) "Copying $< to the board"
mount $(UF2DEV)
cat /mnt/INFO_UF2.TXT > /dev/null
cp $< /mnt
umount /mnt

View File

@ -0,0 +1,72 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Damien P. George
*
* 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.
*/
#include "py/runtime.h"
#include "extmod/machine_mem.h"
#include "samd_soc.h"
#if defined(MCU_SAMD21)
#define DBL_TAP_ADDR ((volatile uint32_t *)(0x20000000 + 32 * 1024 - 4))
#elif defined(MCU_SAMD51)
#define DBL_TAP_ADDR ((volatile uint32_t *)(0x20000000 + 192 * 1024 - 4))
#endif
#define DBL_TAP_MAGIC_LOADER 0xf01669ef
#define DBL_TAP_MAGIC_RESET 0xf02669ef
STATIC mp_obj_t machine_reset(void) {
*DBL_TAP_ADDR = DBL_TAP_MAGIC_RESET;
NVIC_SystemReset();
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_0(machine_reset_obj, machine_reset);
STATIC mp_obj_t machine_bootloader(void) {
*DBL_TAP_ADDR = DBL_TAP_MAGIC_LOADER;
NVIC_SystemReset();
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_0(machine_bootloader_obj, machine_bootloader);
STATIC mp_obj_t machine_freq(void) {
return MP_OBJ_NEW_SMALL_INT(CPU_FREQ);
}
MP_DEFINE_CONST_FUN_OBJ_0(machine_freq_obj, machine_freq);
STATIC const mp_rom_map_elem_t machine_module_globals_table[] = {
{ MP_ROM_QSTR(MP_QSTR___name__), MP_ROM_QSTR(MP_QSTR_umachine) },
{ MP_ROM_QSTR(MP_QSTR_reset), MP_ROM_PTR(&machine_reset_obj) },
{ MP_ROM_QSTR(MP_QSTR_bootloader), MP_ROM_PTR(&machine_bootloader_obj) },
{ MP_ROM_QSTR(MP_QSTR_freq), MP_ROM_PTR(&machine_freq_obj) },
{ MP_ROM_QSTR(MP_QSTR_mem8), MP_ROM_PTR(&machine_mem8_obj) },
{ MP_ROM_QSTR(MP_QSTR_mem16), MP_ROM_PTR(&machine_mem16_obj) },
{ MP_ROM_QSTR(MP_QSTR_mem32), MP_ROM_PTR(&machine_mem32_obj) },
};
STATIC MP_DEFINE_CONST_DICT(machine_module_globals, machine_module_globals_table);
const mp_obj_module_t mp_module_machine = {
.base = { &mp_type_module },
.globals = (mp_obj_dict_t*)&machine_module_globals,
};

View File

@ -0,0 +1,47 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Damien P. George
*
* 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.
*/
#include "extmod/utime_mphal.h"
STATIC const mp_rom_map_elem_t time_module_globals_table[] = {
{ MP_ROM_QSTR(MP_QSTR___name__), MP_ROM_QSTR(MP_QSTR_utime) },
{ MP_ROM_QSTR(MP_QSTR_sleep), MP_ROM_PTR(&mp_utime_sleep_obj) },
{ MP_ROM_QSTR(MP_QSTR_sleep_ms), MP_ROM_PTR(&mp_utime_sleep_ms_obj) },
{ MP_ROM_QSTR(MP_QSTR_sleep_us), MP_ROM_PTR(&mp_utime_sleep_us_obj) },
{ MP_ROM_QSTR(MP_QSTR_ticks_ms), MP_ROM_PTR(&mp_utime_ticks_ms_obj) },
{ MP_ROM_QSTR(MP_QSTR_ticks_us), MP_ROM_PTR(&mp_utime_ticks_us_obj) },
{ MP_ROM_QSTR(MP_QSTR_ticks_cpu), MP_ROM_PTR(&mp_utime_ticks_cpu_obj) },
{ MP_ROM_QSTR(MP_QSTR_ticks_add), MP_ROM_PTR(&mp_utime_ticks_add_obj) },
{ MP_ROM_QSTR(MP_QSTR_ticks_diff), MP_ROM_PTR(&mp_utime_ticks_diff_obj) },
};
STATIC MP_DEFINE_CONST_DICT(time_module_globals, time_module_globals_table);
const mp_obj_module_t mp_module_utime = {
.base = { &mp_type_module },
.globals = (mp_obj_dict_t*)&time_module_globals,
};

View File

@ -0,0 +1,109 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Damien P. George
*
* 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.
*/
// Options controlling how MicroPython is built, overriding defaults in py/mpconfig.h
// Board specific definitions
#include "mpconfigboard.h"
// Memory allocation policies
#define MICROPY_GC_STACK_ENTRY_TYPE uint16_t
#define MICROPY_GC_ALLOC_THRESHOLD (0)
#define MICROPY_ALLOC_PARSE_CHUNK_INIT (32)
#define MICROPY_ALLOC_PATH_MAX (256)
#define MICROPY_QSTR_BYTES_IN_HASH (1)
// Compiler configuration
#define MICROPY_COMP_CONST (0)
// Python internal features
#define MICROPY_ENABLE_GC (1)
#define MICROPY_KBD_EXCEPTION (1)
#define MICROPY_HELPER_REPL (1)
#define MICROPY_LONGINT_IMPL (MICROPY_LONGINT_IMPL_MPZ)
#define MICROPY_ENABLE_SOURCE_LINE (1)
#define MICROPY_ERROR_REPORTING (MICROPY_ERROR_REPORTING_TERSE)
#define MICROPY_CPYTHON_COMPAT (0)
#define MICROPY_CAN_OVERRIDE_BUILTINS (1)
// Control over Python builtins
#define MICROPY_PY_ASYNC_AWAIT (0)
#define MICROPY_PY_BUILTINS_STR_COUNT (0)
#define MICROPY_PY_BUILTINS_MEMORYVIEW (1)
#define MICROPY_PY_BUILTINS_SET (0)
#define MICROPY_PY_BUILTINS_FROZENSET (0)
#define MICROPY_PY_BUILTINS_PROPERTY (0)
#define MICROPY_PY_BUILTINS_ENUMERATE (0)
#define MICROPY_PY_BUILTINS_FILTER (0)
#define MICROPY_PY_BUILTINS_REVERSED (0)
#define MICROPY_PY_BUILTINS_MIN_MAX (0)
#define MICROPY_PY___FILE__ (0)
#define MICROPY_PY_MICROPYTHON_MEM_INFO (1)
#define MICROPY_PY_ARRAY_SLICE_ASSIGN (1)
#define MICROPY_PY_ATTRTUPLE (0)
#define MICROPY_PY_COLLECTIONS (0)
#define MICROPY_PY_SYS_MAXSIZE (1)
// Extended modules
#define MICROPY_PY_UTIME_MP_HAL (1)
#define MICROPY_PY_MACHINE (1)
// Hooks to add builtins
#define MICROPY_PORT_BUILTINS \
{ MP_ROM_QSTR(MP_QSTR_open), MP_ROM_PTR(&mp_builtin_open_obj) },
extern const struct _mp_obj_module_t mp_module_machine;
extern const struct _mp_obj_module_t mp_module_utime;
#define MICROPY_PORT_BUILTIN_MODULES \
{ MP_ROM_QSTR(MP_QSTR_machine), MP_ROM_PTR(&mp_module_machine) }, \
{ MP_ROM_QSTR(MP_QSTR_utime), MP_ROM_PTR(&mp_module_utime) }, \
#define MICROPY_PORT_ROOT_POINTERS \
const char *readline_hist[8];
#define MP_STATE_PORT MP_STATE_VM
// Miscellaneous settings
#define MICROPY_EVENT_POLL_HOOK \
do { \
extern void mp_handle_pending(void); \
mp_handle_pending(); \
__WFI(); \
} while (0);
#define MICROPY_MAKE_POINTER_CALLABLE(p) ((void*)((mp_uint_t)(p) | 1))
#define MP_PLAT_PRINT_STRN(str, len) mp_hal_stdout_tx_strn_cooked(str, len)
#define MP_SSIZE_MAX (0x7fffffff)
typedef int mp_int_t; // must be pointer size
typedef unsigned mp_uint_t; // must be pointer size
typedef long mp_off_t;
// Need to provide a declaration/definition of alloca()
#include <alloca.h>

View File

@ -0,0 +1,112 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Damien P. George
*
* 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.
*/
#include "py/mpstate.h"
#include "py/mphal.h"
#include "lib/utils/interrupt_char.h"
#include "samd_soc.h"
#include "tusb.h"
#if MICROPY_KBD_EXCEPTION
void tud_cdc_rx_wanted_cb(uint8_t itf, char wanted_char) {
(void)itf;
(void)wanted_char;
tud_cdc_read_char(); // discard interrupt char
mp_keyboard_interrupt();
}
void mp_hal_set_interrupt_char(int c) {
if (c != -1) {
mp_obj_exception_clear_traceback(MP_OBJ_FROM_PTR(&MP_STATE_VM(mp_kbd_exception)));
}
tud_cdc_set_wanted_char(c);
}
void mp_keyboard_interrupt(void) {
MP_STATE_VM(mp_pending_exception) = MP_OBJ_FROM_PTR(&MP_STATE_VM(mp_kbd_exception));
#if MICROPY_ENABLE_SCHEDULER
if (MP_STATE_VM(sched_state) == MP_SCHED_IDLE) {
MP_STATE_VM(sched_state) = MP_SCHED_PENDING;
}
#endif
}
#endif
void mp_hal_delay_ms(mp_uint_t ms) {
ms += 1;
uint32_t t0 = systick_ms;
while (systick_ms - t0 < ms) {
MICROPY_EVENT_POLL_HOOK
}
}
void mp_hal_delay_us(mp_uint_t us) {
uint32_t ms = us / 1000 + 1;
uint32_t t0 = systick_ms;
while (systick_ms - t0 < ms) {
__WFI();
}
}
int mp_hal_stdin_rx_chr(void) {
for (;;) {
if (USARTx->USART.INTFLAG.bit.RXC) {
return USARTx->USART.DATA.bit.DATA;
}
if (tud_cdc_connected() && tud_cdc_available()) {
uint8_t buf[1];
uint32_t count = tud_cdc_read(buf, sizeof(buf));
if (count) {
return buf[0];
}
}
__WFI();
}
}
void mp_hal_stdout_tx_strn(const char *str, mp_uint_t len) {
if (tud_cdc_connected()) {
for (size_t i = 0; i < len;) {
uint32_t n = len - i;
uint32_t n2 = tud_cdc_write(str + i, n);
if (n2 < n) {
while (!tud_cdc_write_flush()) {
__WFI();
}
}
i += n2;
}
while (!tud_cdc_write_flush()) {
__WFI();
}
}
while (len--) {
while (!(USARTx->USART.INTFLAG.bit.DRE)) { }
USARTx->USART.DATA.bit.DATA = *str++;
}
}

View File

@ -0,0 +1,39 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Damien P. George
*
* 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.
*/
#ifndef MICROPY_INCLUDED_SAMD_MPHALPORT_H
#define MICROPY_INCLUDED_SAMD_MPHALPORT_H
#include <stdint.h>
extern volatile uint32_t systick_ms;
void mp_hal_set_interrupt_char(int c);
static inline mp_uint_t mp_hal_ticks_ms(void) { return systick_ms; }
static inline mp_uint_t mp_hal_ticks_us(void) { return systick_ms * 1000; }
static inline mp_uint_t mp_hal_ticks_cpu(void) { return 0; }
#endif // MICROPY_INCLUDED_SAMD_MPHALPORT_H

View File

@ -0,0 +1 @@
// qstrs specific to this port

View File

@ -0,0 +1,252 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Damien P. George
*
* 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.
*/
#include "samd_soc.h"
typedef void (*ISR)(void);
extern uint32_t _estack, _sidata, _sdata, _edata, _sbss, _ebss;
const ISR isr_vector[];
uint32_t systick_ms;
void Reset_Handler(void) __attribute__((naked));
void Reset_Handler(void) {
// Set stack pointer
#if __CORTEX_M >= 0x03
__asm volatile ("ldr sp, =_estack");
#else
__asm volatile ("ldr r0, =_estack");
__asm volatile ("mov sp, r0");
#endif
// Copy .data section from flash to RAM
for (uint32_t *src = &_sidata, *dest = &_sdata; dest < &_edata;) {
*dest++ = *src++;
}
// Zero out .bss section
for (uint32_t *dest = &_sbss; dest < &_ebss;) {
*dest++ = 0;
}
// When we get here: stack is initialised, bss is clear, data is copied
#if __FPU_PRESENT == 1 && __FPU_USED == 1
// Set CP10 and CP11 Full Access
SCB->CPACR |= (3UL << 10 * 2) | (3UL << 11 * 2);
#endif
// SCB->VTOR
*((volatile uint32_t*)0xe000ed08) = (uint32_t)&isr_vector;
// SCB->CCR: enable 8-byte stack alignment for IRQ handlers, in accord with EABI
*((volatile uint32_t*)0xe000ed14) |= 1 << 9;
// Initialise the cpu and peripherals
samd_init();
// Now that we have a basic system up and running we can call main
samd_main();
// we must not return
for (;;) {
}
}
void Default_Handler(void) {
for (;;) {
}
}
void SysTick_Handler(void) {
systick_ms += 1;
}
const ISR isr_vector[] __attribute__((section(".isr_vector"))) = {
(ISR)&_estack,
&Reset_Handler,
&Default_Handler, // NMI_Handler
&Default_Handler, // HardFault_Handler
&Default_Handler, // MemManage_Handler
&Default_Handler, // BusFault_Handler
&Default_Handler, // UsageFault_Handler
0,
0,
0,
0,
&Default_Handler, // SVC_Handler
&Default_Handler, // DebugMon_Handler
0,
&Default_Handler, // PendSV_Handler
&SysTick_Handler, // SysTick_Handler
0, // line 0
0,
0,
0,
0,
0,
0,
#if defined(MCU_SAMD21)
USB_Handler_wrapper, // line 7
#else
0,
#endif
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
#if defined(MCU_SAMD51)
&USB_0_Handler_wrapper, // line 80
&USB_1_Handler_wrapper,
&USB_2_Handler_wrapper,
&USB_3_Handler_wrapper,
#else
0,
0,
0,
0,
#endif
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
};

View File

@ -0,0 +1,152 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Damien P. George
*
* 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.
*/
#include "samd_soc.h"
#include "tusb.h"
static void uart0_init(void) {
#if defined(MCU_SAMD21)
// SERCOM0, TX=PA06=PAD2, RX=PA07=PAD3, ALT-D
PORT->Group[0].PMUX[3].reg = 0x33;
PORT->Group[0].PINCFG[6].reg = 1;
PORT->Group[0].PINCFG[7].reg = 1;
PM->APBCMASK.bit.SERCOM0_ = 1;
GCLK->CLKCTRL.reg = GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID_SERCOM0_CORE;
while (GCLK->STATUS.bit.SYNCBUSY) { }
uint32_t rxpo = 3;
uint32_t txpo = 1;
#elif defined(MCU_SAMD51)
// SERCOM3, TX=PA17=PAD0, RX=PA16=PAD1, ALT-D
PORT->Group[0].PMUX[8].reg = 0x33;
PORT->Group[0].PINCFG[16].reg = 1;
PORT->Group[0].PINCFG[17].reg = 1;
// Use Generator 0 which is already enabled and switched to DFLL @ 48MHz
GCLK->PCHCTRL[SERCOM3_GCLK_ID_CORE].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN_GCLK0;
MCLK->APBBMASK.bit.SERCOM3_ = 1;
uint32_t rxpo = 1;
uint32_t txpo = 2;
#endif
while (USARTx->USART.SYNCBUSY.bit.SWRST) { }
USARTx->USART.CTRLA.bit.SWRST = 1;
while (USARTx->USART.SYNCBUSY.bit.SWRST) { }
USARTx->USART.CTRLA.reg =
SERCOM_USART_CTRLA_DORD
| SERCOM_USART_CTRLA_RXPO(rxpo)
| SERCOM_USART_CTRLA_TXPO(txpo)
| SERCOM_USART_CTRLA_MODE(1)
;
USARTx->USART.CTRLB.reg = SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN;
while (USARTx->USART.SYNCBUSY.bit.CTRLB) { }
#if CPU_FREQ == 8000000
uint32_t baud = 50437; // 115200 baud; 65536*(1 - 16 * 115200/8e6)
#elif CPU_FREQ == 48000000
uint32_t baud = 63019; // 115200 baud; 65536*(1 - 16 * 115200/48e6)
#elif CPU_FREQ == 120000000
uint32_t baud = 64529; // 115200 baud; 65536*(1 - 16 * 115200/120e6)
#endif
USARTx->USART.BAUD.bit.BAUD = baud;
USARTx->USART.CTRLA.bit.ENABLE = 1;
while (USARTx->USART.SYNCBUSY.bit.ENABLE) { }
}
static void usb_init(void) {
// Init USB clock
#if defined(MCU_SAMD21)
GCLK->CLKCTRL.reg = GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID_USB;
PM->AHBMASK.bit.USB_ = 1;
PM->APBBMASK.bit.USB_ = 1;
uint8_t alt = 6; // alt G, USB
#elif defined(MCU_SAMD51)
GCLK->PCHCTRL[USB_GCLK_ID].reg = GCLK_PCHCTRL_CHEN | GCLK_PCHCTRL_GEN_GCLK1;
while (GCLK->PCHCTRL[USB_GCLK_ID].bit.CHEN == 0) { }
MCLK->AHBMASK.bit.USB_ = 1;
MCLK->APBBMASK.bit.USB_ = 1;
uint8_t alt = 7; // alt H, USB
#endif
// Init USB pins
PORT->Group[0].DIRSET.reg = 1 << 25 | 1 << 24;
PORT->Group[0].OUTCLR.reg = 1 << 25 | 1 << 24;
PORT->Group[0].PMUX[12].reg = alt << 4 | alt;
PORT->Group[0].PINCFG[24].reg = PORT_PINCFG_PMUXEN;
PORT->Group[0].PINCFG[25].reg = PORT_PINCFG_PMUXEN;
tusb_init();
}
void samd_init(void) {
#if defined(MCU_SAMD21)
NVMCTRL->CTRLB.bit.MANW = 1; // errata "Spurious Writes"
NVMCTRL->CTRLB.bit.RWS = 1; // 1 read wait state for 48MHz
// Enable DFLL48M
SYSCTRL->DFLLCTRL.reg = SYSCTRL_DFLLCTRL_ENABLE;
while (!SYSCTRL->PCLKSR.bit.DFLLRDY) {}
SYSCTRL->DFLLMUL.reg = SYSCTRL_DFLLMUL_CSTEP(1) | SYSCTRL_DFLLMUL_FSTEP(1)
| SYSCTRL_DFLLMUL_MUL(48000);
uint32_t coarse = (*((uint32_t*)FUSES_DFLL48M_COARSE_CAL_ADDR) & FUSES_DFLL48M_COARSE_CAL_Msk)
>> FUSES_DFLL48M_COARSE_CAL_Pos;
if (coarse == 0x3f) {
coarse = 0x1f;
}
uint32_t fine = 512;
SYSCTRL->DFLLVAL.reg = SYSCTRL_DFLLVAL_COARSE(coarse) | SYSCTRL_DFLLVAL_FINE(fine);
SYSCTRL->DFLLCTRL.reg = SYSCTRL_DFLLCTRL_CCDIS | SYSCTRL_DFLLCTRL_USBCRM
| SYSCTRL_DFLLCTRL_MODE | SYSCTRL_DFLLCTRL_ENABLE;
while (!SYSCTRL->PCLKSR.bit.DFLLRDY) {}
GCLK->GENDIV.reg = GCLK_GENDIV_ID(0) | GCLK_GENDIV_DIV(1);
GCLK->GENCTRL.reg = GCLK_GENCTRL_GENEN | GCLK_GENCTRL_SRC_DFLL48M | GCLK_GENCTRL_ID(0);
while (GCLK->STATUS.bit.SYNCBUSY) { }
// Configure PA10 as output for LED
PORT->Group[0].DIRSET.reg = 1 << 10;
#elif defined(MCU_SAMD51)
GCLK->GENCTRL[1].reg = 1 << GCLK_GENCTRL_DIV_Pos | GCLK_GENCTRL_GENEN | GCLK_GENCTRL_SRC_DFLL;
while (GCLK->SYNCBUSY.bit.GENCTRL1) { }
// Configure PA22 as output for LED
PORT->Group[0].DIRSET.reg = 1 << 22;
#endif
SysTick_Config(CPU_FREQ / 1000);
uart0_init();
usb_init();
}

View File

@ -0,0 +1,53 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Damien P. George
*
* 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.
*/
#ifndef MICROPY_INCLUDED_SAMD_SAMD_SOC_H
#define MICROPY_INCLUDED_SAMD_SAMD_SOC_H
#include <stdint.h>
#include "sam.h"
#if defined(MCU_SAMD21)
#define CPU_FREQ (48000000)
#define USARTx SERCOM0
#elif defined(MCU_SAMD51)
#define CPU_FREQ (48000000)
#define USARTx SERCOM3
#endif
void samd_init(void);
void samd_main(void);
void USB_Handler_wrapper(void);
void USB_0_Handler_wrapper(void);
void USB_1_Handler_wrapper(void);
void USB_2_Handler_wrapper(void);
void USB_3_Handler_wrapper(void);
#endif // MICROPY_INCLUDED_SAMD_SAMD_SOC_H

View File

@ -0,0 +1,37 @@
/* Define output sections */
SECTIONS
{
.text :
{
. = ALIGN(4);
KEEP(*(.isr_vector))
*(.text)
*(.text*)
*(.rodata)
*(.rodata*)
. = ALIGN(4);
_etext = .;
_sidata = _etext;
} >FLASH
.data : AT ( _sidata )
{
. = ALIGN(4);
_sdata = .;
*(.data)
*(.data*)
. = ALIGN(4);
_edata = .;
} >RAM
.bss :
{
. = ALIGN(4);
_sbss = .;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .;
} >RAM
}

View File

@ -0,0 +1,47 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Damien P. George
*
* 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.
*/
#ifndef MICROPY_INCLUDED_SAMD_TUSB_CONFIG_H
#define MICROPY_INCLUDED_SAMD_TUSB_CONFIG_H
// Common configuration
#if defined(MCU_SAMD21)
#define CFG_TUSB_MCU OPT_MCU_SAMD21
#elif defined(MCU_SAMD51)
#define CFG_TUSB_MCU OPT_MCU_SAMD51
#endif
#define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE
#define CFG_TUSB_MEM_SECTION
#define CFG_TUSB_MEM_ALIGN TU_ATTR_ALIGNED(4)
// Device configuration
#define CFG_TUD_ENDOINT0_SIZE (64)
#define CFG_TUD_CDC (1)
#define CFG_TUD_CDC_RX_BUFSIZE (64)
#define CFG_TUD_CDC_TX_BUFSIZE (64)
#endif // MICROPY_INCLUDED_SAMD_TUSB_CONFIG_H

View File

@ -0,0 +1,146 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Damien P. George
*
* 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.
*/
#include "samd_soc.h"
#include "tusb.h"
#define USBD_VID (0xf055)
#define USBD_PID (0x9802)
#define USBD_DESC_LEN (TUD_CONFIG_DESC_LEN + TUD_CDC_DESC_LEN)
#define USBD_MAX_POWER_MA (250)
#define USBD_ITF_CDC (0) // needs 2 interfaces
#define USBD_ITF_MAX (2)
#define USBD_CDC_EP_CMD (0x81)
#define USBD_CDC_EP_OUT (0x02)
#define USBD_CDC_EP_IN (0x82)
#define USBD_CDC_CMD_MAX_SIZE (8)
#define USBD_STR_0 (0x00)
#define USBD_STR_MANUF (0x01)
#define USBD_STR_PRODUCT (0x02)
#define USBD_STR_SERIAL (0x03)
#define USBD_STR_CDC (0x04)
// Note: descriptors returned from callbacks must exist long enough for transfer to complete
static const tusb_desc_device_t usbd_desc_device = {
.bLength = sizeof(tusb_desc_device_t),
.bDescriptorType = TUSB_DESC_DEVICE,
.bcdUSB = 0x0200,
.bDeviceClass = TUSB_CLASS_MISC,
.bDeviceSubClass = MISC_SUBCLASS_COMMON,
.bDeviceProtocol = MISC_PROTOCOL_IAD,
.bMaxPacketSize0 = CFG_TUD_ENDOINT0_SIZE,
.idVendor = USBD_VID,
.idProduct = USBD_PID,
.bcdDevice = 0x0100,
.iManufacturer = USBD_STR_MANUF,
.iProduct = USBD_STR_PRODUCT,
.iSerialNumber = USBD_STR_SERIAL,
.bNumConfigurations = 1,
};
static const uint8_t usbd_desc_cfg[USBD_DESC_LEN] = {
TUD_CONFIG_DESCRIPTOR(USBD_ITF_MAX, USBD_STR_0, USBD_DESC_LEN,
TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, USBD_MAX_POWER_MA),
TUD_CDC_DESCRIPTOR(USBD_ITF_CDC, USBD_STR_CDC, USBD_CDC_EP_CMD,
USBD_CDC_CMD_MAX_SIZE, USBD_CDC_EP_OUT, USBD_CDC_EP_IN, CFG_TUD_CDC_RX_BUFSIZE),
};
static const char *const usbd_desc_str[] = {
[USBD_STR_MANUF] = "MicroPython",
[USBD_STR_PRODUCT] = "Board in FS mode",
[USBD_STR_SERIAL] = "000000000000", // TODO
[USBD_STR_CDC] = "Board CDC",
};
const uint8_t *tud_descriptor_device_cb(void) {
return (const uint8_t*)&usbd_desc_device;
}
const uint8_t *tud_descriptor_configuration_cb(uint8_t index) {
(void)index;
return usbd_desc_cfg;
}
const uint16_t *tud_descriptor_string_cb(uint8_t index) {
#define DESC_STR_MAX (20)
static uint16_t desc_str[DESC_STR_MAX];
uint8_t len;
if (index == 0) {
desc_str[1] = 0x0409; // supported language is English
len = 1;
} else {
if (index >= sizeof(usbd_desc_str) / sizeof(usbd_desc_str[0])) {
return NULL;
}
const char* str = usbd_desc_str[index];
for (len = 0; len < DESC_STR_MAX - 1 && str[len]; ++len) {
desc_str[1 + len] = str[len];
}
}
// first byte is len, second byte is string type
desc_str[0] = TUD_DESC_STR_HEADER(len);
return desc_str;
}
#if defined(MCU_SAMD21)
void USB_Handler_wrapper(void) {
USB_Handler();
tud_task();
}
#elif defined(MCU_SAMD51)
void USB_0_Handler_wrapper(void) {
USB_0_Handler();
tud_task();
}
void USB_1_Handler_wrapper(void) {
USB_1_Handler();
tud_task();
}
void USB_2_Handler_wrapper(void) {
USB_2_Handler();
tud_task();
}
void USB_3_Handler_wrapper(void) {
USB_3_Handler();
tud_task();
}
#endif