From 2499c9382d4ff0d67106f6dc6cd4a9dfbd0be20e Mon Sep 17 00:00:00 2001 From: Scott Shawcroft Date: Fri, 17 Sep 2021 16:51:34 -0700 Subject: [PATCH 01/51] rpi start. doesn't work --- .../boards/raspberrypi_cm4/board.h | 38 + .../boards/raspberrypi_cm4/board.mk | 0 hw/bsp/raspberrypi4/family.c | 151 ++ hw/bsp/raspberrypi4/family.mk | 37 + hw/mcu/broadcom/bcm2711/boot.s | 170 ++ hw/mcu/broadcom/bcm2711/interrupts.c | 26 + hw/mcu/broadcom/bcm2711/interrupts.h | 8 + hw/mcu/broadcom/bcm2711/io.c | 168 ++ hw/mcu/broadcom/bcm2711/io.h | 13 + hw/mcu/broadcom/bcm2711/link.ld | 20 + src/class/msc/msc_device.c | 6 +- src/device/dcd_attr.h | 4 + src/portable/broadcom/synopsys/dcd_synopsys.c | 1212 ++++++++++++++ .../broadcom/synopsys/synopsys_common.h | 1465 +++++++++++++++++ src/tusb_option.h | 3 + 15 files changed, 3318 insertions(+), 3 deletions(-) create mode 100644 hw/bsp/raspberrypi4/boards/raspberrypi_cm4/board.h create mode 100644 hw/bsp/raspberrypi4/boards/raspberrypi_cm4/board.mk create mode 100644 hw/bsp/raspberrypi4/family.c create mode 100644 hw/bsp/raspberrypi4/family.mk create mode 100644 hw/mcu/broadcom/bcm2711/boot.s create mode 100644 hw/mcu/broadcom/bcm2711/interrupts.c create mode 100644 hw/mcu/broadcom/bcm2711/interrupts.h create mode 100644 hw/mcu/broadcom/bcm2711/io.c create mode 100644 hw/mcu/broadcom/bcm2711/io.h create mode 100644 hw/mcu/broadcom/bcm2711/link.ld create mode 100644 src/portable/broadcom/synopsys/dcd_synopsys.c create mode 100644 src/portable/broadcom/synopsys/synopsys_common.h diff --git a/hw/bsp/raspberrypi4/boards/raspberrypi_cm4/board.h b/hw/bsp/raspberrypi4/boards/raspberrypi_cm4/board.h new file mode 100644 index 000000000..1d3565d5c --- /dev/null +++ b/hw/bsp/raspberrypi4/boards/raspberrypi_cm4/board.h @@ -0,0 +1,38 @@ +/* + * 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 + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/raspberrypi4/boards/raspberrypi_cm4/board.mk b/hw/bsp/raspberrypi4/boards/raspberrypi_cm4/board.mk new file mode 100644 index 000000000..e69de29bb diff --git a/hw/bsp/raspberrypi4/family.c b/hw/bsp/raspberrypi4/family.c new file mode 100644 index 000000000..b2665f42d --- /dev/null +++ b/hw/bsp/raspberrypi4/family.c @@ -0,0 +1,151 @@ +/* + * 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 "board.h" + +#include "io.h" + +//--------------------------------------------------------------------+ +// Forward USB interrupt events to TinyUSB IRQ Handler +//--------------------------------------------------------------------+ +void OTG_FS_IRQHandler(void) +{ + tud_int_handler(0); +} + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM +//--------------------------------------------------------------------+ + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void print(void) { + const char* greeting2 = "hello from cm100\r\n"; + board_uart_write(greeting2, strlen(greeting2)); +} + +void board_init(void) +{ + gpio_initOutputPinWithPullNone(18); + gpio_setPinOutputBool(18, true); + gpio_initOutputPinWithPullNone(42); + // gpio_initOutputPinWithPullNone(23); + // gpio_initOutputPinWithPullNone(24); + // gpio_initOutputPinWithPullNone(25); + gpio_setPinOutputBool(18, false); + uart_init(); + gpio_setPinOutputBool(18, true); + const char* greeting = "hello to gdb2\r\n"; + gpio_setPinOutputBool(18, false); + for (size_t i = 0; i < 5; i++) { + // while (true) { + for (size_t j = 0; j < 1000000; j++) { + __asm__("nop"); + } + gpio_setPinOutputBool(42, true); + gpio_setPinOutputBool(18, true); + for (size_t j = 0; j < 1000000; j++) { + __asm__("nop"); + } + gpio_setPinOutputBool(42, false); + gpio_setPinOutputBool(18, false); + } + // uart_writeText("hello from io\n"); + // gpio_setPinOutputBool(24, true); + board_uart_write(greeting, strlen(greeting)); + // gpio_setPinOutputBool(24, false); + // gpio_setPinOutputBool(25, true); + print(); + // gpio_setPinOutputBool(25, false); + while (true) { + // for (size_t i = 0; i < 5; i++) { + for (size_t j = 0; j < 10000000000; j++) { + __asm__("nop"); + } + gpio_setPinOutputBool(42, true); + for (size_t j = 0; j < 10000000000; j++) { + __asm__("nop"); + } + gpio_setPinOutputBool(42, false); + } + // while (1) uart_update(); +} + +void board_led_write(bool state) +{ + gpio_setPinOutputBool(42, 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) +{ + for (int i = 0; i < len; i++) { + const char* cbuf = buf; + if (cbuf[i] == '\n') { + uart_writeByteBlockingActual('\r'); + } + uart_writeByteBlockingActual(cbuf[i]); + } + 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/raspberrypi4/family.mk b/hw/bsp/raspberrypi4/family.mk new file mode 100644 index 000000000..2d5c78d22 --- /dev/null +++ b/hw/bsp/raspberrypi4/family.mk @@ -0,0 +1,37 @@ +UF2_FAMILY_ID = 0x57755a57 + +include $(TOP)/$(BOARD_PATH)/board.mk + +MCU_DIR = hw/mcu/broadcom/bcm2711 + +CC = clang + +CFLAGS += \ + -Wall \ + -O0 \ + -ffreestanding \ + -nostdlib \ + -nostartfiles \ + -std=c17 \ + -mgeneral-regs-only \ + -DCFG_TUSB_MCU=OPT_MCU_BCM2711 + +SRC_C += \ + src/portable/broadcom/synopsys/dcd_synopsys.c \ + $(MCU_DIR)/io.c \ + $(MCU_DIR)/interrupts.c + +CROSS_COMPILE = aarch64-none-elf- + +SKIP_NANOLIB = 1 + +LD_FILE = $(MCU_DIR)/link.ld + +INC += \ + $(TOP)/$(BOARD_PATH) \ + $(TOP)/$(MCU_DIR) + +SRC_S += $(MCU_DIR)/boot.S + +$(BUILD)/kernel8.img: $(BUILD)/$(PROJECT).elf + $(OBJCOPY) -O binary $^ $@ diff --git a/hw/mcu/broadcom/bcm2711/boot.s b/hw/mcu/broadcom/bcm2711/boot.s new file mode 100644 index 000000000..076b3a76a --- /dev/null +++ b/hw/mcu/broadcom/bcm2711/boot.s @@ -0,0 +1,170 @@ +.section ".text.boot" // Make sure the linker puts this at the start of the kernel image + +.global _start // Execution starts here + +_start: + // Check processor ID is zero (executing on main core), else hang + mrs x1, mpidr_el1 + and x1, x1, #3 + cbz x1, 2f + // We're not on the main core, so hang in an infinite wait loop +1: wfe + b 1b +2: // We're on the main core! + + // Set stack to start below our code + ldr x1, =_start + mov sp, x1 + + adr x0, vectors // load VBAR_EL1 with virtual + // msr vbar_el3, x0 // vector table address + msr vbar_el1, x0 // vector table address + // msr vbar_el2, x0 // vector table address + isb + + // Clean the BSS section + ldr x1, =__bss_start // Start address + ldr w2, =__bss_size // Size of the section +3: cbz w2, 4f // Quit loop if zero + str xzr, [x1], #8 + sub w2, w2, #1 + cbnz w2, 3b // Loop if non-zero + + // Jump to our main() routine in C (make sure it doesn't return) +4: bl main + // In case it does return, halt the master core too + b 1b + +.macro ventry label +.align 7 +b \label +.endm + +.macro handle_invalid_entry type +irq_entry +mov x0, #\type +mrs x1, esr_el1 +mrs x2, elr_el1 +b err_hang +.endm + +.macro irq_entry +sub sp, sp, #272 +stp x0, x1, [sp, #16 * 0] +stp x2, x3, [sp, #16 * 1] +stp x4, x5, [sp, #16 * 2] +stp x6, x7, [sp, #16 * 3] +stp x8, x9, [sp, #16 * 4] +stp x10, x11, [sp, #16 * 5] +stp x12, x13, [sp, #16 * 6] +stp x14, x15, [sp, #16 * 7] +stp x16, x17, [sp, #16 * 8] +stp x18, x19, [sp, #16 * 9] +stp x20, x21, [sp, #16 * 10] +stp x22, x23, [sp, #16 * 11] +stp x24, x25, [sp, #16 * 12] +stp x26, x27, [sp, #16 * 13] +stp x28, x29, [sp, #16 * 14] +str x30, [sp, #16 * 15] +.endm + +.macro irq_exit +ldp x0, x1, [sp, #16 * 0] +ldp x2, x3, [sp, #16 * 1] +ldp x4, x5, [sp, #16 * 2] +ldp x6, x7, [sp, #16 * 3] +ldp x8, x9, [sp, #16 * 4] +ldp x10, x11, [sp, #16 * 5] +ldp x12, x13, [sp, #16 * 6] +ldp x14, x15, [sp, #16 * 7] +ldp x16, x17, [sp, #16 * 8] +ldp x18, x19, [sp, #16 * 9] +ldp x20, x21, [sp, #16 * 10] +ldp x22, x23, [sp, #16 * 11] +ldp x24, x25, [sp, #16 * 12] +ldp x26, x27, [sp, #16 * 13] +ldp x28, x29, [sp, #16 * 14] +ldr x30, [sp, #16 * 15] +add sp, sp, #272 +eret +.endm + + +/* + * Exception vectors. + */ +.align 11 +.globl vectors +vectors: + ventry sync_invalid_el1t // Synchronous EL1t + ventry irq_invalid_el1t // IRQ EL1t + ventry fiq_invalid_el1t // FIQ EL1t + ventry error_invalid_el1t // Error EL1t + + ventry sync_invalid_el1h // Synchronous EL1h + ventry el1_irq // IRQ EL1h + ventry fiq_invalid_el1h // FIQ EL1h + ventry error_invalid_el1h // Error EL1h + + ventry sync_invalid_el0_64 // Synchronous 64-bit EL0 + ventry irq_invalid_el0_64 // IRQ 64-bit EL0 + ventry fiq_invalid_el0_64 // FIQ 64-bit EL0 + ventry error_invalid_el0_64 // Error 64-bit EL0 + + ventry sync_invalid_el0_32 // Synchronous 32-bit EL0 + ventry irq_invalid_el0_32 // IRQ 32-bit EL0 + ventry fiq_invalid_el0_32 // FIQ 32-bit EL0 + ventry error_invalid_el0_32 // Error 32-bit EL0 + +sync_invalid_el1t: + handle_invalid_entry 0 + +irq_invalid_el1t: + handle_invalid_entry 1 + +fiq_invalid_el1t: + handle_invalid_entry 2 + +error_invalid_el1t: + handle_invalid_entry 3 + +sync_invalid_el1h: + handle_invalid_entry 4 + +fiq_invalid_el1h: + handle_invalid_entry 5 + +error_invalid_el1h: + handle_invalid_entry 6 + +sync_invalid_el0_64: + handle_invalid_entry 7 + +irq_invalid_el0_64: + handle_invalid_entry 8 + +fiq_invalid_el0_64: + handle_invalid_entry 9 + +error_invalid_el0_64: + handle_invalid_entry 10 + +sync_invalid_el0_32: + handle_invalid_entry 11 + +irq_invalid_el0_32: + handle_invalid_entry 12 + +fiq_invalid_el0_32: + handle_invalid_entry 13 + +error_invalid_el0_32: + handle_invalid_entry 14 + +el1_irq: + irq_entry + bl handle_irq + irq_exit + +.globl err_hang +err_hang: b err_hang diff --git a/hw/mcu/broadcom/bcm2711/interrupts.c b/hw/mcu/broadcom/bcm2711/interrupts.c new file mode 100644 index 000000000..cb5607526 --- /dev/null +++ b/hw/mcu/broadcom/bcm2711/interrupts.c @@ -0,0 +1,26 @@ +#include +#include + +void disable_async_interrupts(void) { + +} + +void enable_async_interrupts(void) { + +} + +void Default_Handler(void) { + while (true) {} +} + +__attribute__((weak)) void handle_irq(void) { + unsigned int irq = *((volatile uint32_t*) 0x3F00B204); + switch (irq) { + // case (SYSTEM_TIMER_IRQ_1): + // handle_timer_irq(); + // break; + default: + // printf("Unknown pending irq: %x\r\n", irq); + Default_Handler(); + } +} \ No newline at end of file diff --git a/hw/mcu/broadcom/bcm2711/interrupts.h b/hw/mcu/broadcom/bcm2711/interrupts.h new file mode 100644 index 000000000..5f36d6daa --- /dev/null +++ b/hw/mcu/broadcom/bcm2711/interrupts.h @@ -0,0 +1,8 @@ +#pragma once + +void disable_async_interrupts(void); +void enable_async_interrupts(void); + +#define GIC_BASE 0x4c0040000 +#define NUM_CPUS 4 +#define NUM_SPIS 192 diff --git a/hw/mcu/broadcom/bcm2711/io.c b/hw/mcu/broadcom/bcm2711/io.c new file mode 100644 index 000000000..213d6f2fb --- /dev/null +++ b/hw/mcu/broadcom/bcm2711/io.c @@ -0,0 +1,168 @@ +// From: https://github.com/isometimes/rpi4-osdev/blob/master/part4-miniuart/io.c +// CC-0 License + +// GPIO + +enum { + PERIPHERAL_BASE = 0xFE000000, + GPFSEL0 = PERIPHERAL_BASE + 0x200000, + GPSET0 = PERIPHERAL_BASE + 0x20001C, + GPCLR0 = PERIPHERAL_BASE + 0x200028, + GPPUPPDN0 = PERIPHERAL_BASE + 0x2000E4 +}; + +enum { + GPIO_MAX_PIN = 53, + GPIO_FUNCTION_OUT = 1, + GPIO_FUNCTION_ALT5 = 2, + GPIO_FUNCTION_ALT3 = 7 +}; + +enum { + Pull_None = 0, + Pull_Down = 1, // Are down and up the right way around? + Pull_Up = 2 +}; + +void mmio_write(long reg, unsigned int val) { *(volatile unsigned int *)reg = val; } +unsigned int mmio_read(long reg) { return *(volatile unsigned int *)reg; } + +unsigned int gpio_call(unsigned int pin_number, unsigned int value, unsigned int base, unsigned int field_size, unsigned int field_max) { + unsigned int field_mask = (1 << field_size) - 1; + + if (pin_number > field_max) return 0; + if (value > field_mask) return 0; + + unsigned int num_fields = 32 / field_size; + unsigned int reg = base + ((pin_number / num_fields) * 4); + unsigned int shift = (pin_number % num_fields) * field_size; + + unsigned int curval = mmio_read(reg); + curval &= ~(field_mask << shift); + curval |= value << shift; + mmio_write(reg, curval); + + return 1; +} + +unsigned int gpio_set (unsigned int pin_number, unsigned int value) { return gpio_call(pin_number, value, GPSET0, 1, GPIO_MAX_PIN); } +unsigned int gpio_clear (unsigned int pin_number, unsigned int value) { return gpio_call(pin_number, value, GPCLR0, 1, GPIO_MAX_PIN); } +unsigned int gpio_pull (unsigned int pin_number, unsigned int value) { return gpio_call(pin_number, value, GPPUPPDN0, 2, GPIO_MAX_PIN); } +unsigned int gpio_function(unsigned int pin_number, unsigned int value) { return gpio_call(pin_number, value, GPFSEL0, 3, GPIO_MAX_PIN); } + +void gpio_useAsAlt3(unsigned int pin_number) { + gpio_pull(pin_number, Pull_None); + gpio_function(pin_number, GPIO_FUNCTION_ALT3); +} + +void gpio_useAsAlt5(unsigned int pin_number) { + gpio_pull(pin_number, Pull_None); + gpio_function(pin_number, GPIO_FUNCTION_ALT5); +} + +void gpio_initOutputPinWithPullNone(unsigned int pin_number) { + gpio_pull(pin_number, Pull_None); + gpio_function(pin_number, GPIO_FUNCTION_OUT); +} + +void gpio_setPinOutputBool(unsigned int pin_number, unsigned int onOrOff) { + if (onOrOff) { + gpio_set(pin_number, 1); + } else { + gpio_clear(pin_number, 1); + } +} + +// UART + +enum { + AUX_BASE = PERIPHERAL_BASE + 0x215000, + AUX_IRQ = AUX_BASE, + AUX_ENABLES = AUX_BASE + 4, + AUX_MU_IO_REG = AUX_BASE + 64, + AUX_MU_IER_REG = AUX_BASE + 68, + AUX_MU_IIR_REG = AUX_BASE + 72, + AUX_MU_LCR_REG = AUX_BASE + 76, + AUX_MU_MCR_REG = AUX_BASE + 80, + AUX_MU_LSR_REG = AUX_BASE + 84, + AUX_MU_MSR_REG = AUX_BASE + 88, + AUX_MU_SCRATCH = AUX_BASE + 92, + AUX_MU_CNTL_REG = AUX_BASE + 96, + AUX_MU_STAT_REG = AUX_BASE + 100, + AUX_MU_BAUD_REG = AUX_BASE + 104, + AUX_UART_CLOCK = 500000000, + UART_MAX_QUEUE = 16 * 1024 +}; + +#define AUX_MU_BAUD(baud) ((AUX_UART_CLOCK/(baud*8))-1) + +unsigned char uart_output_queue[UART_MAX_QUEUE]; +unsigned int uart_output_queue_write = 0; +unsigned int uart_output_queue_read = 0; + +void uart_init(void) { + mmio_write(AUX_ENABLES, 1); //enable UART1 + mmio_write(AUX_MU_IER_REG, 0); + mmio_write(AUX_MU_CNTL_REG, 0); + mmio_write(AUX_MU_LCR_REG, 3); //8 bits + mmio_write(AUX_MU_MCR_REG, 0); + mmio_write(AUX_MU_IER_REG, 0); + mmio_write(AUX_MU_IIR_REG, 0xC6); //disable interrupts + mmio_write(AUX_MU_BAUD_REG, AUX_MU_BAUD(115200)); + gpio_useAsAlt5(14); + gpio_useAsAlt5(15); + mmio_write(AUX_MU_CNTL_REG, 3); //enable RX/TX +} + +unsigned int uart_isOutputQueueEmpty(void) { + return uart_output_queue_read == uart_output_queue_write; +} + +unsigned int uart_isReadByteReady(void) { return mmio_read(AUX_MU_LSR_REG) & 0x01; } +unsigned int uart_isWriteByteReady(void) { return mmio_read(AUX_MU_LSR_REG) & 0x20; } + +unsigned char uart_readByte(void) { + while (!uart_isReadByteReady()); + return (unsigned char)mmio_read(AUX_MU_IO_REG); +} + +void uart_writeByteBlockingActual(unsigned char ch) { + while (!uart_isWriteByteReady()); + mmio_write(AUX_MU_IO_REG, (unsigned int)ch); +} + +void uart_loadOutputFifo(void) { + while (!uart_isOutputQueueEmpty() && uart_isWriteByteReady()) { + uart_writeByteBlockingActual(uart_output_queue[uart_output_queue_read]); + uart_output_queue_read = (uart_output_queue_read + 1) & (UART_MAX_QUEUE - 1); // Don't overrun + } +} + +void uart_writeByteBlocking(unsigned char ch) { + unsigned int next = (uart_output_queue_write + 1) & (UART_MAX_QUEUE - 1); // Don't overrun + + while (next == uart_output_queue_read) uart_loadOutputFifo(); + + uart_output_queue[uart_output_queue_write] = ch; + uart_output_queue_write = next; +} + +void uart_writeText(const char *buffer) { + while (*buffer) { + if (*buffer == '\n') uart_writeByteBlocking('\r'); + uart_writeByteBlocking(*buffer++); + } +} + +void uart_drainOutputQueue(void) { + while (!uart_isOutputQueueEmpty()) uart_loadOutputFifo(); +} + +void uart_update(void) { + uart_loadOutputFifo(); + + if (uart_isReadByteReady()) { + unsigned char ch = uart_readByte(); + if (ch == '\r') uart_writeText("\n"); else uart_writeByteBlocking(ch); + } +} diff --git a/hw/mcu/broadcom/bcm2711/io.h b/hw/mcu/broadcom/bcm2711/io.h new file mode 100644 index 000000000..9f70ce504 --- /dev/null +++ b/hw/mcu/broadcom/bcm2711/io.h @@ -0,0 +1,13 @@ +// From: https://github.com/isometimes/rpi4-osdev/blob/master/part4-miniuart/io.h +// CC-0 License + +void uart_init(void); +void uart_writeText(const char *buffer); +void uart_loadOutputFifo(void); +unsigned char uart_readByte(void); +unsigned int uart_isReadByteReady(void); +void uart_writeByteBlocking(unsigned char ch); +void uart_update(void); +void gpio_setPinOutputBool(unsigned int pin_number, unsigned int onOrOff); +void uart_writeByteBlockingActual(unsigned char ch); +void gpio_initOutputPinWithPullNone(unsigned int pin_number); diff --git a/hw/mcu/broadcom/bcm2711/link.ld b/hw/mcu/broadcom/bcm2711/link.ld new file mode 100644 index 000000000..0d5ebe2ab --- /dev/null +++ b/hw/mcu/broadcom/bcm2711/link.ld @@ -0,0 +1,20 @@ +SECTIONS +{ + . = 0x80000; /* Kernel load address for AArch64 */ + .text : { KEEP(*(.text.boot)) *(.text .text.* .gnu.linkonce.t*) } + .rodata : { *(.rodata .rodata.* .gnu.linkonce.r*) } + PROVIDE(_data = .); + .data : { *(.data .data.* .gnu.linkonce.d*) } + .bss (NOLOAD) : { + . = ALIGN(16); + __bss_start = .; + *(.bss .bss.*) + *(COMMON) + __bss_end = .; + } + _end = .; + end = .; + + /DISCARD/ : { *(.comment) *(.gnu*) *(.note*) *(.eh_frame*) } +} +__bss_size = (__bss_end - __bss_start)>>3; diff --git a/src/class/msc/msc_device.c b/src/class/msc/msc_device.c index 0fd592129..5eb28e694 100644 --- a/src/class/msc/msc_device.c +++ b/src/class/msc/msc_device.c @@ -476,7 +476,7 @@ bool mscd_xfer_cb(uint8_t rhport, uint8_t ep_addr, xfer_result_t event, uint32_t if (p_cbw->total_bytes) { // 6.7 The 13 Cases: case 4 (Hi > Dn) - TU_LOG(MSC_DEBUG, " SCSI case 4 (Hi > Dn): %lu\r\n", p_cbw->total_bytes); + // TU_LOG(MSC_DEBUG, " SCSI case 4 (Hi > Dn): %lu\r\n", p_cbw->total_bytes); fail_scsi_op(rhport, p_msc, MSC_CSW_STATUS_FAILED); }else { @@ -489,7 +489,7 @@ bool mscd_xfer_cb(uint8_t rhport, uint8_t ep_addr, xfer_result_t event, uint32_t if ( p_cbw->total_bytes == 0 ) { // 6.7 The 13 Cases: case 2 (Hn < Di) - TU_LOG(MSC_DEBUG, " SCSI case 2 (Hn < Di): %lu\r\n", p_cbw->total_bytes); + // TU_LOG(MSC_DEBUG, " SCSI case 2 (Hn < Di): %lu\r\n", p_cbw->total_bytes); fail_scsi_op(rhport, p_msc, MSC_CSW_STATUS_FAILED); }else { @@ -604,7 +604,7 @@ bool mscd_xfer_cb(uint8_t rhport, uint8_t ep_addr, xfer_result_t event, uint32_t if ( (p_cbw->total_bytes > p_msc->xferred_len) && is_data_in(p_cbw->dir) ) { // 6.7 The 13 Cases: case 5 (Hi > Di): STALL before status - TU_LOG(MSC_DEBUG, " SCSI case 5 (Hi > Di): %lu > %lu\r\n", p_cbw->total_bytes, p_msc->xferred_len); + // TU_LOG(MSC_DEBUG, " SCSI case 5 (Hi > Di): %lu > %lu\r\n", p_cbw->total_bytes, p_msc->xferred_len); usbd_edpt_stall(rhport, p_msc->ep_in); }else { diff --git a/src/device/dcd_attr.h b/src/device/dcd_attr.h index a35fc0ac5..9e833c7bb 100644 --- a/src/device/dcd_attr.h +++ b/src/device/dcd_attr.h @@ -151,6 +151,10 @@ #elif TU_CHECK_MCU(GD32VF103) #define DCD_ATTR_ENDPOINT_MAX 4 +//------------- Broadcom -------------// +#elif TU_CHECK_MCU(BCM2711) + #define DCD_ATTR_ENDPOINT_MAX 8 + #else #warning "DCD_ATTR_ENDPOINT_MAX is not defined for this MCU, default to 8" #define DCD_ATTR_ENDPOINT_MAX 8 diff --git a/src/portable/broadcom/synopsys/dcd_synopsys.c b/src/portable/broadcom/synopsys/dcd_synopsys.c new file mode 100644 index 000000000..5967565a5 --- /dev/null +++ b/src/portable/broadcom/synopsys/dcd_synopsys.c @@ -0,0 +1,1212 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2018 Scott Shawcroft, 2019 William D. Jones for Adafruit Industries + * Copyright (c) 2019 Ha Thach (tinyusb.org) + * Copyright (c) 2020 Jan Duempelmann + * Copyright (c) 2020 Reinhard Panhuber + * + * 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 "tusb_option.h" + +#include "synopsys_common.h" + +// Since TinyUSB doesn't use SOF for now, and this interrupt too often (1ms interval) +// We disable SOF for now until needed later on +#define USE_SOF 0 + +#if TUSB_OPT_DEVICE_ENABLED && \ + ( (CFG_TUSB_MCU == OPT_MCU_BCM2711 ) \ + ) + +// EP_MAX : Max number of bi-directional endpoints including EP0 +// EP_FIFO_SIZE : Size of dedicated USB SRAM +#if CFG_TUSB_MCU == OPT_MCU_BCM2711 +// #include "bcm2711.h" +#define EP_MAX_FS 8 +#define EP_FIFO_SIZE_FS 4096 +#define EP_MAX_HS 8 +#define EP_FIFO_SIZE_HS 4096 +#else +#error "Unsupported MCUs" +#endif + +#define EP_MAX 8 +#define EP_FIFO_SIZE 4096 + +// Info on values here: https://github.com/torvalds/linux/blob/79160a603bdb51916226caf4a6616cc4e1c58a58/Documentation/devicetree/bindings/usb/dwc2.yaml + +// From: https://github.com/raspberrypi/linux/blob/rpi-5.10.y/arch/arm/boot/dts/bcm283x.dtsi +// usb: usb@7e980000 { +// compatible = "brcm,bcm2835-usb"; +// reg = <0x7e980000 0x10000>; +// interrupts = <1 9>; +// #address-cells = <1>; +// #size-cells = <0>; +// clocks = <&clk_usb>; +// clock-names = "otg"; +// phys = <&usbphy>; +// phy-names = "usb2-phy"; +// }; + +// From: https://github.com/raspberrypi/linux/blob/rpi-5.10.y/arch/arm/boot/dts/bcm283x-rpi-usb-otg.dtsi +// SPDX-License-Identifier: GPL-2.0 +// &usb { +// dr_mode = "otg"; +// g-rx-fifo-size = <256>; +// g-np-tx-fifo-size = <32>; + +// * According to dwc2 the sum of all device EP +// * fifo sizes shouldn't exceed 3776 bytes. + +// g-tx-fifo-size = <256 256 512 512 512 768 768>; +// }; + +// From: https://github.com/raspberrypi/linux/blob/rpi-5.10.y/arch/arm/boot/dts/bcm2711-rpi.dtsi +// &usb { +// /* Enable the FIQ support */ +// reg = <0x7e980000 0x10000>, +// <0x7e00b200 0x200>; +// interrupts = , +// ; +// status = "disabled"; +// }; + +// From: https://github.com/raspberrypi/linux/blob/rpi-5.10.y/arch/arm/boot/dts/bcm2711.dtsi +// &usb { +// interrupts = ; +// }; + +// From: https://github.com/torvalds/linux/blob/1d597682d3e669ec7021aa33d088ed3d136a5149/drivers/usb/dwc2/params.c +// static void dwc2_set_bcm_params(struct dwc2_hsotg *hsotg) +// { +// struct dwc2_core_params *p = &hsotg->params; + +// p->host_rx_fifo_size = 774; +// p->max_transfer_size = 65535; +// p->max_packet_count = 511; +// p->ahbcfg = 0x10; +// } + +#include "device/dcd.h" + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM +//--------------------------------------------------------------------+ + +#define RHPORT_REGS_BASE 0x7e980000 + +#define GLOBAL_BASE(_port) ((USB_OTG_GlobalTypeDef*) RHPORT_REGS_BASE) +#define DEVICE_BASE(_port) (USB_OTG_DeviceTypeDef *) (RHPORT_REGS_BASE + USB_OTG_DEVICE_BASE) +#define OUT_EP_BASE(_port) (USB_OTG_OUTEndpointTypeDef *) (RHPORT_REGS_BASE + USB_OTG_OUT_ENDPOINT_BASE) +#define IN_EP_BASE(_port) (USB_OTG_INEndpointTypeDef *) (RHPORT_REGS_BASE + USB_OTG_IN_ENDPOINT_BASE) +#define FIFO_BASE(_port, _x) ((volatile uint32_t *) (RHPORT_REGS_BASE + USB_OTG_FIFO_BASE + (_x) * USB_OTG_FIFO_SIZE)) + +enum +{ + DCD_HIGH_SPEED = 0, // Highspeed mode + DCD_FULL_SPEED_USE_HS = 1, // Full speed in Highspeed port (probably with internal PHY) + DCD_FULL_SPEED = 3, // Full speed with internal PHY +}; + +static TU_ATTR_ALIGNED(4) uint32_t _setup_packet[2]; + +typedef struct { + uint8_t * buffer; + tu_fifo_t * ff; + uint16_t total_len; + uint16_t max_size; + uint8_t interval; +} xfer_ctl_t; + +typedef volatile uint32_t * usb_fifo_t; + +xfer_ctl_t xfer_status[EP_MAX][2]; +#define XFER_CTL_BASE(_ep, _dir) &xfer_status[_ep][_dir] + +// EP0 transfers are limited to 1 packet - larger sizes has to be split +static uint16_t ep0_pending[2]; // Index determines direction as tusb_dir_t type + +// TX FIFO RAM allocation so far in words - RX FIFO size is readily available from usb_otg->GRXFSIZ +static uint16_t _allocated_fifo_words_tx; // TX FIFO size in words (IN EPs) +static bool _out_ep_closed; // Flag to check if RX FIFO size needs an update (reduce its size) + +// Calculate the RX FIFO size according to recommendations from reference manual +static inline uint16_t calc_rx_ff_size(uint16_t ep_size) +{ + return 15 + 2*(ep_size/4) + 2*EP_MAX; +} + +static void update_grxfsiz(uint8_t rhport) +{ + (void) rhport; + + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); + + // Determine largest EP size for RX FIFO + uint16_t max_epsize = 0; + for (uint8_t epnum = 0; epnum < EP_MAX; epnum++) + { + max_epsize = tu_max16(max_epsize, xfer_status[epnum][TUSB_DIR_OUT].max_size); + } + + // Update size of RX FIFO + usb_otg->GRXFSIZ = calc_rx_ff_size(max_epsize); +} + +// Setup the control endpoint 0. +static void bus_reset(uint8_t rhport) +{ + (void) rhport; + + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); + + tu_memclr(xfer_status, sizeof(xfer_status)); + _out_ep_closed = false; + + // clear device address + dev->DCFG &= ~USB_OTG_DCFG_DAD_Msk; + + // 1. NAK for all OUT endpoints + for(uint8_t n = 0; n < EP_MAX; n++) { + out_ep[n].DOEPCTL |= USB_OTG_DOEPCTL_SNAK; + } + + // 2. Un-mask interrupt bits + dev->DAINTMSK = (1 << USB_OTG_DAINTMSK_OEPM_Pos) | (1 << USB_OTG_DAINTMSK_IEPM_Pos); + dev->DOEPMSK = USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM; + dev->DIEPMSK = USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM; + + // "USB Data FIFOs" section in reference manual + // Peripheral FIFO architecture + // + // The FIFO is split up in a lower part where the RX FIFO is located and an upper part where the TX FIFOs start. + // We do this to allow the RX FIFO to grow dynamically which is possible since the free space is located + // between the RX and TX FIFOs. This is required by ISO OUT EPs which need a bigger FIFO than the standard + // configuration done below. + // + // Dynamically FIFO sizes are of interest only for ISO EPs since all others are usually not opened and closed. + // All EPs other than ISO are opened as soon as the driver starts up i.e. when the host sends a + // configure interface command. Hence, all IN EPs other the ISO will be located at the top. IN ISO EPs are usually + // opened when the host sends an additional command: setInterface. At this point in time + // the ISO EP will be located next to the free space and can change its size. In case more IN EPs change its size + // an additional memory + // + // --------------- 320 or 1024 ( 1280 or 4096 bytes ) + // | IN FIFO 0 | + // --------------- (320 or 1024) - 16 + // | IN FIFO 1 | + // --------------- (320 or 1024) - 16 - x + // | . . . . | + // --------------- (320 or 1024) - 16 - x - y - ... - z + // | IN FIFO MAX | + // --------------- + // | FREE | + // --------------- GRXFSIZ + // | OUT FIFO | + // | ( Shared ) | + // --------------- 0 + // + // According to "FIFO RAM allocation" section in RM, FIFO RAM are allocated as follows (each word 32-bits): + // - Each EP IN needs at least max packet size, 16 words is sufficient for EP0 IN + // + // - All EP OUT shared a unique OUT FIFO which uses + // - 13 for setup packets + control words (up to 3 setup packets). + // - 1 for global NAK (not required/used here). + // - Largest-EPsize / 4 + 1. ( FS: 64 bytes, HS: 512 bytes). Recommended is "2 x (Largest-EPsize/4) + 1" + // - 2 for each used OUT endpoint + // + // Therefore GRXFSIZ = 13 + 1 + 1 + 2 x (Largest-EPsize/4) + 2 x EPOUTnum + // - FullSpeed (64 Bytes ): GRXFSIZ = 15 + 2 x 16 + 2 x EP_MAX = 47 + 2 x EP_MAX + // - Highspeed (512 bytes): GRXFSIZ = 15 + 2 x 128 + 2 x EP_MAX = 271 + 2 x EP_MAX + // + // NOTE: Largest-EPsize & EPOUTnum is actual used endpoints in configuration. Since DCD has no knowledge + // of the overall picture yet. We will use the worst scenario: largest possible + EP_MAX + // + // For Isochronous, largest EP size can be 1023/1024 for FS/HS respectively. In addition if multiple ISO + // are enabled at least "2 x (Largest-EPsize/4) + 1" are recommended. Maybe provide a macro for application to + // overwrite this. + + #if TUD_OPT_HIGH_SPEED + usb_otg->GRXFSIZ = calc_rx_ff_size(512); + #else + usb_otg->GRXFSIZ = calc_rx_ff_size(64); + #endif + + _allocated_fifo_words_tx = 16; + + // Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) + usb_otg->DIEPTXF0_HNPTXFSIZ = (16 << USB_OTG_TX0FD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + + // Fixed control EP0 size to 64 bytes + in_ep[0].DIEPCTL &= ~(0x03 << USB_OTG_DIEPCTL_MPSIZ_Pos); + xfer_status[0][TUSB_DIR_OUT].max_size = xfer_status[0][TUSB_DIR_IN].max_size = 64; + + out_ep[0].DOEPTSIZ |= (3 << USB_OTG_DOEPTSIZ_STUPCNT_Pos); + + usb_otg->GINTMSK |= USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT; +} + +// Set turn-around timeout according to link speed +extern uint32_t SystemCoreClock; +static void set_turnaround(USB_OTG_GlobalTypeDef * usb_otg, tusb_speed_t speed) +{ + usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; + + if ( speed == TUSB_SPEED_HIGH ) + { + // Use fixed 0x09 for Highspeed + usb_otg->GUSBCFG |= (0x09 << USB_OTG_GUSBCFG_TRDT_Pos); + } + else + { + // Turnaround timeout depends on the MCU clock + uint32_t turnaround; + + if ( SystemCoreClock >= 32000000U ) + turnaround = 0x6U; + else if ( SystemCoreClock >= 27500000U ) + turnaround = 0x7U; + else if ( SystemCoreClock >= 24000000U ) + turnaround = 0x8U; + else if ( SystemCoreClock >= 21800000U ) + turnaround = 0x9U; + else if ( SystemCoreClock >= 20000000U ) + turnaround = 0xAU; + else if ( SystemCoreClock >= 18500000U ) + turnaround = 0xBU; + else if ( SystemCoreClock >= 17200000U ) + turnaround = 0xCU; + else if ( SystemCoreClock >= 16000000U ) + turnaround = 0xDU; + else if ( SystemCoreClock >= 15000000U ) + turnaround = 0xEU; + else + turnaround = 0xFU; + + // Fullspeed depends on MCU clocks, but we will use 0x06 for 32+ Mhz + usb_otg->GUSBCFG |= (turnaround << USB_OTG_GUSBCFG_TRDT_Pos); + } +} + +static tusb_speed_t get_speed(uint8_t rhport) +{ + (void) rhport; + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + uint32_t const enum_spd = (dev->DSTS & USB_OTG_DSTS_ENUMSPD_Msk) >> USB_OTG_DSTS_ENUMSPD_Pos; + return (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL; +} + +static void set_speed(uint8_t rhport, tusb_speed_t speed) +{ + uint32_t bitvalue; + + if ( rhport == 1 ) + { + bitvalue = ((TUSB_SPEED_HIGH == speed) ? DCD_HIGH_SPEED : DCD_FULL_SPEED_USE_HS); + } + else + { + bitvalue = DCD_FULL_SPEED; + } + + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + + // Clear and set speed bits + dev->DCFG &= ~(3 << USB_OTG_DCFG_DSPD_Pos); + dev->DCFG |= (bitvalue << USB_OTG_DCFG_DSPD_Pos); +} + +#if defined(USB_HS_PHYC) +static bool USB_HS_PHYCInit(void) +{ + USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef*) USB_HS_PHYC_CONTROLLER_BASE; + + // Enable LDO + usb_hs_phyc->USB_HS_PHYC_LDO |= USB_HS_PHYC_LDO_ENABLE; + + // Wait until LDO ready + while ( 0 == (usb_hs_phyc->USB_HS_PHYC_LDO & USB_HS_PHYC_LDO_STATUS) ) {} + + uint32_t phyc_pll = 0; + + // TODO Try to get HSE_VALUE from registers instead of depending CFLAGS + switch ( HSE_VALUE ) + { + case 12000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12MHZ ; break; + case 12500000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12_5MHZ ; break; + case 16000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_16MHZ ; break; + case 24000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_24MHZ ; break; + case 25000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_25MHZ ; break; + case 32000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_Msk ; break; // Value not defined in header + default: + TU_ASSERT(0); + } + usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll; + + // Control the tuning interface of the High Speed PHY + // Use magic value (USB_HS_PHYC_TUNE_VALUE) from ST driver + usb_hs_phyc->USB_HS_PHYC_TUNE |= 0x00000F13U; + + // Enable PLL internal PHY + usb_hs_phyc->USB_HS_PHYC_PLL |= USB_HS_PHYC_PLL_PLLEN; + + // Original ST code has 2 ms delay for PLL stabilization. + // Primitive test shows that more than 10 USB un/replug cycle showed no error with enumeration + + return true; +} +#endif + +static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t const dir, uint16_t const num_packets, uint16_t total_bytes) +{ + (void) rhport; + + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); + + // EP0 is limited to one packet each xfer + // We use multiple transaction of xfer->max_size length to get a whole transfer done + if(epnum == 0) { + xfer_ctl_t * const xfer = XFER_CTL_BASE(epnum, dir); + total_bytes = tu_min16(ep0_pending[dir], xfer->max_size); + ep0_pending[dir] -= total_bytes; + } + + // IN and OUT endpoint xfers are interrupt-driven, we just schedule them here. + if(dir == TUSB_DIR_IN) { + // A full IN transfer (multiple packets, possibly) triggers XFRC. + in_ep[epnum].DIEPTSIZ = (num_packets << USB_OTG_DIEPTSIZ_PKTCNT_Pos) | + ((total_bytes << USB_OTG_DIEPTSIZ_XFRSIZ_Pos) & USB_OTG_DIEPTSIZ_XFRSIZ_Msk); + + in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_EPENA | USB_OTG_DIEPCTL_CNAK; + // For ISO endpoint set correct odd/even bit for next frame. + if ((in_ep[epnum].DIEPCTL & USB_OTG_DIEPCTL_EPTYP) == USB_OTG_DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) + { + // Take odd/even bit from frame counter. + uint32_t const odd_frame_now = (dev->DSTS & (1u << USB_OTG_DSTS_FNSOF_Pos)); + in_ep[epnum].DIEPCTL |= (odd_frame_now ? USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Msk : USB_OTG_DIEPCTL_SODDFRM_Msk); + } + // Enable fifo empty interrupt only if there are something to put in the fifo. + if(total_bytes != 0) { + dev->DIEPEMPMSK |= (1 << epnum); + } + } else { + // A full OUT transfer (multiple packets, possibly) triggers XFRC. + out_ep[epnum].DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT_Msk | USB_OTG_DOEPTSIZ_XFRSIZ); + out_ep[epnum].DOEPTSIZ |= (num_packets << USB_OTG_DOEPTSIZ_PKTCNT_Pos) | + ((total_bytes << USB_OTG_DOEPTSIZ_XFRSIZ_Pos) & USB_OTG_DOEPTSIZ_XFRSIZ_Msk); + + out_ep[epnum].DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + if ((out_ep[epnum].DOEPCTL & USB_OTG_DOEPCTL_EPTYP) == USB_OTG_DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) + { + // Take odd/even bit from frame counter. + uint32_t const odd_frame_now = (dev->DSTS & (1u << USB_OTG_DSTS_FNSOF_Pos)); + out_ep[epnum].DOEPCTL |= (odd_frame_now ? USB_OTG_DOEPCTL_SD0PID_SEVNFRM_Msk : USB_OTG_DOEPCTL_SODDFRM_Msk); + } + } +} + +/*------------------------------------------------------------------*/ +/* Controller API + *------------------------------------------------------------------*/ +void dcd_init (uint8_t rhport) +{ + // Programming model begins in the last section of the chapter on the USB + // peripheral in each Reference Manual. + + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); + + // No HNP/SRP (no OTG support), program timeout later. + if ( rhport == 1 ) + { + // On selected MCUs HS port1 can be used with external PHY via ULPI interface +#if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED + // deactivate internal PHY + usb_otg->GCCFG &= ~USB_OTG_GCCFG_PWRDWN; + + // Init The UTMI Interface + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); + + // Select default internal VBUS Indicator and Drive for ULPI + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); +#else + usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; +#endif + +#if defined(USB_HS_PHYC) + // Highspeed with embedded UTMI PHYC + + // Select UTMI Interface + usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_ULPI_UTMI_SEL; + usb_otg->GCCFG |= USB_OTG_GCCFG_PHYHSEN; + + // Enables control of a High Speed USB PHY + USB_HS_PHYCInit(); +#endif + } else + { + // Enable internal PHY + usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; + } + + // Reset core after selecting PHY + // Wait AHB IDLE, reset then wait until it is cleared + while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U) {} + usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; + while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST) {} + + // Restart PHY clock + *((volatile uint32_t *)(RHPORT_REGS_BASE + USB_OTG_PCGCCTL_BASE)) = 0; + + // Clear all interrupts + usb_otg->GINTSTS |= usb_otg->GINTSTS; + + // Required as part of core initialization. + // TODO: How should mode mismatch be handled? It will cause + // the core to stop working/require reset. + usb_otg->GINTMSK |= USB_OTG_GINTMSK_OTGINT | USB_OTG_GINTMSK_MMISM; + + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + + // If USB host misbehaves during status portion of control xfer + // (non zero-length packet), send STALL back and discard. + dev->DCFG |= USB_OTG_DCFG_NZLSOHSK; + + #if TUD_OPT_HIGH_SPEED + set_speed(rhport, TUSB_SPEED_HIGH); + #else + set_speed(rhport, TUSB_SPEED_FULL); + #endif + + // Enable internal USB transceiver, unless using HS core (port 1) with external PHY. + if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; + + usb_otg->GINTMSK |= USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | + USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_WUIM | + USB_OTG_GINTMSK_RXFLVLM | (USE_SOF ? USB_OTG_GINTMSK_SOFM : 0); + + // Enable global interrupt + usb_otg->GAHBCFG |= USB_OTG_GAHBCFG_GINT; + + dcd_connect(rhport); +} + +void dcd_int_enable (uint8_t rhport) +{ + (void) rhport; + // NVIC_EnableIRQ(RHPORT_IRQn); +} + +void dcd_int_disable (uint8_t rhport) +{ + (void) rhport; + // NVIC_DisableIRQ(RHPORT_IRQn); +} + +void dcd_set_address (uint8_t rhport, uint8_t dev_addr) +{ + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + dev->DCFG = (dev->DCFG & ~USB_OTG_DCFG_DAD_Msk) | (dev_addr << USB_OTG_DCFG_DAD_Pos); + + // Response with status after changing device address + dcd_edpt_xfer(rhport, tu_edpt_addr(0, TUSB_DIR_IN), NULL, 0); +} + +static void remote_wakeup_delay(void) +{ + // try to delay for 1 ms + uint32_t count = SystemCoreClock / 1000; + while ( count-- ) + { + // __NOP(); + } +} + +void dcd_remote_wakeup(uint8_t rhport) +{ + (void) rhport; + + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + + // set remote wakeup + dev->DCTL |= USB_OTG_DCTL_RWUSIG; + + // enable SOF to detect bus resume + usb_otg->GINTSTS = USB_OTG_GINTSTS_SOF; + usb_otg->GINTMSK |= USB_OTG_GINTMSK_SOFM; + + // Per specs: remote wakeup signal bit must be clear within 1-15ms + remote_wakeup_delay(); + + dev->DCTL &= ~USB_OTG_DCTL_RWUSIG; +} + +void dcd_connect(uint8_t rhport) +{ + (void) rhport; + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + dev->DCTL &= ~USB_OTG_DCTL_SDIS; +} + +void dcd_disconnect(uint8_t rhport) +{ + (void) rhport; + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + dev->DCTL |= USB_OTG_DCTL_SDIS; +} + + +/*------------------------------------------------------------------*/ +/* DCD Endpoint port + *------------------------------------------------------------------*/ + +bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) +{ + (void) rhport; + + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); + + uint8_t const epnum = tu_edpt_number(desc_edpt->bEndpointAddress); + uint8_t const dir = tu_edpt_dir(desc_edpt->bEndpointAddress); + + TU_ASSERT(epnum < EP_MAX); + + xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); + xfer->max_size = desc_edpt->wMaxPacketSize.size; + xfer->interval = desc_edpt->bInterval; + + uint16_t const fifo_size = (desc_edpt->wMaxPacketSize.size + 3) / 4; // Round up to next full word + + if(dir == TUSB_DIR_OUT) + { + // Calculate required size of RX FIFO + uint16_t const sz = calc_rx_ff_size(4*fifo_size); + + // If size_rx needs to be extended check if possible and if so enlarge it + if (usb_otg->GRXFSIZ < sz) + { + TU_ASSERT(sz + _allocated_fifo_words_tx <= EP_FIFO_SIZE/4); + + // Enlarge RX FIFO + usb_otg->GRXFSIZ = sz; + } + + out_ep[epnum].DOEPCTL |= (1 << USB_OTG_DOEPCTL_USBAEP_Pos) | + (desc_edpt->bmAttributes.xfer << USB_OTG_DOEPCTL_EPTYP_Pos) | + (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? USB_OTG_DOEPCTL_SD0PID_SEVNFRM : 0) | + (desc_edpt->wMaxPacketSize.size << USB_OTG_DOEPCTL_MPSIZ_Pos); + + dev->DAINTMSK |= (1 << (USB_OTG_DAINTMSK_OEPM_Pos + epnum)); + } + else + { + // "USB Data FIFOs" section in reference manual + // Peripheral FIFO architecture + // + // --------------- 320 or 1024 ( 1280 or 4096 bytes ) + // | IN FIFO 0 | + // --------------- (320 or 1024) - 16 + // | IN FIFO 1 | + // --------------- (320 or 1024) - 16 - x + // | . . . . | + // --------------- (320 or 1024) - 16 - x - y - ... - z + // | IN FIFO MAX | + // --------------- + // | FREE | + // --------------- GRXFSIZ + // | OUT FIFO | + // | ( Shared ) | + // --------------- 0 + // + // In FIFO is allocated by following rules: + // - IN EP 1 gets FIFO 1, IN EP "n" gets FIFO "n". + + // Check if free space is available + TU_ASSERT(_allocated_fifo_words_tx + fifo_size + usb_otg->GRXFSIZ <= EP_FIFO_SIZE/4); + + _allocated_fifo_words_tx += fifo_size; + + TU_LOG(2, " Allocated %u bytes at offset %u", fifo_size*4, EP_FIFO_SIZE-_allocated_fifo_words_tx*4); + + // DIEPTXF starts at FIFO #1. + // Both TXFD and TXSA are in unit of 32-bit words. + usb_otg->DIEPTXF[epnum - 1] = (fifo_size << USB_OTG_DIEPTXF_INEPTXFD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + + in_ep[epnum].DIEPCTL |= (1 << USB_OTG_DIEPCTL_USBAEP_Pos) | + (epnum << USB_OTG_DIEPCTL_TXFNUM_Pos) | + (desc_edpt->bmAttributes.xfer << USB_OTG_DIEPCTL_EPTYP_Pos) | + (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? USB_OTG_DIEPCTL_SD0PID_SEVNFRM : 0) | + (desc_edpt->wMaxPacketSize.size << USB_OTG_DIEPCTL_MPSIZ_Pos); + + dev->DAINTMSK |= (1 << (USB_OTG_DAINTMSK_IEPM_Pos + epnum)); + } + + return true; +} + +// Close all non-control endpoints, cancel all pending transfers if any. +void dcd_edpt_close_all (uint8_t rhport) +{ + (void) rhport; + +// USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); + + // Disable non-control interrupt + dev->DAINTMSK = (1 << USB_OTG_DAINTMSK_OEPM_Pos) | (1 << USB_OTG_DAINTMSK_IEPM_Pos); + + for(uint8_t n = 1; n < EP_MAX; n++) + { + // disable OUT endpoint + out_ep[n].DOEPCTL = 0; + xfer_status[n][TUSB_DIR_OUT].max_size = 0; + + // disable IN endpoint + in_ep[n].DIEPCTL = 0; + xfer_status[n][TUSB_DIR_IN].max_size = 0; + } + + // reset allocated fifo IN + _allocated_fifo_words_tx = 16; +} + +bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t total_bytes) +{ + uint8_t const epnum = tu_edpt_number(ep_addr); + uint8_t const dir = tu_edpt_dir(ep_addr); + + xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); + xfer->buffer = buffer; + xfer->ff = NULL; + xfer->total_len = total_bytes; + + // EP0 can only handle one packet + if(epnum == 0) { + ep0_pending[dir] = total_bytes; + // Schedule the first transaction for EP0 transfer + edpt_schedule_packets(rhport, epnum, dir, 1, ep0_pending[dir]); + return true; + } + + uint16_t num_packets = (total_bytes / xfer->max_size); + uint16_t const short_packet_size = total_bytes % xfer->max_size; + + // Zero-size packet is special case. + if(short_packet_size > 0 || (total_bytes == 0)) { + num_packets++; + } + + // Schedule packets to be sent within interrupt + edpt_schedule_packets(rhport, epnum, dir, num_packets, total_bytes); + + return true; +} + +// The number of bytes has to be given explicitly to allow more flexible control of how many +// bytes should be written and second to keep the return value free to give back a boolean +// success message. If total_bytes is too big, the FIFO will copy only what is available +// into the USB buffer! +bool dcd_edpt_xfer_fifo (uint8_t rhport, uint8_t ep_addr, tu_fifo_t * ff, uint16_t total_bytes) +{ + // USB buffers always work in bytes so to avoid unnecessary divisions we demand item_size = 1 + TU_ASSERT(ff->item_size == 1); + + uint8_t const epnum = tu_edpt_number(ep_addr); + uint8_t const dir = tu_edpt_dir(ep_addr); + + xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); + xfer->buffer = NULL; + xfer->ff = ff; + xfer->total_len = total_bytes; + + uint16_t num_packets = (total_bytes / xfer->max_size); + uint16_t const short_packet_size = total_bytes % xfer->max_size; + + // Zero-size packet is special case. + if(short_packet_size > 0 || (total_bytes == 0)) num_packets++; + + // Schedule packets to be sent within interrupt + edpt_schedule_packets(rhport, epnum, dir, num_packets, total_bytes); + + return true; +} + +static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) +{ + (void) rhport; + + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); + + uint8_t const epnum = tu_edpt_number(ep_addr); + uint8_t const dir = tu_edpt_dir(ep_addr); + + if(dir == TUSB_DIR_IN) { + // Only disable currently enabled non-control endpoint + if ( (epnum == 0) || !(in_ep[epnum].DIEPCTL & USB_OTG_DIEPCTL_EPENA) ){ + in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_SNAK | (stall ? USB_OTG_DIEPCTL_STALL : 0); + } else { + // Stop transmitting packets and NAK IN xfers. + in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_SNAK; + while((in_ep[epnum].DIEPINT & USB_OTG_DIEPINT_INEPNE) == 0); + + // Disable the endpoint. + in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_EPDIS | (stall ? USB_OTG_DIEPCTL_STALL : 0); + while((in_ep[epnum].DIEPINT & USB_OTG_DIEPINT_EPDISD_Msk) == 0); + in_ep[epnum].DIEPINT = USB_OTG_DIEPINT_EPDISD; + } + + // Flush the FIFO, and wait until we have confirmed it cleared. + usb_otg->GRSTCTL |= (epnum << USB_OTG_GRSTCTL_TXFNUM_Pos); + usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_TXFFLSH; + while((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH_Msk) != 0); + } else { + // Only disable currently enabled non-control endpoint + if ( (epnum == 0) || !(out_ep[epnum].DOEPCTL & USB_OTG_DOEPCTL_EPENA) ){ + out_ep[epnum].DOEPCTL |= stall ? USB_OTG_DOEPCTL_STALL : 0; + } else { + // Asserting GONAK is required to STALL an OUT endpoint. + // Simpler to use polling here, we don't use the "B"OUTNAKEFF interrupt + // anyway, and it can't be cleared by user code. If this while loop never + // finishes, we have bigger problems than just the stack. + dev->DCTL |= USB_OTG_DCTL_SGONAK; + while((usb_otg->GINTSTS & USB_OTG_GINTSTS_BOUTNAKEFF_Msk) == 0); + + // Ditto here- disable the endpoint. + out_ep[epnum].DOEPCTL |= USB_OTG_DOEPCTL_EPDIS | (stall ? USB_OTG_DOEPCTL_STALL : 0); + while((out_ep[epnum].DOEPINT & USB_OTG_DOEPINT_EPDISD_Msk) == 0); + out_ep[epnum].DOEPINT = USB_OTG_DOEPINT_EPDISD; + + // Allow other OUT endpoints to keep receiving. + dev->DCTL |= USB_OTG_DCTL_CGONAK; + } + } +} + +/** + * Close an endpoint. + */ +void dcd_edpt_close (uint8_t rhport, uint8_t ep_addr) +{ + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); + + uint8_t const epnum = tu_edpt_number(ep_addr); + uint8_t const dir = tu_edpt_dir(ep_addr); + + dcd_edpt_disable(rhport, ep_addr, false); + + // Update max_size + xfer_status[epnum][dir].max_size = 0; // max_size = 0 marks a disabled EP - required for changing FIFO allocation + + if (dir == TUSB_DIR_IN) + { + uint16_t const fifo_size = (usb_otg->DIEPTXF[epnum - 1] & USB_OTG_DIEPTXF_INEPTXFD_Msk) >> USB_OTG_DIEPTXF_INEPTXFD_Pos; + uint16_t const fifo_start = (usb_otg->DIEPTXF[epnum - 1] & USB_OTG_DIEPTXF_INEPTXSA_Msk) >> USB_OTG_DIEPTXF_INEPTXSA_Pos; + // For now only the last opened endpoint can be closed without fuss. + TU_ASSERT(fifo_start == EP_FIFO_SIZE/4 - _allocated_fifo_words_tx,); + _allocated_fifo_words_tx -= fifo_size; + } + else + { + _out_ep_closed = true; // Set flag such that RX FIFO gets reduced in size once RX FIFO is empty + } +} + +void dcd_edpt_stall (uint8_t rhport, uint8_t ep_addr) +{ + dcd_edpt_disable(rhport, ep_addr, true); +} + +void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) +{ + (void) rhport; + + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); + + uint8_t const epnum = tu_edpt_number(ep_addr); + uint8_t const dir = tu_edpt_dir(ep_addr); + + // Clear stall and reset data toggle + if(dir == TUSB_DIR_IN) { + in_ep[epnum].DIEPCTL &= ~USB_OTG_DIEPCTL_STALL; + in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; + } else { + out_ep[epnum].DOEPCTL &= ~USB_OTG_DOEPCTL_STALL; + out_ep[epnum].DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; + } +} + +/*------------------------------------------------------------------*/ + +// Read a single data packet from receive FIFO +static void read_fifo_packet(uint8_t rhport, uint8_t * dst, uint16_t len) +{ + (void) rhport; + + usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); + + // Reading full available 32 bit words from fifo + uint16_t full_words = len >> 2; + for(uint16_t i = 0; i < full_words; i++) { + uint32_t tmp = *rx_fifo; + dst[0] = tmp & 0x000000FF; + dst[1] = (tmp & 0x0000FF00) >> 8; + dst[2] = (tmp & 0x00FF0000) >> 16; + dst[3] = (tmp & 0xFF000000) >> 24; + dst += 4; + } + + // Read the remaining 1-3 bytes from fifo + uint8_t bytes_rem = len & 0x03; + if(bytes_rem != 0) { + uint32_t tmp = *rx_fifo; + dst[0] = tmp & 0x000000FF; + if(bytes_rem > 1) { + dst[1] = (tmp & 0x0000FF00) >> 8; + } + if(bytes_rem > 2) { + dst[2] = (tmp & 0x00FF0000) >> 16; + } + } +} + +// Write a single data packet to EPIN FIFO +static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, uint16_t len) +{ + (void) rhport; + + usb_fifo_t tx_fifo = FIFO_BASE(rhport, fifo_num); + + // Pushing full available 32 bit words to fifo + uint16_t full_words = len >> 2; + for(uint16_t i = 0; i < full_words; i++){ + *tx_fifo = (src[3] << 24) | (src[2] << 16) | (src[1] << 8) | src[0]; + src += 4; + } + + // Write the remaining 1-3 bytes into fifo + uint8_t bytes_rem = len & 0x03; + if(bytes_rem){ + uint32_t tmp_word = 0; + tmp_word |= src[0]; + if(bytes_rem > 1){ + tmp_word |= src[1] << 8; + } + if(bytes_rem > 2){ + tmp_word |= src[2] << 16; + } + *tx_fifo = tmp_word; + } +} + +static void handle_rxflvl_ints(uint8_t rhport, USB_OTG_OUTEndpointTypeDef * out_ep) { + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); + usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); + + // Pop control word off FIFO + uint32_t ctl_word = usb_otg->GRXSTSP; + uint8_t pktsts = (ctl_word & USB_OTG_GRXSTSP_PKTSTS_Msk) >> USB_OTG_GRXSTSP_PKTSTS_Pos; + uint8_t epnum = (ctl_word & USB_OTG_GRXSTSP_EPNUM_Msk) >> USB_OTG_GRXSTSP_EPNUM_Pos; + uint16_t bcnt = (ctl_word & USB_OTG_GRXSTSP_BCNT_Msk) >> USB_OTG_GRXSTSP_BCNT_Pos; + + switch(pktsts) { + case 0x01: // Global OUT NAK (Interrupt) + break; + + case 0x02: // Out packet recvd + { + xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, TUSB_DIR_OUT); + + // Read packet off RxFIFO + if (xfer->ff) + { + // Ring buffer + tu_fifo_write_n_const_addr_full_words(xfer->ff, (const void *) rx_fifo, bcnt); + } + else + { + // Linear buffer + read_fifo_packet(rhport, xfer->buffer, bcnt); + + // Increment pointer to xfer data + xfer->buffer += bcnt; + } + + // Truncate transfer length in case of short packet + if(bcnt < xfer->max_size) { + xfer->total_len -= (out_ep[epnum].DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DOEPTSIZ_XFRSIZ_Pos; + if(epnum == 0) { + xfer->total_len -= ep0_pending[TUSB_DIR_OUT]; + ep0_pending[TUSB_DIR_OUT] = 0; + } + } + } + break; + + case 0x03: // Out packet done (Interrupt) + break; + + case 0x04: // Setup packet done (Interrupt) + out_ep[epnum].DOEPTSIZ |= (3 << USB_OTG_DOEPTSIZ_STUPCNT_Pos); + break; + + case 0x06: // Setup packet recvd + // We can receive up to three setup packets in succession, but + // only the last one is valid. + _setup_packet[0] = (* rx_fifo); + _setup_packet[1] = (* rx_fifo); + break; + + default: // Invalid + TU_BREAKPOINT(); + break; + } +} + +static void handle_epout_ints(uint8_t rhport, USB_OTG_DeviceTypeDef * dev, USB_OTG_OUTEndpointTypeDef * out_ep) { + // DAINT for a given EP clears when DOEPINTx is cleared. + // OEPINT will be cleared when DAINT's out bits are cleared. + for(uint8_t n = 0; n < EP_MAX; n++) { + xfer_ctl_t * xfer = XFER_CTL_BASE(n, TUSB_DIR_OUT); + + if(dev->DAINT & (1 << (USB_OTG_DAINT_OEPINT_Pos + n))) { + // SETUP packet Setup Phase done. + if(out_ep[n].DOEPINT & USB_OTG_DOEPINT_STUP) { + out_ep[n].DOEPINT = USB_OTG_DOEPINT_STUP; + dcd_event_setup_received(rhport, (uint8_t*) &_setup_packet[0], true); + } + + // OUT XFER complete + if(out_ep[n].DOEPINT & USB_OTG_DOEPINT_XFRC) { + out_ep[n].DOEPINT = USB_OTG_DOEPINT_XFRC; + + // EP0 can only handle one packet + if((n == 0) && ep0_pending[TUSB_DIR_OUT]) { + // Schedule another packet to be received. + edpt_schedule_packets(rhport, n, TUSB_DIR_OUT, 1, ep0_pending[TUSB_DIR_OUT]); + } else { + dcd_event_xfer_complete(rhport, n, xfer->total_len, XFER_RESULT_SUCCESS, true); + } + } + } + } +} + +static void handle_epin_ints(uint8_t rhport, USB_OTG_DeviceTypeDef * dev, USB_OTG_INEndpointTypeDef * in_ep) { + // DAINT for a given EP clears when DIEPINTx is cleared. + // IEPINT will be cleared when DAINT's out bits are cleared. + for ( uint8_t n = 0; n < EP_MAX; n++ ) + { + xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_IN); + + if ( dev->DAINT & (1 << (USB_OTG_DAINT_IEPINT_Pos + n)) ) + { + // IN XFER complete (entire xfer). + if ( in_ep[n].DIEPINT & USB_OTG_DIEPINT_XFRC ) + { + in_ep[n].DIEPINT = USB_OTG_DIEPINT_XFRC; + + // EP0 can only handle one packet + if((n == 0) && ep0_pending[TUSB_DIR_IN]) { + // Schedule another packet to be transmitted. + edpt_schedule_packets(rhport, n, TUSB_DIR_IN, 1, ep0_pending[TUSB_DIR_IN]); + } else { + dcd_event_xfer_complete(rhport, n | TUSB_DIR_IN_MASK, xfer->total_len, XFER_RESULT_SUCCESS, true); + } + } + + // XFER FIFO empty + if ( (in_ep[n].DIEPINT & USB_OTG_DIEPINT_TXFE) && (dev->DIEPEMPMSK & (1 << n)) ) + { + // DIEPINT's TXFE bit is read-only, software cannot clear it. + // It will only be cleared by hardware when written bytes is more than + // - 64 bytes or + // - Half of TX FIFO size (configured by DIEPTXF) + + uint16_t remaining_packets = (in_ep[n].DIEPTSIZ & USB_OTG_DIEPTSIZ_PKTCNT_Msk) >> USB_OTG_DIEPTSIZ_PKTCNT_Pos; + + // Process every single packet (only whole packets can be written to fifo) + for(uint16_t i = 0; i < remaining_packets; i++) + { + uint16_t const remaining_bytes = (in_ep[n].DIEPTSIZ & USB_OTG_DIEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DIEPTSIZ_XFRSIZ_Pos; + + // Packet can not be larger than ep max size + uint16_t const packet_size = tu_min16(remaining_bytes, xfer->max_size); + + // It's only possible to write full packets into FIFO. Therefore DTXFSTS register of current + // EP has to be checked if the buffer can take another WHOLE packet + if(packet_size > ((in_ep[n].DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV_Msk) << 2)) break; + + // Push packet to Tx-FIFO + if (xfer->ff) + { + usb_fifo_t tx_fifo = FIFO_BASE(rhport, n); + tu_fifo_read_n_const_addr_full_words(xfer->ff, (void *) tx_fifo, packet_size); + } + else + { + write_fifo_packet(rhport, n, xfer->buffer, packet_size); + + // Increment pointer to xfer data + xfer->buffer += packet_size; + } + } + + // Turn off TXFE if all bytes are written. + if (((in_ep[n].DIEPTSIZ & USB_OTG_DIEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DIEPTSIZ_XFRSIZ_Pos) == 0) + { + dev->DIEPEMPMSK &= ~(1 << n); + } + } + } + } +} + +void dcd_int_handler(uint8_t rhport) +{ + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); + + uint32_t const int_status = usb_otg->GINTSTS & usb_otg->GINTMSK; + + if(int_status & USB_OTG_GINTSTS_USBRST) + { + // USBRST is start of reset. + usb_otg->GINTSTS = USB_OTG_GINTSTS_USBRST; + bus_reset(rhport); + } + + if(int_status & USB_OTG_GINTSTS_ENUMDNE) + { + // ENUMDNE is the end of reset where speed of the link is detected + + usb_otg->GINTSTS = USB_OTG_GINTSTS_ENUMDNE; + + tusb_speed_t const speed = get_speed(rhport); + + set_turnaround(usb_otg, speed); + dcd_event_bus_reset(rhport, speed, true); + } + + if(int_status & USB_OTG_GINTSTS_USBSUSP) + { + usb_otg->GINTSTS = USB_OTG_GINTSTS_USBSUSP; + dcd_event_bus_signal(rhport, DCD_EVENT_SUSPEND, true); + } + + if(int_status & USB_OTG_GINTSTS_WKUINT) + { + usb_otg->GINTSTS = USB_OTG_GINTSTS_WKUINT; + dcd_event_bus_signal(rhport, DCD_EVENT_RESUME, true); + } + + // TODO check USB_OTG_GINTSTS_DISCINT for disconnect detection + // if(int_status & USB_OTG_GINTSTS_DISCINT) + + if(int_status & USB_OTG_GINTSTS_OTGINT) + { + // OTG INT bit is read-only + uint32_t const otg_int = usb_otg->GOTGINT; + + if (otg_int & USB_OTG_GOTGINT_SEDET) + { + dcd_event_bus_signal(rhport, DCD_EVENT_UNPLUGGED, true); + } + + usb_otg->GOTGINT = otg_int; + } + + if(int_status & USB_OTG_GINTSTS_SOF) + { + usb_otg->GINTSTS = USB_OTG_GINTSTS_SOF; + + // Disable SOF interrupt since currently only used for remote wakeup detection + usb_otg->GINTMSK &= ~USB_OTG_GINTMSK_SOFM; + + dcd_event_bus_signal(rhport, DCD_EVENT_SOF, true); + } + + // RxFIFO non-empty interrupt handling. + if(int_status & USB_OTG_GINTSTS_RXFLVL) + { + // RXFLVL bit is read-only + + // Mask out RXFLVL while reading data from FIFO + usb_otg->GINTMSK &= ~USB_OTG_GINTMSK_RXFLVLM; + + // Loop until all available packets were handled + do + { + handle_rxflvl_ints(rhport, out_ep); + } while(usb_otg->GINTSTS & USB_OTG_GINTSTS_RXFLVL); + + // Manage RX FIFO size + if (_out_ep_closed) + { + update_grxfsiz(rhport); + + // Disable flag + _out_ep_closed = false; + } + + usb_otg->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; + } + + // OUT endpoint interrupt handling. + if(int_status & USB_OTG_GINTSTS_OEPINT) + { + // OEPINT is read-only + handle_epout_ints(rhport, dev, out_ep); + } + + // IN endpoint interrupt handling. + if(int_status & USB_OTG_GINTSTS_IEPINT) + { + // IEPINT bit read-only + handle_epin_ints(rhport, dev, in_ep); + } + + // // Check for Incomplete isochronous IN transfer + // if(int_status & USB_OTG_GINTSTS_IISOIXFR) { + // printf(" IISOIXFR!\r\n"); + //// TU_LOG2(" IISOIXFR!\r\n"); + // } +} + +#endif diff --git a/src/portable/broadcom/synopsys/synopsys_common.h b/src/portable/broadcom/synopsys/synopsys_common.h new file mode 100644 index 000000000..6f0602fe9 --- /dev/null +++ b/src/portable/broadcom/synopsys/synopsys_common.h @@ -0,0 +1,1465 @@ +/** + ****************************************************************************** + * @file synopsys_common.h + * @author MCD Application Team + * @brief CMSIS Cortex-M3 Device USB OTG peripheral Header File. + * This file contains the USB OTG peripheral register's definitions, bits + * definitions and memory mapping for STM32F1xx devices. + * + * This file contains: + * - Data structures and the address mapping for the USB OTG peripheral + * - The Peripheral's registers declarations and bits definition + * - Macros to access the peripheral's registers hardware + * + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +#include "stdint.h" + +#pragma once + +#ifdef __cplusplus + #define __I volatile +#else + #define __I volatile const +#endif +#define __O volatile +#define __IO volatile +#define __IM volatile const +#define __OM volatile +#define __IOM volatile + +/** + * @brief __USB_OTG_Core_register + */ + +typedef struct +{ + __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register Address offset: 000h */ + __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register Address offset: 004h */ + __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register Address offset: 008h */ + __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register Address offset: 00Ch */ + __IO uint32_t GRSTCTL; /*!< Core Reset Register Address offset: 010h */ + __IO uint32_t GINTSTS; /*!< Core Interrupt Register Address offset: 014h */ + __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register Address offset: 018h */ + __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register Address offset: 01Ch */ + __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register Address offset: 020h */ + __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register Address offset: 024h */ + __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register Address offset: 028h */ + __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg Address offset: 02Ch */ + uint32_t Reserved30[2]; /*!< Reserved 030h*/ + __IO uint32_t GCCFG; /*!< General Purpose IO Register Address offset: 038h */ + __IO uint32_t CID; /*!< User ID Register Address offset: 03Ch */ + uint32_t Reserved40[48]; /*!< Reserved 040h-0FFh */ + __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg Address offset: 100h */ + __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO Address offset: 0x104 */ +} USB_OTG_GlobalTypeDef; + +/** + * @brief __device_Registers + */ + +typedef struct +{ + __IO uint32_t DCFG; /*!< dev Configuration Register Address offset: 800h*/ + __IO uint32_t DCTL; /*!< dev Control Register Address offset: 804h*/ + __IO uint32_t DSTS; /*!< dev Status Register (RO) Address offset: 808h*/ + uint32_t Reserved0C; /*!< Reserved 80Ch*/ + __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask Address offset: 810h*/ + __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask Address offset: 814h*/ + __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg Address offset: 818h*/ + __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask Address offset: 81Ch*/ + uint32_t Reserved20; /*!< Reserved 820h*/ + uint32_t Reserved9; /*!< Reserved 824h*/ + __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register Address offset: 828h*/ + __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register Address offset: 82Ch*/ + __IO uint32_t DTHRCTL; /*!< dev thr Address offset: 830h*/ + __IO uint32_t DIEPEMPMSK; /*!< dev empty msk Address offset: 834h*/ + __IO uint32_t DEACHINT; /*!< dedicated EP interrupt Address offset: 838h*/ + __IO uint32_t DEACHMSK; /*!< dedicated EP msk Address offset: 83Ch*/ + uint32_t Reserved40; /*!< dedicated EP mask Address offset: 840h*/ + __IO uint32_t DINEP1MSK; /*!< dedicated EP mask Address offset: 844h*/ + uint32_t Reserved44[15]; /*!< Reserved 844-87Ch*/ + __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk Address offset: 884h*/ +} USB_OTG_DeviceTypeDef; + +/** + * @brief __IN_Endpoint-Specific_Register + */ + +typedef struct +{ + __IO uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h*/ + uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h*/ + __IO uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h*/ + uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch*/ + __IO uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h*/ + __IO uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h*/ + __IO uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h*/ + uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch*/ +} USB_OTG_INEndpointTypeDef; + +/** + * @brief __OUT_Endpoint-Specific_Registers + */ + +typedef struct +{ + __IO uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h*/ + uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h*/ + __IO uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h*/ + uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch*/ + __IO uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h*/ + __IO uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h*/ + uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch*/ +} USB_OTG_OUTEndpointTypeDef; + +/** + * @brief __Host_Mode_Register_Structures + */ + +typedef struct +{ + __IO uint32_t HCFG; /*!< Host Configuration Register 400h*/ + __IO uint32_t HFIR; /*!< Host Frame Interval Register 404h*/ + __IO uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h*/ + uint32_t Reserved40C; /*!< Reserved 40Ch*/ + __IO uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h*/ + __IO uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h*/ + __IO uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h*/ +} USB_OTG_HostTypeDef; + +/** + * @brief __Host_Channel_Specific_Registers + */ + +typedef struct +{ + __IO uint32_t HCCHAR; + __IO uint32_t HCSPLT; + __IO uint32_t HCINT; + __IO uint32_t HCINTMSK; + __IO uint32_t HCTSIZ; + __IO uint32_t HCDMA; + uint32_t Reserved[2]; +} USB_OTG_HostChannelTypeDef; + +/*!< USB registers base address */ +#define USB_OTG_FS_PERIPH_BASE 0x50000000UL + +#define USB_OTG_GLOBAL_BASE 0x00000000UL +#define USB_OTG_DEVICE_BASE 0x00000800UL +#define USB_OTG_IN_ENDPOINT_BASE 0x00000900UL +#define USB_OTG_OUT_ENDPOINT_BASE 0x00000B00UL +#define USB_OTG_EP_REG_SIZE 0x00000020UL +#define USB_OTG_HOST_BASE 0x00000400UL +#define USB_OTG_HOST_PORT_BASE 0x00000440UL +#define USB_OTG_HOST_CHANNEL_BASE 0x00000500UL +#define USB_OTG_HOST_CHANNEL_SIZE 0x00000020UL +#define USB_OTG_PCGCCTL_BASE 0x00000E00UL +#define USB_OTG_FIFO_BASE 0x00001000UL +#define USB_OTG_FIFO_SIZE 0x00001000UL + +/******************************************************************************/ +/* */ +/* USB_OTG */ +/* */ +/******************************************************************************/ +/******************** Bit definition for USB_OTG_GOTGCTL register ***********/ +#define USB_OTG_GOTGCTL_SRQSCS_Pos (0U) +#define USB_OTG_GOTGCTL_SRQSCS_Msk (0x1UL << USB_OTG_GOTGCTL_SRQSCS_Pos) /*!< 0x00000001 */ +#define USB_OTG_GOTGCTL_SRQSCS USB_OTG_GOTGCTL_SRQSCS_Msk /*!< Session request success */ +#define USB_OTG_GOTGCTL_SRQ_Pos (1U) +#define USB_OTG_GOTGCTL_SRQ_Msk (0x1UL << USB_OTG_GOTGCTL_SRQ_Pos) /*!< 0x00000002 */ +#define USB_OTG_GOTGCTL_SRQ USB_OTG_GOTGCTL_SRQ_Msk /*!< Session request */ +#define USB_OTG_GOTGCTL_HNGSCS_Pos (8U) +#define USB_OTG_GOTGCTL_HNGSCS_Msk (0x1UL << USB_OTG_GOTGCTL_HNGSCS_Pos) /*!< 0x00000100 */ +#define USB_OTG_GOTGCTL_HNGSCS USB_OTG_GOTGCTL_HNGSCS_Msk /*!< Host set HNP enable */ +#define USB_OTG_GOTGCTL_HNPRQ_Pos (9U) +#define USB_OTG_GOTGCTL_HNPRQ_Msk (0x1UL << USB_OTG_GOTGCTL_HNPRQ_Pos) /*!< 0x00000200 */ +#define USB_OTG_GOTGCTL_HNPRQ USB_OTG_GOTGCTL_HNPRQ_Msk /*!< HNP request */ +#define USB_OTG_GOTGCTL_HSHNPEN_Pos (10U) +#define USB_OTG_GOTGCTL_HSHNPEN_Msk (0x1UL << USB_OTG_GOTGCTL_HSHNPEN_Pos) /*!< 0x00000400 */ +#define USB_OTG_GOTGCTL_HSHNPEN USB_OTG_GOTGCTL_HSHNPEN_Msk /*!< Host set HNP enable */ +#define USB_OTG_GOTGCTL_DHNPEN_Pos (11U) +#define USB_OTG_GOTGCTL_DHNPEN_Msk (0x1UL << USB_OTG_GOTGCTL_DHNPEN_Pos) /*!< 0x00000800 */ +#define USB_OTG_GOTGCTL_DHNPEN USB_OTG_GOTGCTL_DHNPEN_Msk /*!< Device HNP enabled */ +#define USB_OTG_GOTGCTL_CIDSTS_Pos (16U) +#define USB_OTG_GOTGCTL_CIDSTS_Msk (0x1UL << USB_OTG_GOTGCTL_CIDSTS_Pos) /*!< 0x00010000 */ +#define USB_OTG_GOTGCTL_CIDSTS USB_OTG_GOTGCTL_CIDSTS_Msk /*!< Connector ID status */ +#define USB_OTG_GOTGCTL_DBCT_Pos (17U) +#define USB_OTG_GOTGCTL_DBCT_Msk (0x1UL << USB_OTG_GOTGCTL_DBCT_Pos) /*!< 0x00020000 */ +#define USB_OTG_GOTGCTL_DBCT USB_OTG_GOTGCTL_DBCT_Msk /*!< Long/short debounce time */ +#define USB_OTG_GOTGCTL_ASVLD_Pos (18U) +#define USB_OTG_GOTGCTL_ASVLD_Msk (0x1UL << USB_OTG_GOTGCTL_ASVLD_Pos) /*!< 0x00040000 */ +#define USB_OTG_GOTGCTL_ASVLD USB_OTG_GOTGCTL_ASVLD_Msk /*!< A-session valid */ +#define USB_OTG_GOTGCTL_BSVLD_Pos (19U) +#define USB_OTG_GOTGCTL_BSVLD_Msk (0x1UL << USB_OTG_GOTGCTL_BSVLD_Pos) /*!< 0x00080000 */ +#define USB_OTG_GOTGCTL_BSVLD USB_OTG_GOTGCTL_BSVLD_Msk /*!< B-session valid */ + +/******************** Bit definition for USB_OTG_HCFG register ********************/ + +#define USB_OTG_HCFG_FSLSPCS_Pos (0U) +#define USB_OTG_HCFG_FSLSPCS_Msk (0x3UL << USB_OTG_HCFG_FSLSPCS_Pos) /*!< 0x00000003 */ +#define USB_OTG_HCFG_FSLSPCS USB_OTG_HCFG_FSLSPCS_Msk /*!< FS/LS PHY clock select */ +#define USB_OTG_HCFG_FSLSPCS_0 (0x1UL << USB_OTG_HCFG_FSLSPCS_Pos) /*!< 0x00000001 */ +#define USB_OTG_HCFG_FSLSPCS_1 (0x2UL << USB_OTG_HCFG_FSLSPCS_Pos) /*!< 0x00000002 */ +#define USB_OTG_HCFG_FSLSS_Pos (2U) +#define USB_OTG_HCFG_FSLSS_Msk (0x1UL << USB_OTG_HCFG_FSLSS_Pos) /*!< 0x00000004 */ +#define USB_OTG_HCFG_FSLSS USB_OTG_HCFG_FSLSS_Msk /*!< FS- and LS-only support */ + +/******************** Bit definition for USB_OTG_DCFG register ********************/ + +#define USB_OTG_DCFG_DSPD_Pos (0U) +#define USB_OTG_DCFG_DSPD_Msk (0x3UL << USB_OTG_DCFG_DSPD_Pos) /*!< 0x00000003 */ +#define USB_OTG_DCFG_DSPD USB_OTG_DCFG_DSPD_Msk /*!< Device speed */ +#define USB_OTG_DCFG_DSPD_0 (0x1UL << USB_OTG_DCFG_DSPD_Pos) /*!< 0x00000001 */ +#define USB_OTG_DCFG_DSPD_1 (0x2UL << USB_OTG_DCFG_DSPD_Pos) /*!< 0x00000002 */ +#define USB_OTG_DCFG_NZLSOHSK_Pos (2U) +#define USB_OTG_DCFG_NZLSOHSK_Msk (0x1UL << USB_OTG_DCFG_NZLSOHSK_Pos) /*!< 0x00000004 */ +#define USB_OTG_DCFG_NZLSOHSK USB_OTG_DCFG_NZLSOHSK_Msk /*!< Nonzero-length status OUT handshake */ + +#define USB_OTG_DCFG_DAD_Pos (4U) +#define USB_OTG_DCFG_DAD_Msk (0x7FUL << USB_OTG_DCFG_DAD_Pos) /*!< 0x000007F0 */ +#define USB_OTG_DCFG_DAD USB_OTG_DCFG_DAD_Msk /*!< Device address */ +#define USB_OTG_DCFG_DAD_0 (0x01UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000010 */ +#define USB_OTG_DCFG_DAD_1 (0x02UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000020 */ +#define USB_OTG_DCFG_DAD_2 (0x04UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000040 */ +#define USB_OTG_DCFG_DAD_3 (0x08UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000080 */ +#define USB_OTG_DCFG_DAD_4 (0x10UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000100 */ +#define USB_OTG_DCFG_DAD_5 (0x20UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000200 */ +#define USB_OTG_DCFG_DAD_6 (0x40UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000400 */ + +#define USB_OTG_DCFG_PFIVL_Pos (11U) +#define USB_OTG_DCFG_PFIVL_Msk (0x3UL << USB_OTG_DCFG_PFIVL_Pos) /*!< 0x00001800 */ +#define USB_OTG_DCFG_PFIVL USB_OTG_DCFG_PFIVL_Msk /*!< Periodic (micro)frame interval */ +#define USB_OTG_DCFG_PFIVL_0 (0x1UL << USB_OTG_DCFG_PFIVL_Pos) /*!< 0x00000800 */ +#define USB_OTG_DCFG_PFIVL_1 (0x2UL << USB_OTG_DCFG_PFIVL_Pos) /*!< 0x00001000 */ + +#define USB_OTG_DCFG_PERSCHIVL_Pos (24U) +#define USB_OTG_DCFG_PERSCHIVL_Msk (0x3UL << USB_OTG_DCFG_PERSCHIVL_Pos) /*!< 0x03000000 */ +#define USB_OTG_DCFG_PERSCHIVL USB_OTG_DCFG_PERSCHIVL_Msk /*!< Periodic scheduling interval */ +#define USB_OTG_DCFG_PERSCHIVL_0 (0x1UL << USB_OTG_DCFG_PERSCHIVL_Pos) /*!< 0x01000000 */ +#define USB_OTG_DCFG_PERSCHIVL_1 (0x2UL << USB_OTG_DCFG_PERSCHIVL_Pos) /*!< 0x02000000 */ + +/******************** Bit definition for USB_OTG_PCGCR register ********************/ +#define USB_OTG_PCGCR_STPPCLK_Pos (0U) +#define USB_OTG_PCGCR_STPPCLK_Msk (0x1UL << USB_OTG_PCGCR_STPPCLK_Pos) /*!< 0x00000001 */ +#define USB_OTG_PCGCR_STPPCLK USB_OTG_PCGCR_STPPCLK_Msk /*!< Stop PHY clock */ +#define USB_OTG_PCGCR_GATEHCLK_Pos (1U) +#define USB_OTG_PCGCR_GATEHCLK_Msk (0x1UL << USB_OTG_PCGCR_GATEHCLK_Pos) /*!< 0x00000002 */ +#define USB_OTG_PCGCR_GATEHCLK USB_OTG_PCGCR_GATEHCLK_Msk /*!< Gate HCLK */ +#define USB_OTG_PCGCR_PHYSUSP_Pos (4U) +#define USB_OTG_PCGCR_PHYSUSP_Msk (0x1UL << USB_OTG_PCGCR_PHYSUSP_Pos) /*!< 0x00000010 */ +#define USB_OTG_PCGCR_PHYSUSP USB_OTG_PCGCR_PHYSUSP_Msk /*!< PHY suspended */ + +/******************** Bit definition for USB_OTG_GOTGINT register ********************/ +#define USB_OTG_GOTGINT_SEDET_Pos (2U) +#define USB_OTG_GOTGINT_SEDET_Msk (0x1UL << USB_OTG_GOTGINT_SEDET_Pos) /*!< 0x00000004 */ +#define USB_OTG_GOTGINT_SEDET USB_OTG_GOTGINT_SEDET_Msk /*!< Session end detected */ +#define USB_OTG_GOTGINT_SRSSCHG_Pos (8U) +#define USB_OTG_GOTGINT_SRSSCHG_Msk (0x1UL << USB_OTG_GOTGINT_SRSSCHG_Pos) /*!< 0x00000100 */ +#define USB_OTG_GOTGINT_SRSSCHG USB_OTG_GOTGINT_SRSSCHG_Msk /*!< Session request success status change */ +#define USB_OTG_GOTGINT_HNSSCHG_Pos (9U) +#define USB_OTG_GOTGINT_HNSSCHG_Msk (0x1UL << USB_OTG_GOTGINT_HNSSCHG_Pos) /*!< 0x00000200 */ +#define USB_OTG_GOTGINT_HNSSCHG USB_OTG_GOTGINT_HNSSCHG_Msk /*!< Host negotiation success status change */ +#define USB_OTG_GOTGINT_HNGDET_Pos (17U) +#define USB_OTG_GOTGINT_HNGDET_Msk (0x1UL << USB_OTG_GOTGINT_HNGDET_Pos) /*!< 0x00020000 */ +#define USB_OTG_GOTGINT_HNGDET USB_OTG_GOTGINT_HNGDET_Msk /*!< Host negotiation detected */ +#define USB_OTG_GOTGINT_ADTOCHG_Pos (18U) +#define USB_OTG_GOTGINT_ADTOCHG_Msk (0x1UL << USB_OTG_GOTGINT_ADTOCHG_Pos) /*!< 0x00040000 */ +#define USB_OTG_GOTGINT_ADTOCHG USB_OTG_GOTGINT_ADTOCHG_Msk /*!< A-device timeout change */ +#define USB_OTG_GOTGINT_DBCDNE_Pos (19U) +#define USB_OTG_GOTGINT_DBCDNE_Msk (0x1UL << USB_OTG_GOTGINT_DBCDNE_Pos) /*!< 0x00080000 */ +#define USB_OTG_GOTGINT_DBCDNE USB_OTG_GOTGINT_DBCDNE_Msk /*!< Debounce done */ + +/******************** Bit definition for USB_OTG_DCTL register ********************/ +#define USB_OTG_DCTL_RWUSIG_Pos (0U) +#define USB_OTG_DCTL_RWUSIG_Msk (0x1UL << USB_OTG_DCTL_RWUSIG_Pos) /*!< 0x00000001 */ +#define USB_OTG_DCTL_RWUSIG USB_OTG_DCTL_RWUSIG_Msk /*!< Remote wakeup signaling */ +#define USB_OTG_DCTL_SDIS_Pos (1U) +#define USB_OTG_DCTL_SDIS_Msk (0x1UL << USB_OTG_DCTL_SDIS_Pos) /*!< 0x00000002 */ +#define USB_OTG_DCTL_SDIS USB_OTG_DCTL_SDIS_Msk /*!< Soft disconnect */ +#define USB_OTG_DCTL_GINSTS_Pos (2U) +#define USB_OTG_DCTL_GINSTS_Msk (0x1UL << USB_OTG_DCTL_GINSTS_Pos) /*!< 0x00000004 */ +#define USB_OTG_DCTL_GINSTS USB_OTG_DCTL_GINSTS_Msk /*!< Global IN NAK status */ +#define USB_OTG_DCTL_GONSTS_Pos (3U) +#define USB_OTG_DCTL_GONSTS_Msk (0x1UL << USB_OTG_DCTL_GONSTS_Pos) /*!< 0x00000008 */ +#define USB_OTG_DCTL_GONSTS USB_OTG_DCTL_GONSTS_Msk /*!< Global OUT NAK status */ + +#define USB_OTG_DCTL_TCTL_Pos (4U) +#define USB_OTG_DCTL_TCTL_Msk (0x7UL << USB_OTG_DCTL_TCTL_Pos) /*!< 0x00000070 */ +#define USB_OTG_DCTL_TCTL USB_OTG_DCTL_TCTL_Msk /*!< Test control */ +#define USB_OTG_DCTL_TCTL_0 (0x1UL << USB_OTG_DCTL_TCTL_Pos) /*!< 0x00000010 */ +#define USB_OTG_DCTL_TCTL_1 (0x2UL << USB_OTG_DCTL_TCTL_Pos) /*!< 0x00000020 */ +#define USB_OTG_DCTL_TCTL_2 (0x4UL << USB_OTG_DCTL_TCTL_Pos) /*!< 0x00000040 */ +#define USB_OTG_DCTL_SGINAK_Pos (7U) +#define USB_OTG_DCTL_SGINAK_Msk (0x1UL << USB_OTG_DCTL_SGINAK_Pos) /*!< 0x00000080 */ +#define USB_OTG_DCTL_SGINAK USB_OTG_DCTL_SGINAK_Msk /*!< Set global IN NAK */ +#define USB_OTG_DCTL_CGINAK_Pos (8U) +#define USB_OTG_DCTL_CGINAK_Msk (0x1UL << USB_OTG_DCTL_CGINAK_Pos) /*!< 0x00000100 */ +#define USB_OTG_DCTL_CGINAK USB_OTG_DCTL_CGINAK_Msk /*!< Clear global IN NAK */ +#define USB_OTG_DCTL_SGONAK_Pos (9U) +#define USB_OTG_DCTL_SGONAK_Msk (0x1UL << USB_OTG_DCTL_SGONAK_Pos) /*!< 0x00000200 */ +#define USB_OTG_DCTL_SGONAK USB_OTG_DCTL_SGONAK_Msk /*!< Set global OUT NAK */ +#define USB_OTG_DCTL_CGONAK_Pos (10U) +#define USB_OTG_DCTL_CGONAK_Msk (0x1UL << USB_OTG_DCTL_CGONAK_Pos) /*!< 0x00000400 */ +#define USB_OTG_DCTL_CGONAK USB_OTG_DCTL_CGONAK_Msk /*!< Clear global OUT NAK */ +#define USB_OTG_DCTL_POPRGDNE_Pos (11U) +#define USB_OTG_DCTL_POPRGDNE_Msk (0x1UL << USB_OTG_DCTL_POPRGDNE_Pos) /*!< 0x00000800 */ +#define USB_OTG_DCTL_POPRGDNE USB_OTG_DCTL_POPRGDNE_Msk /*!< Power-on programming done */ + +/******************** Bit definition for USB_OTG_HFIR register ********************/ +#define USB_OTG_HFIR_FRIVL_Pos (0U) +#define USB_OTG_HFIR_FRIVL_Msk (0xFFFFUL << USB_OTG_HFIR_FRIVL_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_HFIR_FRIVL USB_OTG_HFIR_FRIVL_Msk /*!< Frame interval */ + +/******************** Bit definition for USB_OTG_HFNUM register ********************/ +#define USB_OTG_HFNUM_FRNUM_Pos (0U) +#define USB_OTG_HFNUM_FRNUM_Msk (0xFFFFUL << USB_OTG_HFNUM_FRNUM_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_HFNUM_FRNUM USB_OTG_HFNUM_FRNUM_Msk /*!< Frame number */ +#define USB_OTG_HFNUM_FTREM_Pos (16U) +#define USB_OTG_HFNUM_FTREM_Msk (0xFFFFUL << USB_OTG_HFNUM_FTREM_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_HFNUM_FTREM USB_OTG_HFNUM_FTREM_Msk /*!< Frame time remaining */ + +/******************** Bit definition for USB_OTG_DSTS register ********************/ +#define USB_OTG_DSTS_SUSPSTS_Pos (0U) +#define USB_OTG_DSTS_SUSPSTS_Msk (0x1UL << USB_OTG_DSTS_SUSPSTS_Pos) /*!< 0x00000001 */ +#define USB_OTG_DSTS_SUSPSTS USB_OTG_DSTS_SUSPSTS_Msk /*!< Suspend status */ + +#define USB_OTG_DSTS_ENUMSPD_Pos (1U) +#define USB_OTG_DSTS_ENUMSPD_Msk (0x3UL << USB_OTG_DSTS_ENUMSPD_Pos) /*!< 0x00000006 */ +#define USB_OTG_DSTS_ENUMSPD USB_OTG_DSTS_ENUMSPD_Msk /*!< Enumerated speed */ +#define USB_OTG_DSTS_ENUMSPD_0 (0x1UL << USB_OTG_DSTS_ENUMSPD_Pos) /*!< 0x00000002 */ +#define USB_OTG_DSTS_ENUMSPD_1 (0x2UL << USB_OTG_DSTS_ENUMSPD_Pos) /*!< 0x00000004 */ +#define USB_OTG_DSTS_EERR_Pos (3U) +#define USB_OTG_DSTS_EERR_Msk (0x1UL << USB_OTG_DSTS_EERR_Pos) /*!< 0x00000008 */ +#define USB_OTG_DSTS_EERR USB_OTG_DSTS_EERR_Msk /*!< Erratic error */ +#define USB_OTG_DSTS_FNSOF_Pos (8U) +#define USB_OTG_DSTS_FNSOF_Msk (0x3FFFUL << USB_OTG_DSTS_FNSOF_Pos) /*!< 0x003FFF00 */ +#define USB_OTG_DSTS_FNSOF USB_OTG_DSTS_FNSOF_Msk /*!< Frame number of the received SOF */ + +/******************** Bit definition for USB_OTG_GAHBCFG register ********************/ +#define USB_OTG_GAHBCFG_GINT_Pos (0U) +#define USB_OTG_GAHBCFG_GINT_Msk (0x1UL << USB_OTG_GAHBCFG_GINT_Pos) /*!< 0x00000001 */ +#define USB_OTG_GAHBCFG_GINT USB_OTG_GAHBCFG_GINT_Msk /*!< Global interrupt mask */ +#define USB_OTG_GAHBCFG_HBSTLEN_Pos (1U) +#define USB_OTG_GAHBCFG_HBSTLEN_Msk (0xFUL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< 0x0000001E */ +#define USB_OTG_GAHBCFG_HBSTLEN USB_OTG_GAHBCFG_HBSTLEN_Msk /*!< Burst length/type */ +#define USB_OTG_GAHBCFG_HBSTLEN_0 (0x0UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< Single */ +#define USB_OTG_GAHBCFG_HBSTLEN_1 (0x1UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< INCR */ +#define USB_OTG_GAHBCFG_HBSTLEN_2 (0x3UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< INCR4 */ +#define USB_OTG_GAHBCFG_HBSTLEN_3 (0x5UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< INCR8 */ +#define USB_OTG_GAHBCFG_HBSTLEN_4 (0x7UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< INCR16 */ +#define USB_OTG_GAHBCFG_DMAEN_Pos (5U) +#define USB_OTG_GAHBCFG_DMAEN_Msk (0x1UL << USB_OTG_GAHBCFG_DMAEN_Pos) /*!< 0x00000020 */ +#define USB_OTG_GAHBCFG_DMAEN USB_OTG_GAHBCFG_DMAEN_Msk /*!< DMA enable */ +#define USB_OTG_GAHBCFG_TXFELVL_Pos (7U) +#define USB_OTG_GAHBCFG_TXFELVL_Msk (0x1UL << USB_OTG_GAHBCFG_TXFELVL_Pos) /*!< 0x00000080 */ +#define USB_OTG_GAHBCFG_TXFELVL USB_OTG_GAHBCFG_TXFELVL_Msk /*!< TxFIFO empty level */ +#define USB_OTG_GAHBCFG_PTXFELVL_Pos (8U) +#define USB_OTG_GAHBCFG_PTXFELVL_Msk (0x1UL << USB_OTG_GAHBCFG_PTXFELVL_Pos) /*!< 0x00000100 */ +#define USB_OTG_GAHBCFG_PTXFELVL USB_OTG_GAHBCFG_PTXFELVL_Msk /*!< Periodic TxFIFO empty level */ + +/******************** Bit definition for USB_OTG_GUSBCFG register ********************/ + +#define USB_OTG_GUSBCFG_TOCAL_Pos (0U) +#define USB_OTG_GUSBCFG_TOCAL_Msk (0x7UL << USB_OTG_GUSBCFG_TOCAL_Pos) /*!< 0x00000007 */ +#define USB_OTG_GUSBCFG_TOCAL USB_OTG_GUSBCFG_TOCAL_Msk /*!< FS timeout calibration */ +#define USB_OTG_GUSBCFG_TOCAL_0 (0x1UL << USB_OTG_GUSBCFG_TOCAL_Pos) /*!< 0x00000001 */ +#define USB_OTG_GUSBCFG_TOCAL_1 (0x2UL << USB_OTG_GUSBCFG_TOCAL_Pos) /*!< 0x00000002 */ +#define USB_OTG_GUSBCFG_TOCAL_2 (0x4UL << USB_OTG_GUSBCFG_TOCAL_Pos) /*!< 0x00000004 */ +#define USB_OTG_GUSBCFG_PHYSEL_Pos (6U) +#define USB_OTG_GUSBCFG_PHYSEL_Msk (0x1UL << USB_OTG_GUSBCFG_PHYSEL_Pos) /*!< 0x00000040 */ +#define USB_OTG_GUSBCFG_PHYSEL USB_OTG_GUSBCFG_PHYSEL_Msk /*!< USB 2.0 high-speed ULPI PHY or USB 1.1 full-speed serial transceiver select */ +#define USB_OTG_GUSBCFG_SRPCAP_Pos (8U) +#define USB_OTG_GUSBCFG_SRPCAP_Msk (0x1UL << USB_OTG_GUSBCFG_SRPCAP_Pos) /*!< 0x00000100 */ +#define USB_OTG_GUSBCFG_SRPCAP USB_OTG_GUSBCFG_SRPCAP_Msk /*!< SRP-capable */ +#define USB_OTG_GUSBCFG_HNPCAP_Pos (9U) +#define USB_OTG_GUSBCFG_HNPCAP_Msk (0x1UL << USB_OTG_GUSBCFG_HNPCAP_Pos) /*!< 0x00000200 */ +#define USB_OTG_GUSBCFG_HNPCAP USB_OTG_GUSBCFG_HNPCAP_Msk /*!< HNP-capable */ +#define USB_OTG_GUSBCFG_TRDT_Pos (10U) +#define USB_OTG_GUSBCFG_TRDT_Msk (0xFUL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00003C00 */ +#define USB_OTG_GUSBCFG_TRDT USB_OTG_GUSBCFG_TRDT_Msk /*!< USB turnaround time */ +#define USB_OTG_GUSBCFG_TRDT_0 (0x1UL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00000400 */ +#define USB_OTG_GUSBCFG_TRDT_1 (0x2UL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00000800 */ +#define USB_OTG_GUSBCFG_TRDT_2 (0x4UL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00001000 */ +#define USB_OTG_GUSBCFG_TRDT_3 (0x8UL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00002000 */ +#define USB_OTG_GUSBCFG_PHYLPCS_Pos (15U) +#define USB_OTG_GUSBCFG_PHYLPCS_Msk (0x1UL << USB_OTG_GUSBCFG_PHYLPCS_Pos) /*!< 0x00008000 */ +#define USB_OTG_GUSBCFG_PHYLPCS USB_OTG_GUSBCFG_PHYLPCS_Msk /*!< PHY Low-power clock select */ +#define USB_OTG_GUSBCFG_ULPIFSLS_Pos (17U) +#define USB_OTG_GUSBCFG_ULPIFSLS_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIFSLS_Pos) /*!< 0x00020000 */ +#define USB_OTG_GUSBCFG_ULPIFSLS USB_OTG_GUSBCFG_ULPIFSLS_Msk /*!< ULPI FS/LS select */ +#define USB_OTG_GUSBCFG_ULPIAR_Pos (18U) +#define USB_OTG_GUSBCFG_ULPIAR_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIAR_Pos) /*!< 0x00040000 */ +#define USB_OTG_GUSBCFG_ULPIAR USB_OTG_GUSBCFG_ULPIAR_Msk /*!< ULPI Auto-resume */ +#define USB_OTG_GUSBCFG_ULPICSM_Pos (19U) +#define USB_OTG_GUSBCFG_ULPICSM_Msk (0x1UL << USB_OTG_GUSBCFG_ULPICSM_Pos) /*!< 0x00080000 */ +#define USB_OTG_GUSBCFG_ULPICSM USB_OTG_GUSBCFG_ULPICSM_Msk /*!< ULPI Clock SuspendM */ +#define USB_OTG_GUSBCFG_ULPIEVBUSD_Pos (20U) +#define USB_OTG_GUSBCFG_ULPIEVBUSD_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIEVBUSD_Pos) /*!< 0x00100000 */ +#define USB_OTG_GUSBCFG_ULPIEVBUSD USB_OTG_GUSBCFG_ULPIEVBUSD_Msk /*!< ULPI External VBUS Drive */ +#define USB_OTG_GUSBCFG_ULPIEVBUSI_Pos (21U) +#define USB_OTG_GUSBCFG_ULPIEVBUSI_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIEVBUSI_Pos) /*!< 0x00200000 */ +#define USB_OTG_GUSBCFG_ULPIEVBUSI USB_OTG_GUSBCFG_ULPIEVBUSI_Msk /*!< ULPI external VBUS indicator */ +#define USB_OTG_GUSBCFG_TSDPS_Pos (22U) +#define USB_OTG_GUSBCFG_TSDPS_Msk (0x1UL << USB_OTG_GUSBCFG_TSDPS_Pos) /*!< 0x00400000 */ +#define USB_OTG_GUSBCFG_TSDPS USB_OTG_GUSBCFG_TSDPS_Msk /*!< TermSel DLine pulsing selection */ +#define USB_OTG_GUSBCFG_PCCI_Pos (23U) +#define USB_OTG_GUSBCFG_PCCI_Msk (0x1UL << USB_OTG_GUSBCFG_PCCI_Pos) /*!< 0x00800000 */ +#define USB_OTG_GUSBCFG_PCCI USB_OTG_GUSBCFG_PCCI_Msk /*!< Indicator complement */ +#define USB_OTG_GUSBCFG_PTCI_Pos (24U) +#define USB_OTG_GUSBCFG_PTCI_Msk (0x1UL << USB_OTG_GUSBCFG_PTCI_Pos) /*!< 0x01000000 */ +#define USB_OTG_GUSBCFG_PTCI USB_OTG_GUSBCFG_PTCI_Msk /*!< Indicator pass through */ +#define USB_OTG_GUSBCFG_ULPIIPD_Pos (25U) +#define USB_OTG_GUSBCFG_ULPIIPD_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIIPD_Pos) /*!< 0x02000000 */ +#define USB_OTG_GUSBCFG_ULPIIPD USB_OTG_GUSBCFG_ULPIIPD_Msk /*!< ULPI interface protect disable */ +#define USB_OTG_GUSBCFG_FHMOD_Pos (29U) +#define USB_OTG_GUSBCFG_FHMOD_Msk (0x1UL << USB_OTG_GUSBCFG_FHMOD_Pos) /*!< 0x20000000 */ +#define USB_OTG_GUSBCFG_FHMOD USB_OTG_GUSBCFG_FHMOD_Msk /*!< Forced host mode */ +#define USB_OTG_GUSBCFG_FDMOD_Pos (30U) +#define USB_OTG_GUSBCFG_FDMOD_Msk (0x1UL << USB_OTG_GUSBCFG_FDMOD_Pos) /*!< 0x40000000 */ +#define USB_OTG_GUSBCFG_FDMOD USB_OTG_GUSBCFG_FDMOD_Msk /*!< Forced peripheral mode */ +#define USB_OTG_GUSBCFG_CTXPKT_Pos (31U) +#define USB_OTG_GUSBCFG_CTXPKT_Msk (0x1UL << USB_OTG_GUSBCFG_CTXPKT_Pos) /*!< 0x80000000 */ +#define USB_OTG_GUSBCFG_CTXPKT USB_OTG_GUSBCFG_CTXPKT_Msk /*!< Corrupt Tx packet */ + +/******************** Bit definition for USB_OTG_GRSTCTL register ********************/ +#define USB_OTG_GRSTCTL_CSRST_Pos (0U) +#define USB_OTG_GRSTCTL_CSRST_Msk (0x1UL << USB_OTG_GRSTCTL_CSRST_Pos) /*!< 0x00000001 */ +#define USB_OTG_GRSTCTL_CSRST USB_OTG_GRSTCTL_CSRST_Msk /*!< Core soft reset */ +#define USB_OTG_GRSTCTL_HSRST_Pos (1U) +#define USB_OTG_GRSTCTL_HSRST_Msk (0x1UL << USB_OTG_GRSTCTL_HSRST_Pos) /*!< 0x00000002 */ +#define USB_OTG_GRSTCTL_HSRST USB_OTG_GRSTCTL_HSRST_Msk /*!< HCLK soft reset */ +#define USB_OTG_GRSTCTL_FCRST_Pos (2U) +#define USB_OTG_GRSTCTL_FCRST_Msk (0x1UL << USB_OTG_GRSTCTL_FCRST_Pos) /*!< 0x00000004 */ +#define USB_OTG_GRSTCTL_FCRST USB_OTG_GRSTCTL_FCRST_Msk /*!< Host frame counter reset */ +#define USB_OTG_GRSTCTL_RXFFLSH_Pos (4U) +#define USB_OTG_GRSTCTL_RXFFLSH_Msk (0x1UL << USB_OTG_GRSTCTL_RXFFLSH_Pos) /*!< 0x00000010 */ +#define USB_OTG_GRSTCTL_RXFFLSH USB_OTG_GRSTCTL_RXFFLSH_Msk /*!< RxFIFO flush */ +#define USB_OTG_GRSTCTL_TXFFLSH_Pos (5U) +#define USB_OTG_GRSTCTL_TXFFLSH_Msk (0x1UL << USB_OTG_GRSTCTL_TXFFLSH_Pos) /*!< 0x00000020 */ +#define USB_OTG_GRSTCTL_TXFFLSH USB_OTG_GRSTCTL_TXFFLSH_Msk /*!< TxFIFO flush */ + + +#define USB_OTG_GRSTCTL_TXFNUM_Pos (6U) +#define USB_OTG_GRSTCTL_TXFNUM_Msk (0x1FUL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x000007C0 */ +#define USB_OTG_GRSTCTL_TXFNUM USB_OTG_GRSTCTL_TXFNUM_Msk /*!< TxFIFO number */ +#define USB_OTG_GRSTCTL_TXFNUM_0 (0x01UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000040 */ +#define USB_OTG_GRSTCTL_TXFNUM_1 (0x02UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000080 */ +#define USB_OTG_GRSTCTL_TXFNUM_2 (0x04UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000100 */ +#define USB_OTG_GRSTCTL_TXFNUM_3 (0x08UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000200 */ +#define USB_OTG_GRSTCTL_TXFNUM_4 (0x10UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000400 */ +#define USB_OTG_GRSTCTL_DMAREQ_Pos (30U) +#define USB_OTG_GRSTCTL_DMAREQ_Msk (0x1UL << USB_OTG_GRSTCTL_DMAREQ_Pos) /*!< 0x40000000 */ +#define USB_OTG_GRSTCTL_DMAREQ USB_OTG_GRSTCTL_DMAREQ_Msk /*!< DMA request signal */ +#define USB_OTG_GRSTCTL_AHBIDL_Pos (31U) +#define USB_OTG_GRSTCTL_AHBIDL_Msk (0x1UL << USB_OTG_GRSTCTL_AHBIDL_Pos) /*!< 0x80000000 */ +#define USB_OTG_GRSTCTL_AHBIDL USB_OTG_GRSTCTL_AHBIDL_Msk /*!< AHB master idle */ + +/******************** Bit definition for USB_OTG_DIEPMSK register ********************/ +#define USB_OTG_DIEPMSK_XFRCM_Pos (0U) +#define USB_OTG_DIEPMSK_XFRCM_Msk (0x1UL << USB_OTG_DIEPMSK_XFRCM_Pos) /*!< 0x00000001 */ +#define USB_OTG_DIEPMSK_XFRCM USB_OTG_DIEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define USB_OTG_DIEPMSK_EPDM_Pos (1U) +#define USB_OTG_DIEPMSK_EPDM_Msk (0x1UL << USB_OTG_DIEPMSK_EPDM_Pos) /*!< 0x00000002 */ +#define USB_OTG_DIEPMSK_EPDM USB_OTG_DIEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define USB_OTG_DIEPMSK_TOM_Pos (3U) +#define USB_OTG_DIEPMSK_TOM_Msk (0x1UL << USB_OTG_DIEPMSK_TOM_Pos) /*!< 0x00000008 */ +#define USB_OTG_DIEPMSK_TOM USB_OTG_DIEPMSK_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ +#define USB_OTG_DIEPMSK_ITTXFEMSK_Pos (4U) +#define USB_OTG_DIEPMSK_ITTXFEMSK_Msk (0x1UL << USB_OTG_DIEPMSK_ITTXFEMSK_Pos) /*!< 0x00000010 */ +#define USB_OTG_DIEPMSK_ITTXFEMSK USB_OTG_DIEPMSK_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define USB_OTG_DIEPMSK_INEPNMM_Pos (5U) +#define USB_OTG_DIEPMSK_INEPNMM_Msk (0x1UL << USB_OTG_DIEPMSK_INEPNMM_Pos) /*!< 0x00000020 */ +#define USB_OTG_DIEPMSK_INEPNMM USB_OTG_DIEPMSK_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define USB_OTG_DIEPMSK_INEPNEM_Pos (6U) +#define USB_OTG_DIEPMSK_INEPNEM_Msk (0x1UL << USB_OTG_DIEPMSK_INEPNEM_Pos) /*!< 0x00000040 */ +#define USB_OTG_DIEPMSK_INEPNEM USB_OTG_DIEPMSK_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define USB_OTG_DIEPMSK_TXFURM_Pos (8U) +#define USB_OTG_DIEPMSK_TXFURM_Msk (0x1UL << USB_OTG_DIEPMSK_TXFURM_Pos) /*!< 0x00000100 */ +#define USB_OTG_DIEPMSK_TXFURM USB_OTG_DIEPMSK_TXFURM_Msk /*!< FIFO underrun mask */ +#define USB_OTG_DIEPMSK_BIM_Pos (9U) +#define USB_OTG_DIEPMSK_BIM_Msk (0x1UL << USB_OTG_DIEPMSK_BIM_Pos) /*!< 0x00000200 */ +#define USB_OTG_DIEPMSK_BIM USB_OTG_DIEPMSK_BIM_Msk /*!< BNA interrupt mask */ + +/******************** Bit definition for USB_OTG_HPTXSTS register ********************/ +#define USB_OTG_HPTXSTS_PTXFSAVL_Pos (0U) +#define USB_OTG_HPTXSTS_PTXFSAVL_Msk (0xFFFFUL << USB_OTG_HPTXSTS_PTXFSAVL_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_HPTXSTS_PTXFSAVL USB_OTG_HPTXSTS_PTXFSAVL_Msk /*!< Periodic transmit data FIFO space available */ +#define USB_OTG_HPTXSTS_PTXQSAV_Pos (16U) +#define USB_OTG_HPTXSTS_PTXQSAV_Msk (0xFFUL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00FF0000 */ +#define USB_OTG_HPTXSTS_PTXQSAV USB_OTG_HPTXSTS_PTXQSAV_Msk /*!< Periodic transmit request queue space available */ +#define USB_OTG_HPTXSTS_PTXQSAV_0 (0x01UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00010000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_1 (0x02UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00020000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_2 (0x04UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00040000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_3 (0x08UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00080000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_4 (0x10UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00100000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_5 (0x20UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00200000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_6 (0x40UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00400000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_7 (0x80UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00800000 */ + +#define USB_OTG_HPTXSTS_PTXQTOP_Pos (24U) +#define USB_OTG_HPTXSTS_PTXQTOP_Msk (0xFFUL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0xFF000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP USB_OTG_HPTXSTS_PTXQTOP_Msk /*!< Top of the periodic transmit request queue */ +#define USB_OTG_HPTXSTS_PTXQTOP_0 (0x01UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x01000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_1 (0x02UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x02000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_2 (0x04UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x04000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_3 (0x08UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x08000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_4 (0x10UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x10000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_5 (0x20UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x20000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_6 (0x40UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x40000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_7 (0x80UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for USB_OTG_HAINT register ********************/ +#define USB_OTG_HAINT_HAINT_Pos (0U) +#define USB_OTG_HAINT_HAINT_Msk (0xFFFFUL << USB_OTG_HAINT_HAINT_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_HAINT_HAINT USB_OTG_HAINT_HAINT_Msk /*!< Channel interrupts */ + +/******************** Bit definition for USB_OTG_DOEPMSK register ********************/ +#define USB_OTG_DOEPMSK_XFRCM_Pos (0U) +#define USB_OTG_DOEPMSK_XFRCM_Msk (0x1UL << USB_OTG_DOEPMSK_XFRCM_Pos) /*!< 0x00000001 */ +#define USB_OTG_DOEPMSK_XFRCM USB_OTG_DOEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define USB_OTG_DOEPMSK_EPDM_Pos (1U) +#define USB_OTG_DOEPMSK_EPDM_Msk (0x1UL << USB_OTG_DOEPMSK_EPDM_Pos) /*!< 0x00000002 */ +#define USB_OTG_DOEPMSK_EPDM USB_OTG_DOEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define USB_OTG_DOEPMSK_AHBERRM_Pos (2U) +#define USB_OTG_DOEPMSK_AHBERRM_Msk (0x1UL << USB_OTG_DOEPMSK_AHBERRM_Pos) /*!< 0x00000004 */ +#define USB_OTG_DOEPMSK_AHBERRM USB_OTG_DOEPMSK_AHBERRM_Msk /*!< OUT transaction AHB Error interrupt mask */ +#define USB_OTG_DOEPMSK_STUPM_Pos (3U) +#define USB_OTG_DOEPMSK_STUPM_Msk (0x1UL << USB_OTG_DOEPMSK_STUPM_Pos) /*!< 0x00000008 */ +#define USB_OTG_DOEPMSK_STUPM USB_OTG_DOEPMSK_STUPM_Msk /*!< SETUP phase done mask */ +#define USB_OTG_DOEPMSK_OTEPDM_Pos (4U) +#define USB_OTG_DOEPMSK_OTEPDM_Msk (0x1UL << USB_OTG_DOEPMSK_OTEPDM_Pos) /*!< 0x00000010 */ +#define USB_OTG_DOEPMSK_OTEPDM USB_OTG_DOEPMSK_OTEPDM_Msk /*!< OUT token received when endpoint disabled mask */ +#define USB_OTG_DOEPMSK_OTEPSPRM_Pos (5U) +#define USB_OTG_DOEPMSK_OTEPSPRM_Msk (0x1UL << USB_OTG_DOEPMSK_OTEPSPRM_Pos) /*!< 0x00000020 */ +#define USB_OTG_DOEPMSK_OTEPSPRM USB_OTG_DOEPMSK_OTEPSPRM_Msk /*!< Status Phase Received mask */ +#define USB_OTG_DOEPMSK_B2BSTUP_Pos (6U) +#define USB_OTG_DOEPMSK_B2BSTUP_Msk (0x1UL << USB_OTG_DOEPMSK_B2BSTUP_Pos) /*!< 0x00000040 */ +#define USB_OTG_DOEPMSK_B2BSTUP USB_OTG_DOEPMSK_B2BSTUP_Msk /*!< Back-to-back SETUP packets received mask */ +#define USB_OTG_DOEPMSK_OPEM_Pos (8U) +#define USB_OTG_DOEPMSK_OPEM_Msk (0x1UL << USB_OTG_DOEPMSK_OPEM_Pos) /*!< 0x00000100 */ +#define USB_OTG_DOEPMSK_OPEM USB_OTG_DOEPMSK_OPEM_Msk /*!< OUT packet error mask */ +#define USB_OTG_DOEPMSK_BOIM_Pos (9U) +#define USB_OTG_DOEPMSK_BOIM_Msk (0x1UL << USB_OTG_DOEPMSK_BOIM_Pos) /*!< 0x00000200 */ +#define USB_OTG_DOEPMSK_BOIM USB_OTG_DOEPMSK_BOIM_Msk /*!< BNA interrupt mask */ +#define USB_OTG_DOEPMSK_BERRM_Pos (12U) +#define USB_OTG_DOEPMSK_BERRM_Msk (0x1UL << USB_OTG_DOEPMSK_BERRM_Pos) /*!< 0x00001000 */ +#define USB_OTG_DOEPMSK_BERRM USB_OTG_DOEPMSK_BERRM_Msk /*!< Babble error interrupt mask */ +#define USB_OTG_DOEPMSK_NAKM_Pos (13U) +#define USB_OTG_DOEPMSK_NAKM_Msk (0x1UL << USB_OTG_DOEPMSK_NAKM_Pos) /*!< 0x00002000 */ +#define USB_OTG_DOEPMSK_NAKM USB_OTG_DOEPMSK_NAKM_Msk /*!< OUT Packet NAK interrupt mask */ +#define USB_OTG_DOEPMSK_NYETM_Pos (14U) +#define USB_OTG_DOEPMSK_NYETM_Msk (0x1UL << USB_OTG_DOEPMSK_NYETM_Pos) /*!< 0x00004000 */ +#define USB_OTG_DOEPMSK_NYETM USB_OTG_DOEPMSK_NYETM_Msk /*!< NYET interrupt mask */ +/******************** Bit definition for USB_OTG_GINTSTS register ********************/ +#define USB_OTG_GINTSTS_CMOD_Pos (0U) +#define USB_OTG_GINTSTS_CMOD_Msk (0x1UL << USB_OTG_GINTSTS_CMOD_Pos) /*!< 0x00000001 */ +#define USB_OTG_GINTSTS_CMOD USB_OTG_GINTSTS_CMOD_Msk /*!< Current mode of operation */ +#define USB_OTG_GINTSTS_MMIS_Pos (1U) +#define USB_OTG_GINTSTS_MMIS_Msk (0x1UL << USB_OTG_GINTSTS_MMIS_Pos) /*!< 0x00000002 */ +#define USB_OTG_GINTSTS_MMIS USB_OTG_GINTSTS_MMIS_Msk /*!< Mode mismatch interrupt */ +#define USB_OTG_GINTSTS_OTGINT_Pos (2U) +#define USB_OTG_GINTSTS_OTGINT_Msk (0x1UL << USB_OTG_GINTSTS_OTGINT_Pos) /*!< 0x00000004 */ +#define USB_OTG_GINTSTS_OTGINT USB_OTG_GINTSTS_OTGINT_Msk /*!< OTG interrupt */ +#define USB_OTG_GINTSTS_SOF_Pos (3U) +#define USB_OTG_GINTSTS_SOF_Msk (0x1UL << USB_OTG_GINTSTS_SOF_Pos) /*!< 0x00000008 */ +#define USB_OTG_GINTSTS_SOF USB_OTG_GINTSTS_SOF_Msk /*!< Start of frame */ +#define USB_OTG_GINTSTS_RXFLVL_Pos (4U) +#define USB_OTG_GINTSTS_RXFLVL_Msk (0x1UL << USB_OTG_GINTSTS_RXFLVL_Pos) /*!< 0x00000010 */ +#define USB_OTG_GINTSTS_RXFLVL USB_OTG_GINTSTS_RXFLVL_Msk /*!< RxFIFO nonempty */ +#define USB_OTG_GINTSTS_NPTXFE_Pos (5U) +#define USB_OTG_GINTSTS_NPTXFE_Msk (0x1UL << USB_OTG_GINTSTS_NPTXFE_Pos) /*!< 0x00000020 */ +#define USB_OTG_GINTSTS_NPTXFE USB_OTG_GINTSTS_NPTXFE_Msk /*!< Nonperiodic TxFIFO empty */ +#define USB_OTG_GINTSTS_GINAKEFF_Pos (6U) +#define USB_OTG_GINTSTS_GINAKEFF_Msk (0x1UL << USB_OTG_GINTSTS_GINAKEFF_Pos) /*!< 0x00000040 */ +#define USB_OTG_GINTSTS_GINAKEFF USB_OTG_GINTSTS_GINAKEFF_Msk /*!< Global IN nonperiodic NAK effective */ +#define USB_OTG_GINTSTS_BOUTNAKEFF_Pos (7U) +#define USB_OTG_GINTSTS_BOUTNAKEFF_Msk (0x1UL << USB_OTG_GINTSTS_BOUTNAKEFF_Pos) /*!< 0x00000080 */ +#define USB_OTG_GINTSTS_BOUTNAKEFF USB_OTG_GINTSTS_BOUTNAKEFF_Msk /*!< Global OUT NAK effective */ +#define USB_OTG_GINTSTS_ESUSP_Pos (10U) +#define USB_OTG_GINTSTS_ESUSP_Msk (0x1UL << USB_OTG_GINTSTS_ESUSP_Pos) /*!< 0x00000400 */ +#define USB_OTG_GINTSTS_ESUSP USB_OTG_GINTSTS_ESUSP_Msk /*!< Early suspend */ +#define USB_OTG_GINTSTS_USBSUSP_Pos (11U) +#define USB_OTG_GINTSTS_USBSUSP_Msk (0x1UL << USB_OTG_GINTSTS_USBSUSP_Pos) /*!< 0x00000800 */ +#define USB_OTG_GINTSTS_USBSUSP USB_OTG_GINTSTS_USBSUSP_Msk /*!< USB suspend */ +#define USB_OTG_GINTSTS_USBRST_Pos (12U) +#define USB_OTG_GINTSTS_USBRST_Msk (0x1UL << USB_OTG_GINTSTS_USBRST_Pos) /*!< 0x00001000 */ +#define USB_OTG_GINTSTS_USBRST USB_OTG_GINTSTS_USBRST_Msk /*!< USB reset */ +#define USB_OTG_GINTSTS_ENUMDNE_Pos (13U) +#define USB_OTG_GINTSTS_ENUMDNE_Msk (0x1UL << USB_OTG_GINTSTS_ENUMDNE_Pos) /*!< 0x00002000 */ +#define USB_OTG_GINTSTS_ENUMDNE USB_OTG_GINTSTS_ENUMDNE_Msk /*!< Enumeration done */ +#define USB_OTG_GINTSTS_ISOODRP_Pos (14U) +#define USB_OTG_GINTSTS_ISOODRP_Msk (0x1UL << USB_OTG_GINTSTS_ISOODRP_Pos) /*!< 0x00004000 */ +#define USB_OTG_GINTSTS_ISOODRP USB_OTG_GINTSTS_ISOODRP_Msk /*!< Isochronous OUT packet dropped interrupt */ +#define USB_OTG_GINTSTS_EOPF_Pos (15U) +#define USB_OTG_GINTSTS_EOPF_Msk (0x1UL << USB_OTG_GINTSTS_EOPF_Pos) /*!< 0x00008000 */ +#define USB_OTG_GINTSTS_EOPF USB_OTG_GINTSTS_EOPF_Msk /*!< End of periodic frame interrupt */ +#define USB_OTG_GINTSTS_IEPINT_Pos (18U) +#define USB_OTG_GINTSTS_IEPINT_Msk (0x1UL << USB_OTG_GINTSTS_IEPINT_Pos) /*!< 0x00040000 */ +#define USB_OTG_GINTSTS_IEPINT USB_OTG_GINTSTS_IEPINT_Msk /*!< IN endpoint interrupt */ +#define USB_OTG_GINTSTS_OEPINT_Pos (19U) +#define USB_OTG_GINTSTS_OEPINT_Msk (0x1UL << USB_OTG_GINTSTS_OEPINT_Pos) /*!< 0x00080000 */ +#define USB_OTG_GINTSTS_OEPINT USB_OTG_GINTSTS_OEPINT_Msk /*!< OUT endpoint interrupt */ +#define USB_OTG_GINTSTS_IISOIXFR_Pos (20U) +#define USB_OTG_GINTSTS_IISOIXFR_Msk (0x1UL << USB_OTG_GINTSTS_IISOIXFR_Pos) /*!< 0x00100000 */ +#define USB_OTG_GINTSTS_IISOIXFR USB_OTG_GINTSTS_IISOIXFR_Msk /*!< Incomplete isochronous IN transfer */ +#define USB_OTG_GINTSTS_PXFR_INCOMPISOOUT_Pos (21U) +#define USB_OTG_GINTSTS_PXFR_INCOMPISOOUT_Msk (0x1UL << USB_OTG_GINTSTS_PXFR_INCOMPISOOUT_Pos) /*!< 0x00200000 */ +#define USB_OTG_GINTSTS_PXFR_INCOMPISOOUT USB_OTG_GINTSTS_PXFR_INCOMPISOOUT_Msk /*!< Incomplete periodic transfer */ +#define USB_OTG_GINTSTS_DATAFSUSP_Pos (22U) +#define USB_OTG_GINTSTS_DATAFSUSP_Msk (0x1UL << USB_OTG_GINTSTS_DATAFSUSP_Pos) /*!< 0x00400000 */ +#define USB_OTG_GINTSTS_DATAFSUSP USB_OTG_GINTSTS_DATAFSUSP_Msk /*!< Data fetch suspended */ +#define USB_OTG_GINTSTS_HPRTINT_Pos (24U) +#define USB_OTG_GINTSTS_HPRTINT_Msk (0x1UL << USB_OTG_GINTSTS_HPRTINT_Pos) /*!< 0x01000000 */ +#define USB_OTG_GINTSTS_HPRTINT USB_OTG_GINTSTS_HPRTINT_Msk /*!< Host port interrupt */ +#define USB_OTG_GINTSTS_HCINT_Pos (25U) +#define USB_OTG_GINTSTS_HCINT_Msk (0x1UL << USB_OTG_GINTSTS_HCINT_Pos) /*!< 0x02000000 */ +#define USB_OTG_GINTSTS_HCINT USB_OTG_GINTSTS_HCINT_Msk /*!< Host channels interrupt */ +#define USB_OTG_GINTSTS_PTXFE_Pos (26U) +#define USB_OTG_GINTSTS_PTXFE_Msk (0x1UL << USB_OTG_GINTSTS_PTXFE_Pos) /*!< 0x04000000 */ +#define USB_OTG_GINTSTS_PTXFE USB_OTG_GINTSTS_PTXFE_Msk /*!< Periodic TxFIFO empty */ +#define USB_OTG_GINTSTS_CIDSCHG_Pos (28U) +#define USB_OTG_GINTSTS_CIDSCHG_Msk (0x1UL << USB_OTG_GINTSTS_CIDSCHG_Pos) /*!< 0x10000000 */ +#define USB_OTG_GINTSTS_CIDSCHG USB_OTG_GINTSTS_CIDSCHG_Msk /*!< Connector ID status change */ +#define USB_OTG_GINTSTS_DISCINT_Pos (29U) +#define USB_OTG_GINTSTS_DISCINT_Msk (0x1UL << USB_OTG_GINTSTS_DISCINT_Pos) /*!< 0x20000000 */ +#define USB_OTG_GINTSTS_DISCINT USB_OTG_GINTSTS_DISCINT_Msk /*!< Disconnect detected interrupt */ +#define USB_OTG_GINTSTS_SRQINT_Pos (30U) +#define USB_OTG_GINTSTS_SRQINT_Msk (0x1UL << USB_OTG_GINTSTS_SRQINT_Pos) /*!< 0x40000000 */ +#define USB_OTG_GINTSTS_SRQINT USB_OTG_GINTSTS_SRQINT_Msk /*!< Session request/new session detected interrupt */ +#define USB_OTG_GINTSTS_WKUINT_Pos (31U) +#define USB_OTG_GINTSTS_WKUINT_Msk (0x1UL << USB_OTG_GINTSTS_WKUINT_Pos) /*!< 0x80000000 */ +#define USB_OTG_GINTSTS_WKUINT USB_OTG_GINTSTS_WKUINT_Msk /*!< Resume/remote wakeup detected interrupt */ + +/******************** Bit definition for USB_OTG_GINTMSK register ********************/ +#define USB_OTG_GINTMSK_MMISM_Pos (1U) +#define USB_OTG_GINTMSK_MMISM_Msk (0x1UL << USB_OTG_GINTMSK_MMISM_Pos) /*!< 0x00000002 */ +#define USB_OTG_GINTMSK_MMISM USB_OTG_GINTMSK_MMISM_Msk /*!< Mode mismatch interrupt mask */ +#define USB_OTG_GINTMSK_OTGINT_Pos (2U) +#define USB_OTG_GINTMSK_OTGINT_Msk (0x1UL << USB_OTG_GINTMSK_OTGINT_Pos) /*!< 0x00000004 */ +#define USB_OTG_GINTMSK_OTGINT USB_OTG_GINTMSK_OTGINT_Msk /*!< OTG interrupt mask */ +#define USB_OTG_GINTMSK_SOFM_Pos (3U) +#define USB_OTG_GINTMSK_SOFM_Msk (0x1UL << USB_OTG_GINTMSK_SOFM_Pos) /*!< 0x00000008 */ +#define USB_OTG_GINTMSK_SOFM USB_OTG_GINTMSK_SOFM_Msk /*!< Start of frame mask */ +#define USB_OTG_GINTMSK_RXFLVLM_Pos (4U) +#define USB_OTG_GINTMSK_RXFLVLM_Msk (0x1UL << USB_OTG_GINTMSK_RXFLVLM_Pos) /*!< 0x00000010 */ +#define USB_OTG_GINTMSK_RXFLVLM USB_OTG_GINTMSK_RXFLVLM_Msk /*!< Receive FIFO nonempty mask */ +#define USB_OTG_GINTMSK_NPTXFEM_Pos (5U) +#define USB_OTG_GINTMSK_NPTXFEM_Msk (0x1UL << USB_OTG_GINTMSK_NPTXFEM_Pos) /*!< 0x00000020 */ +#define USB_OTG_GINTMSK_NPTXFEM USB_OTG_GINTMSK_NPTXFEM_Msk /*!< Nonperiodic TxFIFO empty mask */ +#define USB_OTG_GINTMSK_GINAKEFFM_Pos (6U) +#define USB_OTG_GINTMSK_GINAKEFFM_Msk (0x1UL << USB_OTG_GINTMSK_GINAKEFFM_Pos) /*!< 0x00000040 */ +#define USB_OTG_GINTMSK_GINAKEFFM USB_OTG_GINTMSK_GINAKEFFM_Msk /*!< Global nonperiodic IN NAK effective mask */ +#define USB_OTG_GINTMSK_GONAKEFFM_Pos (7U) +#define USB_OTG_GINTMSK_GONAKEFFM_Msk (0x1UL << USB_OTG_GINTMSK_GONAKEFFM_Pos) /*!< 0x00000080 */ +#define USB_OTG_GINTMSK_GONAKEFFM USB_OTG_GINTMSK_GONAKEFFM_Msk /*!< Global OUT NAK effective mask */ +#define USB_OTG_GINTMSK_ESUSPM_Pos (10U) +#define USB_OTG_GINTMSK_ESUSPM_Msk (0x1UL << USB_OTG_GINTMSK_ESUSPM_Pos) /*!< 0x00000400 */ +#define USB_OTG_GINTMSK_ESUSPM USB_OTG_GINTMSK_ESUSPM_Msk /*!< Early suspend mask */ +#define USB_OTG_GINTMSK_USBSUSPM_Pos (11U) +#define USB_OTG_GINTMSK_USBSUSPM_Msk (0x1UL << USB_OTG_GINTMSK_USBSUSPM_Pos) /*!< 0x00000800 */ +#define USB_OTG_GINTMSK_USBSUSPM USB_OTG_GINTMSK_USBSUSPM_Msk /*!< USB suspend mask */ +#define USB_OTG_GINTMSK_USBRST_Pos (12U) +#define USB_OTG_GINTMSK_USBRST_Msk (0x1UL << USB_OTG_GINTMSK_USBRST_Pos) /*!< 0x00001000 */ +#define USB_OTG_GINTMSK_USBRST USB_OTG_GINTMSK_USBRST_Msk /*!< USB reset mask */ +#define USB_OTG_GINTMSK_ENUMDNEM_Pos (13U) +#define USB_OTG_GINTMSK_ENUMDNEM_Msk (0x1UL << USB_OTG_GINTMSK_ENUMDNEM_Pos) /*!< 0x00002000 */ +#define USB_OTG_GINTMSK_ENUMDNEM USB_OTG_GINTMSK_ENUMDNEM_Msk /*!< Enumeration done mask */ +#define USB_OTG_GINTMSK_ISOODRPM_Pos (14U) +#define USB_OTG_GINTMSK_ISOODRPM_Msk (0x1UL << USB_OTG_GINTMSK_ISOODRPM_Pos) /*!< 0x00004000 */ +#define USB_OTG_GINTMSK_ISOODRPM USB_OTG_GINTMSK_ISOODRPM_Msk /*!< Isochronous OUT packet dropped interrupt mask */ +#define USB_OTG_GINTMSK_EOPFM_Pos (15U) +#define USB_OTG_GINTMSK_EOPFM_Msk (0x1UL << USB_OTG_GINTMSK_EOPFM_Pos) /*!< 0x00008000 */ +#define USB_OTG_GINTMSK_EOPFM USB_OTG_GINTMSK_EOPFM_Msk /*!< End of periodic frame interrupt mask */ +#define USB_OTG_GINTMSK_EPMISM_Pos (17U) +#define USB_OTG_GINTMSK_EPMISM_Msk (0x1UL << USB_OTG_GINTMSK_EPMISM_Pos) /*!< 0x00020000 */ +#define USB_OTG_GINTMSK_EPMISM USB_OTG_GINTMSK_EPMISM_Msk /*!< Endpoint mismatch interrupt mask */ +#define USB_OTG_GINTMSK_IEPINT_Pos (18U) +#define USB_OTG_GINTMSK_IEPINT_Msk (0x1UL << USB_OTG_GINTMSK_IEPINT_Pos) /*!< 0x00040000 */ +#define USB_OTG_GINTMSK_IEPINT USB_OTG_GINTMSK_IEPINT_Msk /*!< IN endpoints interrupt mask */ +#define USB_OTG_GINTMSK_OEPINT_Pos (19U) +#define USB_OTG_GINTMSK_OEPINT_Msk (0x1UL << USB_OTG_GINTMSK_OEPINT_Pos) /*!< 0x00080000 */ +#define USB_OTG_GINTMSK_OEPINT USB_OTG_GINTMSK_OEPINT_Msk /*!< OUT endpoints interrupt mask */ +#define USB_OTG_GINTMSK_IISOIXFRM_Pos (20U) +#define USB_OTG_GINTMSK_IISOIXFRM_Msk (0x1UL << USB_OTG_GINTMSK_IISOIXFRM_Pos) /*!< 0x00100000 */ +#define USB_OTG_GINTMSK_IISOIXFRM USB_OTG_GINTMSK_IISOIXFRM_Msk /*!< Incomplete isochronous IN transfer mask */ +#define USB_OTG_GINTMSK_PXFRM_IISOOXFRM_Pos (21U) +#define USB_OTG_GINTMSK_PXFRM_IISOOXFRM_Msk (0x1UL << USB_OTG_GINTMSK_PXFRM_IISOOXFRM_Pos) /*!< 0x00200000 */ +#define USB_OTG_GINTMSK_PXFRM_IISOOXFRM USB_OTG_GINTMSK_PXFRM_IISOOXFRM_Msk /*!< Incomplete periodic transfer mask */ +#define USB_OTG_GINTMSK_FSUSPM_Pos (22U) +#define USB_OTG_GINTMSK_FSUSPM_Msk (0x1UL << USB_OTG_GINTMSK_FSUSPM_Pos) /*!< 0x00400000 */ +#define USB_OTG_GINTMSK_FSUSPM USB_OTG_GINTMSK_FSUSPM_Msk /*!< Data fetch suspended mask */ +#define USB_OTG_GINTMSK_PRTIM_Pos (24U) +#define USB_OTG_GINTMSK_PRTIM_Msk (0x1UL << USB_OTG_GINTMSK_PRTIM_Pos) /*!< 0x01000000 */ +#define USB_OTG_GINTMSK_PRTIM USB_OTG_GINTMSK_PRTIM_Msk /*!< Host port interrupt mask */ +#define USB_OTG_GINTMSK_HCIM_Pos (25U) +#define USB_OTG_GINTMSK_HCIM_Msk (0x1UL << USB_OTG_GINTMSK_HCIM_Pos) /*!< 0x02000000 */ +#define USB_OTG_GINTMSK_HCIM USB_OTG_GINTMSK_HCIM_Msk /*!< Host channels interrupt mask */ +#define USB_OTG_GINTMSK_PTXFEM_Pos (26U) +#define USB_OTG_GINTMSK_PTXFEM_Msk (0x1UL << USB_OTG_GINTMSK_PTXFEM_Pos) /*!< 0x04000000 */ +#define USB_OTG_GINTMSK_PTXFEM USB_OTG_GINTMSK_PTXFEM_Msk /*!< Periodic TxFIFO empty mask */ +#define USB_OTG_GINTMSK_CIDSCHGM_Pos (28U) +#define USB_OTG_GINTMSK_CIDSCHGM_Msk (0x1UL << USB_OTG_GINTMSK_CIDSCHGM_Pos) /*!< 0x10000000 */ +#define USB_OTG_GINTMSK_CIDSCHGM USB_OTG_GINTMSK_CIDSCHGM_Msk /*!< Connector ID status change mask */ +#define USB_OTG_GINTMSK_DISCINT_Pos (29U) +#define USB_OTG_GINTMSK_DISCINT_Msk (0x1UL << USB_OTG_GINTMSK_DISCINT_Pos) /*!< 0x20000000 */ +#define USB_OTG_GINTMSK_DISCINT USB_OTG_GINTMSK_DISCINT_Msk /*!< Disconnect detected interrupt mask */ +#define USB_OTG_GINTMSK_SRQIM_Pos (30U) +#define USB_OTG_GINTMSK_SRQIM_Msk (0x1UL << USB_OTG_GINTMSK_SRQIM_Pos) /*!< 0x40000000 */ +#define USB_OTG_GINTMSK_SRQIM USB_OTG_GINTMSK_SRQIM_Msk /*!< Session request/new session detected interrupt mask */ +#define USB_OTG_GINTMSK_WUIM_Pos (31U) +#define USB_OTG_GINTMSK_WUIM_Msk (0x1UL << USB_OTG_GINTMSK_WUIM_Pos) /*!< 0x80000000 */ +#define USB_OTG_GINTMSK_WUIM USB_OTG_GINTMSK_WUIM_Msk /*!< Resume/remote wakeup detected interrupt mask */ + +/******************** Bit definition for USB_OTG_DAINT register ********************/ +#define USB_OTG_DAINT_IEPINT_Pos (0U) +#define USB_OTG_DAINT_IEPINT_Msk (0xFFFFUL << USB_OTG_DAINT_IEPINT_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_DAINT_IEPINT USB_OTG_DAINT_IEPINT_Msk /*!< IN endpoint interrupt bits */ +#define USB_OTG_DAINT_OEPINT_Pos (16U) +#define USB_OTG_DAINT_OEPINT_Msk (0xFFFFUL << USB_OTG_DAINT_OEPINT_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_DAINT_OEPINT USB_OTG_DAINT_OEPINT_Msk /*!< OUT endpoint interrupt bits */ + +/******************** Bit definition for USB_OTG_HAINTMSK register ********************/ +#define USB_OTG_HAINTMSK_HAINTM_Pos (0U) +#define USB_OTG_HAINTMSK_HAINTM_Msk (0xFFFFUL << USB_OTG_HAINTMSK_HAINTM_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_HAINTMSK_HAINTM USB_OTG_HAINTMSK_HAINTM_Msk /*!< Channel interrupt mask */ + +/******************** Bit definition for USB_OTG_GRXSTSP register ********************/ +#define USB_OTG_GRXSTSP_EPNUM_Pos (0U) +#define USB_OTG_GRXSTSP_EPNUM_Msk (0xFUL << USB_OTG_GRXSTSP_EPNUM_Pos) /*!< 0x0000000F */ +#define USB_OTG_GRXSTSP_EPNUM USB_OTG_GRXSTSP_EPNUM_Msk /*!< IN EP interrupt mask bits */ +#define USB_OTG_GRXSTSP_BCNT_Pos (4U) +#define USB_OTG_GRXSTSP_BCNT_Msk (0x7FFUL << USB_OTG_GRXSTSP_BCNT_Pos) /*!< 0x00007FF0 */ +#define USB_OTG_GRXSTSP_BCNT USB_OTG_GRXSTSP_BCNT_Msk /*!< OUT EP interrupt mask bits */ +#define USB_OTG_GRXSTSP_DPID_Pos (15U) +#define USB_OTG_GRXSTSP_DPID_Msk (0x3UL << USB_OTG_GRXSTSP_DPID_Pos) /*!< 0x00018000 */ +#define USB_OTG_GRXSTSP_DPID USB_OTG_GRXSTSP_DPID_Msk /*!< OUT EP interrupt mask bits */ +#define USB_OTG_GRXSTSP_PKTSTS_Pos (17U) +#define USB_OTG_GRXSTSP_PKTSTS_Msk (0xFUL << USB_OTG_GRXSTSP_PKTSTS_Pos) /*!< 0x001E0000 */ +#define USB_OTG_GRXSTSP_PKTSTS USB_OTG_GRXSTSP_PKTSTS_Msk /*!< OUT EP interrupt mask bits */ + +/******************** Bit definition for USB_OTG_DAINTMSK register ********************/ +#define USB_OTG_DAINTMSK_IEPM_Pos (0U) +#define USB_OTG_DAINTMSK_IEPM_Msk (0xFFFFUL << USB_OTG_DAINTMSK_IEPM_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_DAINTMSK_IEPM USB_OTG_DAINTMSK_IEPM_Msk /*!< IN EP interrupt mask bits */ +#define USB_OTG_DAINTMSK_OEPM_Pos (16U) +#define USB_OTG_DAINTMSK_OEPM_Msk (0xFFFFUL << USB_OTG_DAINTMSK_OEPM_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_DAINTMSK_OEPM USB_OTG_DAINTMSK_OEPM_Msk /*!< OUT EP interrupt mask bits */ + +/******************** Bit definition for USB_OTG_GRXFSIZ register ********************/ +#define USB_OTG_GRXFSIZ_RXFD_Pos (0U) +#define USB_OTG_GRXFSIZ_RXFD_Msk (0xFFFFUL << USB_OTG_GRXFSIZ_RXFD_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_GRXFSIZ_RXFD USB_OTG_GRXFSIZ_RXFD_Msk /*!< RxFIFO depth */ + +/******************** Bit definition for USB_OTG_DVBUSDIS register ********************/ +#define USB_OTG_DVBUSDIS_VBUSDT_Pos (0U) +#define USB_OTG_DVBUSDIS_VBUSDT_Msk (0xFFFFUL << USB_OTG_DVBUSDIS_VBUSDT_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_DVBUSDIS_VBUSDT USB_OTG_DVBUSDIS_VBUSDT_Msk /*!< Device VBUS discharge time */ + +/******************** Bit definition for OTG register ********************/ +#define USB_OTG_NPTXFSA_Pos (0U) +#define USB_OTG_NPTXFSA_Msk (0xFFFFUL << USB_OTG_NPTXFSA_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_NPTXFSA USB_OTG_NPTXFSA_Msk /*!< Nonperiodic transmit RAM start address */ +#define USB_OTG_NPTXFD_Pos (16U) +#define USB_OTG_NPTXFD_Msk (0xFFFFUL << USB_OTG_NPTXFD_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_NPTXFD USB_OTG_NPTXFD_Msk /*!< Nonperiodic TxFIFO depth */ +#define USB_OTG_TX0FSA_Pos (0U) +#define USB_OTG_TX0FSA_Msk (0xFFFFUL << USB_OTG_TX0FSA_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_TX0FSA USB_OTG_TX0FSA_Msk /*!< Endpoint 0 transmit RAM start address */ +#define USB_OTG_TX0FD_Pos (16U) +#define USB_OTG_TX0FD_Msk (0xFFFFUL << USB_OTG_TX0FD_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_TX0FD USB_OTG_TX0FD_Msk /*!< Endpoint 0 TxFIFO depth */ + +/******************** Bit definition for USB_OTG_DVBUSPULSE register ********************/ +#define USB_OTG_DVBUSPULSE_DVBUSP_Pos (0U) +#define USB_OTG_DVBUSPULSE_DVBUSP_Msk (0xFFFUL << USB_OTG_DVBUSPULSE_DVBUSP_Pos) /*!< 0x00000FFF */ +#define USB_OTG_DVBUSPULSE_DVBUSP USB_OTG_DVBUSPULSE_DVBUSP_Msk /*!< Device VBUS pulsing time */ + +/******************** Bit definition for USB_OTG_GNPTXSTS register ********************/ +#define USB_OTG_GNPTXSTS_NPTXFSAV_Pos (0U) +#define USB_OTG_GNPTXSTS_NPTXFSAV_Msk (0xFFFFUL << USB_OTG_GNPTXSTS_NPTXFSAV_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_GNPTXSTS_NPTXFSAV USB_OTG_GNPTXSTS_NPTXFSAV_Msk /*!< Nonperiodic TxFIFO space available */ + +#define USB_OTG_GNPTXSTS_NPTQXSAV_Pos (16U) +#define USB_OTG_GNPTXSTS_NPTQXSAV_Msk (0xFFUL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00FF0000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV USB_OTG_GNPTXSTS_NPTQXSAV_Msk /*!< Nonperiodic transmit request queue space available */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_0 (0x01UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00010000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_1 (0x02UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00020000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_2 (0x04UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00040000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_3 (0x08UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00080000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_4 (0x10UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00100000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_5 (0x20UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00200000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_6 (0x40UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00400000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_7 (0x80UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00800000 */ + +#define USB_OTG_GNPTXSTS_NPTXQTOP_Pos (24U) +#define USB_OTG_GNPTXSTS_NPTXQTOP_Msk (0x7FUL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x7F000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP USB_OTG_GNPTXSTS_NPTXQTOP_Msk /*!< Top of the nonperiodic transmit request queue */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_0 (0x01UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x01000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_1 (0x02UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x02000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_2 (0x04UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x04000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_3 (0x08UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x08000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_4 (0x10UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x10000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_5 (0x20UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x20000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_6 (0x40UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x40000000 */ + +/******************** Bit definition for USB_OTG_DTHRCTL register ********************/ +#define USB_OTG_DTHRCTL_NONISOTHREN_Pos (0U) +#define USB_OTG_DTHRCTL_NONISOTHREN_Msk (0x1UL << USB_OTG_DTHRCTL_NONISOTHREN_Pos) /*!< 0x00000001 */ +#define USB_OTG_DTHRCTL_NONISOTHREN USB_OTG_DTHRCTL_NONISOTHREN_Msk /*!< Nonisochronous IN endpoints threshold enable */ +#define USB_OTG_DTHRCTL_ISOTHREN_Pos (1U) +#define USB_OTG_DTHRCTL_ISOTHREN_Msk (0x1UL << USB_OTG_DTHRCTL_ISOTHREN_Pos) /*!< 0x00000002 */ +#define USB_OTG_DTHRCTL_ISOTHREN USB_OTG_DTHRCTL_ISOTHREN_Msk /*!< ISO IN endpoint threshold enable */ + +#define USB_OTG_DTHRCTL_TXTHRLEN_Pos (2U) +#define USB_OTG_DTHRCTL_TXTHRLEN_Msk (0x1FFUL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x000007FC */ +#define USB_OTG_DTHRCTL_TXTHRLEN USB_OTG_DTHRCTL_TXTHRLEN_Msk /*!< Transmit threshold length */ +#define USB_OTG_DTHRCTL_TXTHRLEN_0 (0x001UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000004 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_1 (0x002UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000008 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_2 (0x004UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000010 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_3 (0x008UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000020 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_4 (0x010UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000040 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_5 (0x020UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000080 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_6 (0x040UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000100 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_7 (0x080UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000200 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_8 (0x100UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000400 */ +#define USB_OTG_DTHRCTL_RXTHREN_Pos (16U) +#define USB_OTG_DTHRCTL_RXTHREN_Msk (0x1UL << USB_OTG_DTHRCTL_RXTHREN_Pos) /*!< 0x00010000 */ +#define USB_OTG_DTHRCTL_RXTHREN USB_OTG_DTHRCTL_RXTHREN_Msk /*!< Receive threshold enable */ + +#define USB_OTG_DTHRCTL_RXTHRLEN_Pos (17U) +#define USB_OTG_DTHRCTL_RXTHRLEN_Msk (0x1FFUL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x03FE0000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN USB_OTG_DTHRCTL_RXTHRLEN_Msk /*!< Receive threshold length */ +#define USB_OTG_DTHRCTL_RXTHRLEN_0 (0x001UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00020000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_1 (0x002UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00040000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_2 (0x004UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00080000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_3 (0x008UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00100000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_4 (0x010UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00200000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_5 (0x020UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00400000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_6 (0x040UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00800000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_7 (0x080UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x01000000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_8 (0x100UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x02000000 */ +#define USB_OTG_DTHRCTL_ARPEN_Pos (27U) +#define USB_OTG_DTHRCTL_ARPEN_Msk (0x1UL << USB_OTG_DTHRCTL_ARPEN_Pos) /*!< 0x08000000 */ +#define USB_OTG_DTHRCTL_ARPEN USB_OTG_DTHRCTL_ARPEN_Msk /*!< Arbiter parking enable */ + +/******************** Bit definition for USB_OTG_DIEPEMPMSK register ********************/ +#define USB_OTG_DIEPEMPMSK_INEPTXFEM_Pos (0U) +#define USB_OTG_DIEPEMPMSK_INEPTXFEM_Msk (0xFFFFUL << USB_OTG_DIEPEMPMSK_INEPTXFEM_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_DIEPEMPMSK_INEPTXFEM USB_OTG_DIEPEMPMSK_INEPTXFEM_Msk /*!< IN EP Tx FIFO empty interrupt mask bits */ + +/******************** Bit definition for USB_OTG_DEACHINT register ********************/ +#define USB_OTG_DEACHINT_IEP1INT_Pos (1U) +#define USB_OTG_DEACHINT_IEP1INT_Msk (0x1UL << USB_OTG_DEACHINT_IEP1INT_Pos) /*!< 0x00000002 */ +#define USB_OTG_DEACHINT_IEP1INT USB_OTG_DEACHINT_IEP1INT_Msk /*!< IN endpoint 1interrupt bit */ +#define USB_OTG_DEACHINT_OEP1INT_Pos (17U) +#define USB_OTG_DEACHINT_OEP1INT_Msk (0x1UL << USB_OTG_DEACHINT_OEP1INT_Pos) /*!< 0x00020000 */ +#define USB_OTG_DEACHINT_OEP1INT USB_OTG_DEACHINT_OEP1INT_Msk /*!< OUT endpoint 1 interrupt bit */ + +/******************** Bit definition for USB_OTG_GCCFG register ********************/ +#define USB_OTG_GCCFG_PWRDWN_Pos (16U) +#define USB_OTG_GCCFG_PWRDWN_Msk (0x1UL << USB_OTG_GCCFG_PWRDWN_Pos) /*!< 0x00010000 */ +#define USB_OTG_GCCFG_PWRDWN USB_OTG_GCCFG_PWRDWN_Msk /*!< Power down */ +#define USB_OTG_GCCFG_VBUSASEN_Pos (18U) +#define USB_OTG_GCCFG_VBUSASEN_Msk (0x1UL << USB_OTG_GCCFG_VBUSASEN_Pos) /*!< 0x00040000 */ +#define USB_OTG_GCCFG_VBUSASEN USB_OTG_GCCFG_VBUSASEN_Msk /*!< Enable the VBUS sensing device */ +#define USB_OTG_GCCFG_VBUSBSEN_Pos (19U) +#define USB_OTG_GCCFG_VBUSBSEN_Msk (0x1UL << USB_OTG_GCCFG_VBUSBSEN_Pos) /*!< 0x00080000 */ +#define USB_OTG_GCCFG_VBUSBSEN USB_OTG_GCCFG_VBUSBSEN_Msk /*!< Enable the VBUS sensing device */ +#define USB_OTG_GCCFG_SOFOUTEN_Pos (20U) +#define USB_OTG_GCCFG_SOFOUTEN_Msk (0x1UL << USB_OTG_GCCFG_SOFOUTEN_Pos) /*!< 0x00100000 */ +#define USB_OTG_GCCFG_SOFOUTEN USB_OTG_GCCFG_SOFOUTEN_Msk /*!< SOF output enable */ + +/******************** Bit definition for USB_OTG_DEACHINTMSK register ********************/ +#define USB_OTG_DEACHINTMSK_IEP1INTM_Pos (1U) +#define USB_OTG_DEACHINTMSK_IEP1INTM_Msk (0x1UL << USB_OTG_DEACHINTMSK_IEP1INTM_Pos) /*!< 0x00000002 */ +#define USB_OTG_DEACHINTMSK_IEP1INTM USB_OTG_DEACHINTMSK_IEP1INTM_Msk /*!< IN Endpoint 1 interrupt mask bit */ +#define USB_OTG_DEACHINTMSK_OEP1INTM_Pos (17U) +#define USB_OTG_DEACHINTMSK_OEP1INTM_Msk (0x1UL << USB_OTG_DEACHINTMSK_OEP1INTM_Pos) /*!< 0x00020000 */ +#define USB_OTG_DEACHINTMSK_OEP1INTM USB_OTG_DEACHINTMSK_OEP1INTM_Msk /*!< OUT Endpoint 1 interrupt mask bit */ + +/******************** Bit definition for USB_OTG_CID register ********************/ +#define USB_OTG_CID_PRODUCT_ID_Pos (0U) +#define USB_OTG_CID_PRODUCT_ID_Msk (0xFFFFFFFFUL << USB_OTG_CID_PRODUCT_ID_Pos) /*!< 0xFFFFFFFF */ +#define USB_OTG_CID_PRODUCT_ID USB_OTG_CID_PRODUCT_ID_Msk /*!< Product ID field */ + +/******************** Bit definition for USB_OTG_DIEPEACHMSK1 register ********************/ +#define USB_OTG_DIEPEACHMSK1_XFRCM_Pos (0U) +#define USB_OTG_DIEPEACHMSK1_XFRCM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ +#define USB_OTG_DIEPEACHMSK1_XFRCM USB_OTG_DIEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define USB_OTG_DIEPEACHMSK1_EPDM_Pos (1U) +#define USB_OTG_DIEPEACHMSK1_EPDM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ +#define USB_OTG_DIEPEACHMSK1_EPDM USB_OTG_DIEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define USB_OTG_DIEPEACHMSK1_TOM_Pos (3U) +#define USB_OTG_DIEPEACHMSK1_TOM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ +#define USB_OTG_DIEPEACHMSK1_TOM USB_OTG_DIEPEACHMSK1_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ +#define USB_OTG_DIEPEACHMSK1_ITTXFEMSK_Pos (4U) +#define USB_OTG_DIEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ +#define USB_OTG_DIEPEACHMSK1_ITTXFEMSK USB_OTG_DIEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define USB_OTG_DIEPEACHMSK1_INEPNMM_Pos (5U) +#define USB_OTG_DIEPEACHMSK1_INEPNMM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ +#define USB_OTG_DIEPEACHMSK1_INEPNMM USB_OTG_DIEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define USB_OTG_DIEPEACHMSK1_INEPNEM_Pos (6U) +#define USB_OTG_DIEPEACHMSK1_INEPNEM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ +#define USB_OTG_DIEPEACHMSK1_INEPNEM USB_OTG_DIEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define USB_OTG_DIEPEACHMSK1_TXFURM_Pos (8U) +#define USB_OTG_DIEPEACHMSK1_TXFURM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ +#define USB_OTG_DIEPEACHMSK1_TXFURM USB_OTG_DIEPEACHMSK1_TXFURM_Msk /*!< FIFO underrun mask */ +#define USB_OTG_DIEPEACHMSK1_BIM_Pos (9U) +#define USB_OTG_DIEPEACHMSK1_BIM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ +#define USB_OTG_DIEPEACHMSK1_BIM USB_OTG_DIEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ +#define USB_OTG_DIEPEACHMSK1_NAKM_Pos (13U) +#define USB_OTG_DIEPEACHMSK1_NAKM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ +#define USB_OTG_DIEPEACHMSK1_NAKM USB_OTG_DIEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ + +/******************** Bit definition for USB_OTG_HPRT register ********************/ +#define USB_OTG_HPRT_PCSTS_Pos (0U) +#define USB_OTG_HPRT_PCSTS_Msk (0x1UL << USB_OTG_HPRT_PCSTS_Pos) /*!< 0x00000001 */ +#define USB_OTG_HPRT_PCSTS USB_OTG_HPRT_PCSTS_Msk /*!< Port connect status */ +#define USB_OTG_HPRT_PCDET_Pos (1U) +#define USB_OTG_HPRT_PCDET_Msk (0x1UL << USB_OTG_HPRT_PCDET_Pos) /*!< 0x00000002 */ +#define USB_OTG_HPRT_PCDET USB_OTG_HPRT_PCDET_Msk /*!< Port connect detected */ +#define USB_OTG_HPRT_PENA_Pos (2U) +#define USB_OTG_HPRT_PENA_Msk (0x1UL << USB_OTG_HPRT_PENA_Pos) /*!< 0x00000004 */ +#define USB_OTG_HPRT_PENA USB_OTG_HPRT_PENA_Msk /*!< Port enable */ +#define USB_OTG_HPRT_PENCHNG_Pos (3U) +#define USB_OTG_HPRT_PENCHNG_Msk (0x1UL << USB_OTG_HPRT_PENCHNG_Pos) /*!< 0x00000008 */ +#define USB_OTG_HPRT_PENCHNG USB_OTG_HPRT_PENCHNG_Msk /*!< Port enable/disable change */ +#define USB_OTG_HPRT_POCA_Pos (4U) +#define USB_OTG_HPRT_POCA_Msk (0x1UL << USB_OTG_HPRT_POCA_Pos) /*!< 0x00000010 */ +#define USB_OTG_HPRT_POCA USB_OTG_HPRT_POCA_Msk /*!< Port overcurrent active */ +#define USB_OTG_HPRT_POCCHNG_Pos (5U) +#define USB_OTG_HPRT_POCCHNG_Msk (0x1UL << USB_OTG_HPRT_POCCHNG_Pos) /*!< 0x00000020 */ +#define USB_OTG_HPRT_POCCHNG USB_OTG_HPRT_POCCHNG_Msk /*!< Port overcurrent change */ +#define USB_OTG_HPRT_PRES_Pos (6U) +#define USB_OTG_HPRT_PRES_Msk (0x1UL << USB_OTG_HPRT_PRES_Pos) /*!< 0x00000040 */ +#define USB_OTG_HPRT_PRES USB_OTG_HPRT_PRES_Msk /*!< Port resume */ +#define USB_OTG_HPRT_PSUSP_Pos (7U) +#define USB_OTG_HPRT_PSUSP_Msk (0x1UL << USB_OTG_HPRT_PSUSP_Pos) /*!< 0x00000080 */ +#define USB_OTG_HPRT_PSUSP USB_OTG_HPRT_PSUSP_Msk /*!< Port suspend */ +#define USB_OTG_HPRT_PRST_Pos (8U) +#define USB_OTG_HPRT_PRST_Msk (0x1UL << USB_OTG_HPRT_PRST_Pos) /*!< 0x00000100 */ +#define USB_OTG_HPRT_PRST USB_OTG_HPRT_PRST_Msk /*!< Port reset */ + +#define USB_OTG_HPRT_PLSTS_Pos (10U) +#define USB_OTG_HPRT_PLSTS_Msk (0x3UL << USB_OTG_HPRT_PLSTS_Pos) /*!< 0x00000C00 */ +#define USB_OTG_HPRT_PLSTS USB_OTG_HPRT_PLSTS_Msk /*!< Port line status */ +#define USB_OTG_HPRT_PLSTS_0 (0x1UL << USB_OTG_HPRT_PLSTS_Pos) /*!< 0x00000400 */ +#define USB_OTG_HPRT_PLSTS_1 (0x2UL << USB_OTG_HPRT_PLSTS_Pos) /*!< 0x00000800 */ +#define USB_OTG_HPRT_PPWR_Pos (12U) +#define USB_OTG_HPRT_PPWR_Msk (0x1UL << USB_OTG_HPRT_PPWR_Pos) /*!< 0x00001000 */ +#define USB_OTG_HPRT_PPWR USB_OTG_HPRT_PPWR_Msk /*!< Port power */ + +#define USB_OTG_HPRT_PTCTL_Pos (13U) +#define USB_OTG_HPRT_PTCTL_Msk (0xFUL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x0001E000 */ +#define USB_OTG_HPRT_PTCTL USB_OTG_HPRT_PTCTL_Msk /*!< Port test control */ +#define USB_OTG_HPRT_PTCTL_0 (0x1UL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x00002000 */ +#define USB_OTG_HPRT_PTCTL_1 (0x2UL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x00004000 */ +#define USB_OTG_HPRT_PTCTL_2 (0x4UL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x00008000 */ +#define USB_OTG_HPRT_PTCTL_3 (0x8UL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x00010000 */ + +#define USB_OTG_HPRT_PSPD_Pos (17U) +#define USB_OTG_HPRT_PSPD_Msk (0x3UL << USB_OTG_HPRT_PSPD_Pos) /*!< 0x00060000 */ +#define USB_OTG_HPRT_PSPD USB_OTG_HPRT_PSPD_Msk /*!< Port speed */ +#define USB_OTG_HPRT_PSPD_0 (0x1UL << USB_OTG_HPRT_PSPD_Pos) /*!< 0x00020000 */ +#define USB_OTG_HPRT_PSPD_1 (0x2UL << USB_OTG_HPRT_PSPD_Pos) /*!< 0x00040000 */ + +/******************** Bit definition for USB_OTG_DOEPEACHMSK1 register ********************/ +#define USB_OTG_DOEPEACHMSK1_XFRCM_Pos (0U) +#define USB_OTG_DOEPEACHMSK1_XFRCM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ +#define USB_OTG_DOEPEACHMSK1_XFRCM USB_OTG_DOEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define USB_OTG_DOEPEACHMSK1_EPDM_Pos (1U) +#define USB_OTG_DOEPEACHMSK1_EPDM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ +#define USB_OTG_DOEPEACHMSK1_EPDM USB_OTG_DOEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define USB_OTG_DOEPEACHMSK1_TOM_Pos (3U) +#define USB_OTG_DOEPEACHMSK1_TOM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ +#define USB_OTG_DOEPEACHMSK1_TOM USB_OTG_DOEPEACHMSK1_TOM_Msk /*!< Timeout condition mask */ +#define USB_OTG_DOEPEACHMSK1_ITTXFEMSK_Pos (4U) +#define USB_OTG_DOEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ +#define USB_OTG_DOEPEACHMSK1_ITTXFEMSK USB_OTG_DOEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define USB_OTG_DOEPEACHMSK1_INEPNMM_Pos (5U) +#define USB_OTG_DOEPEACHMSK1_INEPNMM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ +#define USB_OTG_DOEPEACHMSK1_INEPNMM USB_OTG_DOEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define USB_OTG_DOEPEACHMSK1_INEPNEM_Pos (6U) +#define USB_OTG_DOEPEACHMSK1_INEPNEM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ +#define USB_OTG_DOEPEACHMSK1_INEPNEM USB_OTG_DOEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define USB_OTG_DOEPEACHMSK1_TXFURM_Pos (8U) +#define USB_OTG_DOEPEACHMSK1_TXFURM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ +#define USB_OTG_DOEPEACHMSK1_TXFURM USB_OTG_DOEPEACHMSK1_TXFURM_Msk /*!< OUT packet error mask */ +#define USB_OTG_DOEPEACHMSK1_BIM_Pos (9U) +#define USB_OTG_DOEPEACHMSK1_BIM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ +#define USB_OTG_DOEPEACHMSK1_BIM USB_OTG_DOEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ +#define USB_OTG_DOEPEACHMSK1_BERRM_Pos (12U) +#define USB_OTG_DOEPEACHMSK1_BERRM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_BERRM_Pos) /*!< 0x00001000 */ +#define USB_OTG_DOEPEACHMSK1_BERRM USB_OTG_DOEPEACHMSK1_BERRM_Msk /*!< Bubble error interrupt mask */ +#define USB_OTG_DOEPEACHMSK1_NAKM_Pos (13U) +#define USB_OTG_DOEPEACHMSK1_NAKM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ +#define USB_OTG_DOEPEACHMSK1_NAKM USB_OTG_DOEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ +#define USB_OTG_DOEPEACHMSK1_NYETM_Pos (14U) +#define USB_OTG_DOEPEACHMSK1_NYETM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_NYETM_Pos) /*!< 0x00004000 */ +#define USB_OTG_DOEPEACHMSK1_NYETM USB_OTG_DOEPEACHMSK1_NYETM_Msk /*!< NYET interrupt mask */ + +/******************** Bit definition for USB_OTG_HPTXFSIZ register ********************/ +#define USB_OTG_HPTXFSIZ_PTXSA_Pos (0U) +#define USB_OTG_HPTXFSIZ_PTXSA_Msk (0xFFFFUL << USB_OTG_HPTXFSIZ_PTXSA_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_HPTXFSIZ_PTXSA USB_OTG_HPTXFSIZ_PTXSA_Msk /*!< Host periodic TxFIFO start address */ +#define USB_OTG_HPTXFSIZ_PTXFD_Pos (16U) +#define USB_OTG_HPTXFSIZ_PTXFD_Msk (0xFFFFUL << USB_OTG_HPTXFSIZ_PTXFD_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_HPTXFSIZ_PTXFD USB_OTG_HPTXFSIZ_PTXFD_Msk /*!< Host periodic TxFIFO depth */ + +/******************** Bit definition for USB_OTG_DIEPCTL register ********************/ +#define USB_OTG_DIEPCTL_MPSIZ_Pos (0U) +#define USB_OTG_DIEPCTL_MPSIZ_Msk (0x7FFUL << USB_OTG_DIEPCTL_MPSIZ_Pos) /*!< 0x000007FF */ +#define USB_OTG_DIEPCTL_MPSIZ USB_OTG_DIEPCTL_MPSIZ_Msk /*!< Maximum packet size */ +#define USB_OTG_DIEPCTL_USBAEP_Pos (15U) +#define USB_OTG_DIEPCTL_USBAEP_Msk (0x1UL << USB_OTG_DIEPCTL_USBAEP_Pos) /*!< 0x00008000 */ +#define USB_OTG_DIEPCTL_USBAEP USB_OTG_DIEPCTL_USBAEP_Msk /*!< USB active endpoint */ +#define USB_OTG_DIEPCTL_EONUM_DPID_Pos (16U) +#define USB_OTG_DIEPCTL_EONUM_DPID_Msk (0x1UL << USB_OTG_DIEPCTL_EONUM_DPID_Pos) /*!< 0x00010000 */ +#define USB_OTG_DIEPCTL_EONUM_DPID USB_OTG_DIEPCTL_EONUM_DPID_Msk /*!< Even/odd frame */ +#define USB_OTG_DIEPCTL_NAKSTS_Pos (17U) +#define USB_OTG_DIEPCTL_NAKSTS_Msk (0x1UL << USB_OTG_DIEPCTL_NAKSTS_Pos) /*!< 0x00020000 */ +#define USB_OTG_DIEPCTL_NAKSTS USB_OTG_DIEPCTL_NAKSTS_Msk /*!< NAK status */ + +#define USB_OTG_DIEPCTL_EPTYP_Pos (18U) +#define USB_OTG_DIEPCTL_EPTYP_Msk (0x3UL << USB_OTG_DIEPCTL_EPTYP_Pos) /*!< 0x000C0000 */ +#define USB_OTG_DIEPCTL_EPTYP USB_OTG_DIEPCTL_EPTYP_Msk /*!< Endpoint type */ +#define USB_OTG_DIEPCTL_EPTYP_0 (0x1UL << USB_OTG_DIEPCTL_EPTYP_Pos) /*!< 0x00040000 */ +#define USB_OTG_DIEPCTL_EPTYP_1 (0x2UL << USB_OTG_DIEPCTL_EPTYP_Pos) /*!< 0x00080000 */ +#define USB_OTG_DIEPCTL_STALL_Pos (21U) +#define USB_OTG_DIEPCTL_STALL_Msk (0x1UL << USB_OTG_DIEPCTL_STALL_Pos) /*!< 0x00200000 */ +#define USB_OTG_DIEPCTL_STALL USB_OTG_DIEPCTL_STALL_Msk /*!< STALL handshake */ + +#define USB_OTG_DIEPCTL_TXFNUM_Pos (22U) +#define USB_OTG_DIEPCTL_TXFNUM_Msk (0xFUL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x03C00000 */ +#define USB_OTG_DIEPCTL_TXFNUM USB_OTG_DIEPCTL_TXFNUM_Msk /*!< TxFIFO number */ +#define USB_OTG_DIEPCTL_TXFNUM_0 (0x1UL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x00400000 */ +#define USB_OTG_DIEPCTL_TXFNUM_1 (0x2UL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x00800000 */ +#define USB_OTG_DIEPCTL_TXFNUM_2 (0x4UL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x01000000 */ +#define USB_OTG_DIEPCTL_TXFNUM_3 (0x8UL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x02000000 */ +#define USB_OTG_DIEPCTL_CNAK_Pos (26U) +#define USB_OTG_DIEPCTL_CNAK_Msk (0x1UL << USB_OTG_DIEPCTL_CNAK_Pos) /*!< 0x04000000 */ +#define USB_OTG_DIEPCTL_CNAK USB_OTG_DIEPCTL_CNAK_Msk /*!< Clear NAK */ +#define USB_OTG_DIEPCTL_SNAK_Pos (27U) +#define USB_OTG_DIEPCTL_SNAK_Msk (0x1UL << USB_OTG_DIEPCTL_SNAK_Pos) /*!< 0x08000000 */ +#define USB_OTG_DIEPCTL_SNAK USB_OTG_DIEPCTL_SNAK_Msk /*!< Set NAK */ +#define USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Pos (28U) +#define USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Msk (0x1UL << USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Pos) /*!< 0x10000000 */ +#define USB_OTG_DIEPCTL_SD0PID_SEVNFRM USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Msk /*!< Set DATA0 PID */ +#define USB_OTG_DIEPCTL_SODDFRM_Pos (29U) +#define USB_OTG_DIEPCTL_SODDFRM_Msk (0x1UL << USB_OTG_DIEPCTL_SODDFRM_Pos) /*!< 0x20000000 */ +#define USB_OTG_DIEPCTL_SODDFRM USB_OTG_DIEPCTL_SODDFRM_Msk /*!< Set odd frame */ +#define USB_OTG_DIEPCTL_EPDIS_Pos (30U) +#define USB_OTG_DIEPCTL_EPDIS_Msk (0x1UL << USB_OTG_DIEPCTL_EPDIS_Pos) /*!< 0x40000000 */ +#define USB_OTG_DIEPCTL_EPDIS USB_OTG_DIEPCTL_EPDIS_Msk /*!< Endpoint disable */ +#define USB_OTG_DIEPCTL_EPENA_Pos (31U) +#define USB_OTG_DIEPCTL_EPENA_Msk (0x1UL << USB_OTG_DIEPCTL_EPENA_Pos) /*!< 0x80000000 */ +#define USB_OTG_DIEPCTL_EPENA USB_OTG_DIEPCTL_EPENA_Msk /*!< Endpoint enable */ + +/******************** Bit definition for USB_OTG_HCCHAR register ********************/ +#define USB_OTG_HCCHAR_MPSIZ_Pos (0U) +#define USB_OTG_HCCHAR_MPSIZ_Msk (0x7FFUL << USB_OTG_HCCHAR_MPSIZ_Pos) /*!< 0x000007FF */ +#define USB_OTG_HCCHAR_MPSIZ USB_OTG_HCCHAR_MPSIZ_Msk /*!< Maximum packet size */ + +#define USB_OTG_HCCHAR_EPNUM_Pos (11U) +#define USB_OTG_HCCHAR_EPNUM_Msk (0xFUL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00007800 */ +#define USB_OTG_HCCHAR_EPNUM USB_OTG_HCCHAR_EPNUM_Msk /*!< Endpoint number */ +#define USB_OTG_HCCHAR_EPNUM_0 (0x1UL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00000800 */ +#define USB_OTG_HCCHAR_EPNUM_1 (0x2UL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00001000 */ +#define USB_OTG_HCCHAR_EPNUM_2 (0x4UL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00002000 */ +#define USB_OTG_HCCHAR_EPNUM_3 (0x8UL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00004000 */ +#define USB_OTG_HCCHAR_EPDIR_Pos (15U) +#define USB_OTG_HCCHAR_EPDIR_Msk (0x1UL << USB_OTG_HCCHAR_EPDIR_Pos) /*!< 0x00008000 */ +#define USB_OTG_HCCHAR_EPDIR USB_OTG_HCCHAR_EPDIR_Msk /*!< Endpoint direction */ +#define USB_OTG_HCCHAR_LSDEV_Pos (17U) +#define USB_OTG_HCCHAR_LSDEV_Msk (0x1UL << USB_OTG_HCCHAR_LSDEV_Pos) /*!< 0x00020000 */ +#define USB_OTG_HCCHAR_LSDEV USB_OTG_HCCHAR_LSDEV_Msk /*!< Low-speed device */ + +#define USB_OTG_HCCHAR_EPTYP_Pos (18U) +#define USB_OTG_HCCHAR_EPTYP_Msk (0x3UL << USB_OTG_HCCHAR_EPTYP_Pos) /*!< 0x000C0000 */ +#define USB_OTG_HCCHAR_EPTYP USB_OTG_HCCHAR_EPTYP_Msk /*!< Endpoint type */ +#define USB_OTG_HCCHAR_EPTYP_0 (0x1UL << USB_OTG_HCCHAR_EPTYP_Pos) /*!< 0x00040000 */ +#define USB_OTG_HCCHAR_EPTYP_1 (0x2UL << USB_OTG_HCCHAR_EPTYP_Pos) /*!< 0x00080000 */ + +#define USB_OTG_HCCHAR_MC_Pos (20U) +#define USB_OTG_HCCHAR_MC_Msk (0x3UL << USB_OTG_HCCHAR_MC_Pos) /*!< 0x00300000 */ +#define USB_OTG_HCCHAR_MC USB_OTG_HCCHAR_MC_Msk /*!< Multi Count (MC) / Error Count (EC) */ +#define USB_OTG_HCCHAR_MC_0 (0x1UL << USB_OTG_HCCHAR_MC_Pos) /*!< 0x00100000 */ +#define USB_OTG_HCCHAR_MC_1 (0x2UL << USB_OTG_HCCHAR_MC_Pos) /*!< 0x00200000 */ + +#define USB_OTG_HCCHAR_DAD_Pos (22U) +#define USB_OTG_HCCHAR_DAD_Msk (0x7FUL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x1FC00000 */ +#define USB_OTG_HCCHAR_DAD USB_OTG_HCCHAR_DAD_Msk /*!< Device address */ +#define USB_OTG_HCCHAR_DAD_0 (0x01UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x00400000 */ +#define USB_OTG_HCCHAR_DAD_1 (0x02UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x00800000 */ +#define USB_OTG_HCCHAR_DAD_2 (0x04UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x01000000 */ +#define USB_OTG_HCCHAR_DAD_3 (0x08UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x02000000 */ +#define USB_OTG_HCCHAR_DAD_4 (0x10UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x04000000 */ +#define USB_OTG_HCCHAR_DAD_5 (0x20UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x08000000 */ +#define USB_OTG_HCCHAR_DAD_6 (0x40UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x10000000 */ +#define USB_OTG_HCCHAR_ODDFRM_Pos (29U) +#define USB_OTG_HCCHAR_ODDFRM_Msk (0x1UL << USB_OTG_HCCHAR_ODDFRM_Pos) /*!< 0x20000000 */ +#define USB_OTG_HCCHAR_ODDFRM USB_OTG_HCCHAR_ODDFRM_Msk /*!< Odd frame */ +#define USB_OTG_HCCHAR_CHDIS_Pos (30U) +#define USB_OTG_HCCHAR_CHDIS_Msk (0x1UL << USB_OTG_HCCHAR_CHDIS_Pos) /*!< 0x40000000 */ +#define USB_OTG_HCCHAR_CHDIS USB_OTG_HCCHAR_CHDIS_Msk /*!< Channel disable */ +#define USB_OTG_HCCHAR_CHENA_Pos (31U) +#define USB_OTG_HCCHAR_CHENA_Msk (0x1UL << USB_OTG_HCCHAR_CHENA_Pos) /*!< 0x80000000 */ +#define USB_OTG_HCCHAR_CHENA USB_OTG_HCCHAR_CHENA_Msk /*!< Channel enable */ + +/******************** Bit definition for USB_OTG_HCSPLT register ********************/ + +#define USB_OTG_HCSPLT_PRTADDR_Pos (0U) +#define USB_OTG_HCSPLT_PRTADDR_Msk (0x7FUL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x0000007F */ +#define USB_OTG_HCSPLT_PRTADDR USB_OTG_HCSPLT_PRTADDR_Msk /*!< Port address */ +#define USB_OTG_HCSPLT_PRTADDR_0 (0x01UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000001 */ +#define USB_OTG_HCSPLT_PRTADDR_1 (0x02UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000002 */ +#define USB_OTG_HCSPLT_PRTADDR_2 (0x04UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000004 */ +#define USB_OTG_HCSPLT_PRTADDR_3 (0x08UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000008 */ +#define USB_OTG_HCSPLT_PRTADDR_4 (0x10UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000010 */ +#define USB_OTG_HCSPLT_PRTADDR_5 (0x20UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000020 */ +#define USB_OTG_HCSPLT_PRTADDR_6 (0x40UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000040 */ + +#define USB_OTG_HCSPLT_HUBADDR_Pos (7U) +#define USB_OTG_HCSPLT_HUBADDR_Msk (0x7FUL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00003F80 */ +#define USB_OTG_HCSPLT_HUBADDR USB_OTG_HCSPLT_HUBADDR_Msk /*!< Hub address */ +#define USB_OTG_HCSPLT_HUBADDR_0 (0x01UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000080 */ +#define USB_OTG_HCSPLT_HUBADDR_1 (0x02UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000100 */ +#define USB_OTG_HCSPLT_HUBADDR_2 (0x04UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000200 */ +#define USB_OTG_HCSPLT_HUBADDR_3 (0x08UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000400 */ +#define USB_OTG_HCSPLT_HUBADDR_4 (0x10UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000800 */ +#define USB_OTG_HCSPLT_HUBADDR_5 (0x20UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00001000 */ +#define USB_OTG_HCSPLT_HUBADDR_6 (0x40UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00002000 */ + +#define USB_OTG_HCSPLT_XACTPOS_Pos (14U) +#define USB_OTG_HCSPLT_XACTPOS_Msk (0x3UL << USB_OTG_HCSPLT_XACTPOS_Pos) /*!< 0x0000C000 */ +#define USB_OTG_HCSPLT_XACTPOS USB_OTG_HCSPLT_XACTPOS_Msk /*!< XACTPOS */ +#define USB_OTG_HCSPLT_XACTPOS_0 (0x1UL << USB_OTG_HCSPLT_XACTPOS_Pos) /*!< 0x00004000 */ +#define USB_OTG_HCSPLT_XACTPOS_1 (0x2UL << USB_OTG_HCSPLT_XACTPOS_Pos) /*!< 0x00008000 */ +#define USB_OTG_HCSPLT_COMPLSPLT_Pos (16U) +#define USB_OTG_HCSPLT_COMPLSPLT_Msk (0x1UL << USB_OTG_HCSPLT_COMPLSPLT_Pos) /*!< 0x00010000 */ +#define USB_OTG_HCSPLT_COMPLSPLT USB_OTG_HCSPLT_COMPLSPLT_Msk /*!< Do complete split */ +#define USB_OTG_HCSPLT_SPLITEN_Pos (31U) +#define USB_OTG_HCSPLT_SPLITEN_Msk (0x1UL << USB_OTG_HCSPLT_SPLITEN_Pos) /*!< 0x80000000 */ +#define USB_OTG_HCSPLT_SPLITEN USB_OTG_HCSPLT_SPLITEN_Msk /*!< Split enable */ + +/******************** Bit definition for USB_OTG_HCINT register ********************/ +#define USB_OTG_HCINT_XFRC_Pos (0U) +#define USB_OTG_HCINT_XFRC_Msk (0x1UL << USB_OTG_HCINT_XFRC_Pos) /*!< 0x00000001 */ +#define USB_OTG_HCINT_XFRC USB_OTG_HCINT_XFRC_Msk /*!< Transfer completed */ +#define USB_OTG_HCINT_CHH_Pos (1U) +#define USB_OTG_HCINT_CHH_Msk (0x1UL << USB_OTG_HCINT_CHH_Pos) /*!< 0x00000002 */ +#define USB_OTG_HCINT_CHH USB_OTG_HCINT_CHH_Msk /*!< Channel halted */ +#define USB_OTG_HCINT_AHBERR_Pos (2U) +#define USB_OTG_HCINT_AHBERR_Msk (0x1UL << USB_OTG_HCINT_AHBERR_Pos) /*!< 0x00000004 */ +#define USB_OTG_HCINT_AHBERR USB_OTG_HCINT_AHBERR_Msk /*!< AHB error */ +#define USB_OTG_HCINT_STALL_Pos (3U) +#define USB_OTG_HCINT_STALL_Msk (0x1UL << USB_OTG_HCINT_STALL_Pos) /*!< 0x00000008 */ +#define USB_OTG_HCINT_STALL USB_OTG_HCINT_STALL_Msk /*!< STALL response received interrupt */ +#define USB_OTG_HCINT_NAK_Pos (4U) +#define USB_OTG_HCINT_NAK_Msk (0x1UL << USB_OTG_HCINT_NAK_Pos) /*!< 0x00000010 */ +#define USB_OTG_HCINT_NAK USB_OTG_HCINT_NAK_Msk /*!< NAK response received interrupt */ +#define USB_OTG_HCINT_ACK_Pos (5U) +#define USB_OTG_HCINT_ACK_Msk (0x1UL << USB_OTG_HCINT_ACK_Pos) /*!< 0x00000020 */ +#define USB_OTG_HCINT_ACK USB_OTG_HCINT_ACK_Msk /*!< ACK response received/transmitted interrupt */ +#define USB_OTG_HCINT_NYET_Pos (6U) +#define USB_OTG_HCINT_NYET_Msk (0x1UL << USB_OTG_HCINT_NYET_Pos) /*!< 0x00000040 */ +#define USB_OTG_HCINT_NYET USB_OTG_HCINT_NYET_Msk /*!< Response received interrupt */ +#define USB_OTG_HCINT_TXERR_Pos (7U) +#define USB_OTG_HCINT_TXERR_Msk (0x1UL << USB_OTG_HCINT_TXERR_Pos) /*!< 0x00000080 */ +#define USB_OTG_HCINT_TXERR USB_OTG_HCINT_TXERR_Msk /*!< Transaction error */ +#define USB_OTG_HCINT_BBERR_Pos (8U) +#define USB_OTG_HCINT_BBERR_Msk (0x1UL << USB_OTG_HCINT_BBERR_Pos) /*!< 0x00000100 */ +#define USB_OTG_HCINT_BBERR USB_OTG_HCINT_BBERR_Msk /*!< Babble error */ +#define USB_OTG_HCINT_FRMOR_Pos (9U) +#define USB_OTG_HCINT_FRMOR_Msk (0x1UL << USB_OTG_HCINT_FRMOR_Pos) /*!< 0x00000200 */ +#define USB_OTG_HCINT_FRMOR USB_OTG_HCINT_FRMOR_Msk /*!< Frame overrun */ +#define USB_OTG_HCINT_DTERR_Pos (10U) +#define USB_OTG_HCINT_DTERR_Msk (0x1UL << USB_OTG_HCINT_DTERR_Pos) /*!< 0x00000400 */ +#define USB_OTG_HCINT_DTERR USB_OTG_HCINT_DTERR_Msk /*!< Data toggle error */ + +/******************** Bit definition for USB_OTG_DIEPINT register ********************/ +#define USB_OTG_DIEPINT_XFRC_Pos (0U) +#define USB_OTG_DIEPINT_XFRC_Msk (0x1UL << USB_OTG_DIEPINT_XFRC_Pos) /*!< 0x00000001 */ +#define USB_OTG_DIEPINT_XFRC USB_OTG_DIEPINT_XFRC_Msk /*!< Transfer completed interrupt */ +#define USB_OTG_DIEPINT_EPDISD_Pos (1U) +#define USB_OTG_DIEPINT_EPDISD_Msk (0x1UL << USB_OTG_DIEPINT_EPDISD_Pos) /*!< 0x00000002 */ +#define USB_OTG_DIEPINT_EPDISD USB_OTG_DIEPINT_EPDISD_Msk /*!< Endpoint disabled interrupt */ +#define USB_OTG_DIEPINT_AHBERR_Pos (2U) +#define USB_OTG_DIEPINT_AHBERR_Msk (0x1UL << USB_OTG_DIEPINT_AHBERR_Pos) /*!< 0x00000004 */ +#define USB_OTG_DIEPINT_AHBERR USB_OTG_DIEPINT_AHBERR_Msk /*!< AHB Error (AHBErr) during an IN transaction */ +#define USB_OTG_DIEPINT_TOC_Pos (3U) +#define USB_OTG_DIEPINT_TOC_Msk (0x1UL << USB_OTG_DIEPINT_TOC_Pos) /*!< 0x00000008 */ +#define USB_OTG_DIEPINT_TOC USB_OTG_DIEPINT_TOC_Msk /*!< Timeout condition */ +#define USB_OTG_DIEPINT_ITTXFE_Pos (4U) +#define USB_OTG_DIEPINT_ITTXFE_Msk (0x1UL << USB_OTG_DIEPINT_ITTXFE_Pos) /*!< 0x00000010 */ +#define USB_OTG_DIEPINT_ITTXFE USB_OTG_DIEPINT_ITTXFE_Msk /*!< IN token received when TxFIFO is empty */ +#define USB_OTG_DIEPINT_INEPNM_Pos (5U) +#define USB_OTG_DIEPINT_INEPNM_Msk (0x1UL << USB_OTG_DIEPINT_INEPNM_Pos) /*!< 0x00000004 */ +#define USB_OTG_DIEPINT_INEPNM USB_OTG_DIEPINT_INEPNM_Msk /*!< IN token received with EP mismatch */ +#define USB_OTG_DIEPINT_INEPNE_Pos (6U) +#define USB_OTG_DIEPINT_INEPNE_Msk (0x1UL << USB_OTG_DIEPINT_INEPNE_Pos) /*!< 0x00000040 */ +#define USB_OTG_DIEPINT_INEPNE USB_OTG_DIEPINT_INEPNE_Msk /*!< IN endpoint NAK effective */ +#define USB_OTG_DIEPINT_TXFE_Pos (7U) +#define USB_OTG_DIEPINT_TXFE_Msk (0x1UL << USB_OTG_DIEPINT_TXFE_Pos) /*!< 0x00000080 */ +#define USB_OTG_DIEPINT_TXFE USB_OTG_DIEPINT_TXFE_Msk /*!< Transmit FIFO empty */ +#define USB_OTG_DIEPINT_TXFIFOUDRN_Pos (8U) +#define USB_OTG_DIEPINT_TXFIFOUDRN_Msk (0x1UL << USB_OTG_DIEPINT_TXFIFOUDRN_Pos) /*!< 0x00000100 */ +#define USB_OTG_DIEPINT_TXFIFOUDRN USB_OTG_DIEPINT_TXFIFOUDRN_Msk /*!< Transmit Fifo Underrun */ +#define USB_OTG_DIEPINT_BNA_Pos (9U) +#define USB_OTG_DIEPINT_BNA_Msk (0x1UL << USB_OTG_DIEPINT_BNA_Pos) /*!< 0x00000200 */ +#define USB_OTG_DIEPINT_BNA USB_OTG_DIEPINT_BNA_Msk /*!< Buffer not available interrupt */ +#define USB_OTG_DIEPINT_PKTDRPSTS_Pos (11U) +#define USB_OTG_DIEPINT_PKTDRPSTS_Msk (0x1UL << USB_OTG_DIEPINT_PKTDRPSTS_Pos) /*!< 0x00000800 */ +#define USB_OTG_DIEPINT_PKTDRPSTS USB_OTG_DIEPINT_PKTDRPSTS_Msk /*!< Packet dropped status */ +#define USB_OTG_DIEPINT_BERR_Pos (12U) +#define USB_OTG_DIEPINT_BERR_Msk (0x1UL << USB_OTG_DIEPINT_BERR_Pos) /*!< 0x00001000 */ +#define USB_OTG_DIEPINT_BERR USB_OTG_DIEPINT_BERR_Msk /*!< Babble error interrupt */ +#define USB_OTG_DIEPINT_NAK_Pos (13U) +#define USB_OTG_DIEPINT_NAK_Msk (0x1UL << USB_OTG_DIEPINT_NAK_Pos) /*!< 0x00002000 */ +#define USB_OTG_DIEPINT_NAK USB_OTG_DIEPINT_NAK_Msk /*!< NAK interrupt */ + +/******************** Bit definition for USB_OTG_HCINTMSK register ********************/ +#define USB_OTG_HCINTMSK_XFRCM_Pos (0U) +#define USB_OTG_HCINTMSK_XFRCM_Msk (0x1UL << USB_OTG_HCINTMSK_XFRCM_Pos) /*!< 0x00000001 */ +#define USB_OTG_HCINTMSK_XFRCM USB_OTG_HCINTMSK_XFRCM_Msk /*!< Transfer completed mask */ +#define USB_OTG_HCINTMSK_CHHM_Pos (1U) +#define USB_OTG_HCINTMSK_CHHM_Msk (0x1UL << USB_OTG_HCINTMSK_CHHM_Pos) /*!< 0x00000002 */ +#define USB_OTG_HCINTMSK_CHHM USB_OTG_HCINTMSK_CHHM_Msk /*!< Channel halted mask */ +#define USB_OTG_HCINTMSK_AHBERR_Pos (2U) +#define USB_OTG_HCINTMSK_AHBERR_Msk (0x1UL << USB_OTG_HCINTMSK_AHBERR_Pos) /*!< 0x00000004 */ +#define USB_OTG_HCINTMSK_AHBERR USB_OTG_HCINTMSK_AHBERR_Msk /*!< AHB error */ +#define USB_OTG_HCINTMSK_STALLM_Pos (3U) +#define USB_OTG_HCINTMSK_STALLM_Msk (0x1UL << USB_OTG_HCINTMSK_STALLM_Pos) /*!< 0x00000008 */ +#define USB_OTG_HCINTMSK_STALLM USB_OTG_HCINTMSK_STALLM_Msk /*!< STALL response received interrupt mask */ +#define USB_OTG_HCINTMSK_NAKM_Pos (4U) +#define USB_OTG_HCINTMSK_NAKM_Msk (0x1UL << USB_OTG_HCINTMSK_NAKM_Pos) /*!< 0x00000010 */ +#define USB_OTG_HCINTMSK_NAKM USB_OTG_HCINTMSK_NAKM_Msk /*!< NAK response received interrupt mask */ +#define USB_OTG_HCINTMSK_ACKM_Pos (5U) +#define USB_OTG_HCINTMSK_ACKM_Msk (0x1UL << USB_OTG_HCINTMSK_ACKM_Pos) /*!< 0x00000020 */ +#define USB_OTG_HCINTMSK_ACKM USB_OTG_HCINTMSK_ACKM_Msk /*!< ACK response received/transmitted interrupt mask */ +#define USB_OTG_HCINTMSK_NYET_Pos (6U) +#define USB_OTG_HCINTMSK_NYET_Msk (0x1UL << USB_OTG_HCINTMSK_NYET_Pos) /*!< 0x00000040 */ +#define USB_OTG_HCINTMSK_NYET USB_OTG_HCINTMSK_NYET_Msk /*!< response received interrupt mask */ +#define USB_OTG_HCINTMSK_TXERRM_Pos (7U) +#define USB_OTG_HCINTMSK_TXERRM_Msk (0x1UL << USB_OTG_HCINTMSK_TXERRM_Pos) /*!< 0x00000080 */ +#define USB_OTG_HCINTMSK_TXERRM USB_OTG_HCINTMSK_TXERRM_Msk /*!< Transaction error mask */ +#define USB_OTG_HCINTMSK_BBERRM_Pos (8U) +#define USB_OTG_HCINTMSK_BBERRM_Msk (0x1UL << USB_OTG_HCINTMSK_BBERRM_Pos) /*!< 0x00000100 */ +#define USB_OTG_HCINTMSK_BBERRM USB_OTG_HCINTMSK_BBERRM_Msk /*!< Babble error mask */ +#define USB_OTG_HCINTMSK_FRMORM_Pos (9U) +#define USB_OTG_HCINTMSK_FRMORM_Msk (0x1UL << USB_OTG_HCINTMSK_FRMORM_Pos) /*!< 0x00000200 */ +#define USB_OTG_HCINTMSK_FRMORM USB_OTG_HCINTMSK_FRMORM_Msk /*!< Frame overrun mask */ +#define USB_OTG_HCINTMSK_DTERRM_Pos (10U) +#define USB_OTG_HCINTMSK_DTERRM_Msk (0x1UL << USB_OTG_HCINTMSK_DTERRM_Pos) /*!< 0x00000400 */ +#define USB_OTG_HCINTMSK_DTERRM USB_OTG_HCINTMSK_DTERRM_Msk /*!< Data toggle error mask */ + +/******************** Bit definition for USB_OTG_DIEPTSIZ register ********************/ + +#define USB_OTG_DIEPTSIZ_XFRSIZ_Pos (0U) +#define USB_OTG_DIEPTSIZ_XFRSIZ_Msk (0x7FFFFUL << USB_OTG_DIEPTSIZ_XFRSIZ_Pos) /*!< 0x0007FFFF */ +#define USB_OTG_DIEPTSIZ_XFRSIZ USB_OTG_DIEPTSIZ_XFRSIZ_Msk /*!< Transfer size */ +#define USB_OTG_DIEPTSIZ_PKTCNT_Pos (19U) +#define USB_OTG_DIEPTSIZ_PKTCNT_Msk (0x3FFUL << USB_OTG_DIEPTSIZ_PKTCNT_Pos) /*!< 0x1FF80000 */ +#define USB_OTG_DIEPTSIZ_PKTCNT USB_OTG_DIEPTSIZ_PKTCNT_Msk /*!< Packet count */ +#define USB_OTG_DIEPTSIZ_MULCNT_Pos (29U) +#define USB_OTG_DIEPTSIZ_MULCNT_Msk (0x3UL << USB_OTG_DIEPTSIZ_MULCNT_Pos) /*!< 0x60000000 */ +#define USB_OTG_DIEPTSIZ_MULCNT USB_OTG_DIEPTSIZ_MULCNT_Msk /*!< Packet count */ +/******************** Bit definition for USB_OTG_HCTSIZ register ********************/ +#define USB_OTG_HCTSIZ_XFRSIZ_Pos (0U) +#define USB_OTG_HCTSIZ_XFRSIZ_Msk (0x7FFFFUL << USB_OTG_HCTSIZ_XFRSIZ_Pos) /*!< 0x0007FFFF */ +#define USB_OTG_HCTSIZ_XFRSIZ USB_OTG_HCTSIZ_XFRSIZ_Msk /*!< Transfer size */ +#define USB_OTG_HCTSIZ_PKTCNT_Pos (19U) +#define USB_OTG_HCTSIZ_PKTCNT_Msk (0x3FFUL << USB_OTG_HCTSIZ_PKTCNT_Pos) /*!< 0x1FF80000 */ +#define USB_OTG_HCTSIZ_PKTCNT USB_OTG_HCTSIZ_PKTCNT_Msk /*!< Packet count */ +#define USB_OTG_HCTSIZ_DOPING_Pos (31U) +#define USB_OTG_HCTSIZ_DOPING_Msk (0x1UL << USB_OTG_HCTSIZ_DOPING_Pos) /*!< 0x80000000 */ +#define USB_OTG_HCTSIZ_DOPING USB_OTG_HCTSIZ_DOPING_Msk /*!< Do PING */ +#define USB_OTG_HCTSIZ_DPID_Pos (29U) +#define USB_OTG_HCTSIZ_DPID_Msk (0x3UL << USB_OTG_HCTSIZ_DPID_Pos) /*!< 0x60000000 */ +#define USB_OTG_HCTSIZ_DPID USB_OTG_HCTSIZ_DPID_Msk /*!< Data PID */ +#define USB_OTG_HCTSIZ_DPID_0 (0x1UL << USB_OTG_HCTSIZ_DPID_Pos) /*!< 0x20000000 */ +#define USB_OTG_HCTSIZ_DPID_1 (0x2UL << USB_OTG_HCTSIZ_DPID_Pos) /*!< 0x40000000 */ + +/******************** Bit definition for USB_OTG_DIEPDMA register ********************/ +#define USB_OTG_DIEPDMA_DMAADDR_Pos (0U) +#define USB_OTG_DIEPDMA_DMAADDR_Msk (0xFFFFFFFFUL << USB_OTG_DIEPDMA_DMAADDR_Pos) /*!< 0xFFFFFFFF */ +#define USB_OTG_DIEPDMA_DMAADDR USB_OTG_DIEPDMA_DMAADDR_Msk /*!< DMA address */ + +/******************** Bit definition for USB_OTG_HCDMA register ********************/ +#define USB_OTG_HCDMA_DMAADDR_Pos (0U) +#define USB_OTG_HCDMA_DMAADDR_Msk (0xFFFFFFFFUL << USB_OTG_HCDMA_DMAADDR_Pos) /*!< 0xFFFFFFFF */ +#define USB_OTG_HCDMA_DMAADDR USB_OTG_HCDMA_DMAADDR_Msk /*!< DMA address */ + +/******************** Bit definition for USB_OTG_DTXFSTS register ********************/ +#define USB_OTG_DTXFSTS_INEPTFSAV_Pos (0U) +#define USB_OTG_DTXFSTS_INEPTFSAV_Msk (0xFFFFUL << USB_OTG_DTXFSTS_INEPTFSAV_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_DTXFSTS_INEPTFSAV USB_OTG_DTXFSTS_INEPTFSAV_Msk /*!< IN endpoint TxFIFO space available */ + +/******************** Bit definition for USB_OTG_DIEPTXF register ********************/ +#define USB_OTG_DIEPTXF_INEPTXSA_Pos (0U) +#define USB_OTG_DIEPTXF_INEPTXSA_Msk (0xFFFFUL << USB_OTG_DIEPTXF_INEPTXSA_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_DIEPTXF_INEPTXSA USB_OTG_DIEPTXF_INEPTXSA_Msk /*!< IN endpoint FIFOx transmit RAM start address */ +#define USB_OTG_DIEPTXF_INEPTXFD_Pos (16U) +#define USB_OTG_DIEPTXF_INEPTXFD_Msk (0xFFFFUL << USB_OTG_DIEPTXF_INEPTXFD_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_DIEPTXF_INEPTXFD USB_OTG_DIEPTXF_INEPTXFD_Msk /*!< IN endpoint TxFIFO depth */ + +/******************** Bit definition for USB_OTG_DOEPCTL register ********************/ + +#define USB_OTG_DOEPCTL_MPSIZ_Pos (0U) +#define USB_OTG_DOEPCTL_MPSIZ_Msk (0x7FFUL << USB_OTG_DOEPCTL_MPSIZ_Pos) /*!< 0x000007FF */ +#define USB_OTG_DOEPCTL_MPSIZ USB_OTG_DOEPCTL_MPSIZ_Msk /*!< Maximum packet size */ /*! Date: Wed, 22 Sep 2021 15:19:02 -0700 Subject: [PATCH 02/51] Trying to setup the mmu --- hw/bsp/raspberrypi4/family.c | 24 +++++++------- hw/bsp/raspberrypi4/family.mk | 3 +- hw/mcu/broadcom/bcm2711/boot.s | 4 ++- hw/mcu/broadcom/bcm2711/link.ld | 16 ++++++--- hw/mcu/broadcom/bcm2711/mmu.c | 58 +++++++++++++++++++++++++++++++++ hw/mcu/broadcom/bcm2711/mmu.h | 44 +++++++++++++++++++++++++ 6 files changed, 132 insertions(+), 17 deletions(-) create mode 100644 hw/mcu/broadcom/bcm2711/mmu.c create mode 100644 hw/mcu/broadcom/bcm2711/mmu.h diff --git a/hw/bsp/raspberrypi4/family.c b/hw/bsp/raspberrypi4/family.c index b2665f42d..6266d5a35 100644 --- a/hw/bsp/raspberrypi4/family.c +++ b/hw/bsp/raspberrypi4/family.c @@ -28,6 +28,7 @@ #include "board.h" #include "io.h" +#include "mmu.h" //--------------------------------------------------------------------+ // Forward USB interrupt events to TinyUSB IRQ Handler @@ -55,6 +56,7 @@ void board_init(void) gpio_initOutputPinWithPullNone(18); gpio_setPinOutputBool(18, true); gpio_initOutputPinWithPullNone(42); + setup_mmu_flat_map(); // gpio_initOutputPinWithPullNone(23); // gpio_initOutputPinWithPullNone(24); // gpio_initOutputPinWithPullNone(25); @@ -83,17 +85,17 @@ void board_init(void) // gpio_setPinOutputBool(25, true); print(); // gpio_setPinOutputBool(25, false); - while (true) { - // for (size_t i = 0; i < 5; i++) { - for (size_t j = 0; j < 10000000000; j++) { - __asm__("nop"); - } - gpio_setPinOutputBool(42, true); - for (size_t j = 0; j < 10000000000; j++) { - __asm__("nop"); - } - gpio_setPinOutputBool(42, false); - } + // while (true) { + // // for (size_t i = 0; i < 5; i++) { + // for (size_t j = 0; j < 10000000000; j++) { + // __asm__("nop"); + // } + // gpio_setPinOutputBool(42, true); + // for (size_t j = 0; j < 10000000000; j++) { + // __asm__("nop"); + // } + // gpio_setPinOutputBool(42, false); + // } // while (1) uart_update(); } diff --git a/hw/bsp/raspberrypi4/family.mk b/hw/bsp/raspberrypi4/family.mk index 2d5c78d22..1547beee1 100644 --- a/hw/bsp/raspberrypi4/family.mk +++ b/hw/bsp/raspberrypi4/family.mk @@ -18,8 +18,9 @@ CFLAGS += \ SRC_C += \ src/portable/broadcom/synopsys/dcd_synopsys.c \ + $(MCU_DIR)/interrupts.c \ $(MCU_DIR)/io.c \ - $(MCU_DIR)/interrupts.c + $(MCU_DIR)/mmu.c CROSS_COMPILE = aarch64-none-elf- diff --git a/hw/mcu/broadcom/bcm2711/boot.s b/hw/mcu/broadcom/bcm2711/boot.s index 076b3a76a..dcc588924 100644 --- a/hw/mcu/broadcom/bcm2711/boot.s +++ b/hw/mcu/broadcom/bcm2711/boot.s @@ -19,7 +19,7 @@ _start: adr x0, vectors // load VBAR_EL1 with virtual // msr vbar_el3, x0 // vector table address msr vbar_el1, x0 // vector table address - // msr vbar_el2, x0 // vector table address + msr vbar_el2, x0 // vector table address isb // Clean the BSS section @@ -45,6 +45,8 @@ irq_entry mov x0, #\type mrs x1, esr_el1 mrs x2, elr_el1 +mrs x3, esr_el2 +mrs x4, elr_el2 b err_hang .endm diff --git a/hw/mcu/broadcom/bcm2711/link.ld b/hw/mcu/broadcom/bcm2711/link.ld index 0d5ebe2ab..43c4e722f 100644 --- a/hw/mcu/broadcom/bcm2711/link.ld +++ b/hw/mcu/broadcom/bcm2711/link.ld @@ -1,12 +1,20 @@ SECTIONS { . = 0x80000; /* Kernel load address for AArch64 */ - .text : { KEEP(*(.text.boot)) *(.text .text.* .gnu.linkonce.t*) } - .rodata : { *(.rodata .rodata.* .gnu.linkonce.r*) } + .text : { + KEEP(*(.text.boot)) + *(.text .text.* .gnu.linkonce.t*) + } + .rodata : { + . = ALIGN(4096); + *(.rodata .rodata.* .gnu.linkonce.r*) + } PROVIDE(_data = .); - .data : { *(.data .data.* .gnu.linkonce.d*) } + .data : { + . = ALIGN(4096); + *(.data .data.* .gnu.linkonce.d*) + } .bss (NOLOAD) : { - . = ALIGN(16); __bss_start = .; *(.bss .bss.*) *(COMMON) diff --git a/hw/mcu/broadcom/bcm2711/mmu.c b/hw/mcu/broadcom/bcm2711/mmu.c new file mode 100644 index 000000000..3c20436e6 --- /dev/null +++ b/hw/mcu/broadcom/bcm2711/mmu.c @@ -0,0 +1,58 @@ +#include +#include + + +#include "mmu.h" + +// Each entry is a gig. +volatile uint64_t level_1_table[32] __attribute__((aligned(4096))); + +// Third gig has peripherals +uint64_t level_2_0x0_c000_0000_to_0x1_0000_0000[512] __attribute__((aligned(4096))); + +void setup_mmu_flat_map(void) { + // Set the first gig to regular access. + level_1_table[0] = 0x0000000000000000 | + MM_DESCRIPTOR_MAIR_INDEX(MT_NORMAL_NC) | + MM_DESCRIPTOR_BLOCK | + MM_DESCRIPTOR_VALID; + level_1_table[2] = ((uint64_t) level_2_0x0_c000_0000_to_0x1_0000_0000) | + MM_DESCRIPTOR_TABLE | + MM_DESCRIPTOR_VALID; + // Set peripherals to register access. + for (uint64_t i = 480; i < 512; i++) { + level_2_0x0_c000_0000_to_0x1_0000_0000[i] = (0x00000000c0000000 + (i << 21)) | + MM_DESCRIPTOR_EXECUTE_NEVER | + MM_DESCRIPTOR_MAIR_INDEX(MT_DEVICE_nGnRnE) | + MM_DESCRIPTOR_BLOCK | + MM_DESCRIPTOR_VALID; + } + uint64_t mair = MAIR_VALUE; + uint64_t tcr = TCR_VALUE; + uint64_t ttbr0 = ((uint64_t) level_1_table) | MM_TTBR_CNP; + uint64_t sctlr = 0; + __asm__ volatile ( + // Set MAIR + "MSR MAIR_EL2, %[mair]\n\t" + // Set TTBR0 + "MSR TTBR0_EL2, %[ttbr0]\n\t" + // Set TCR + "MSR TCR_EL2, %[tcr]\n\t" + // The ISB forces these changes to be seen before the MMU is enabled. + "ISB\n\t" + // Read System Control Register configuration data + "MRS %[sctlr], SCTLR_EL2\n\t" + // Write System Control Register configuration data + "ORR %[sctlr], %[sctlr], #1\n\t" + // Set [M] bit and enable the MMU. + "MSR SCTLR_EL2, %[sctlr]\n\t" + // The ISB forces these changes to be seen by the next instruction + "ISB" + : /* No outputs. */ + : [mair] "r" (mair), + [tcr] "r" (tcr), + [ttbr0] "r" (ttbr0), + [sctlr] "r" (sctlr) + ); + while (true) {} +} diff --git a/hw/mcu/broadcom/bcm2711/mmu.h b/hw/mcu/broadcom/bcm2711/mmu.h new file mode 100644 index 000000000..9f0a7db49 --- /dev/null +++ b/hw/mcu/broadcom/bcm2711/mmu.h @@ -0,0 +1,44 @@ +#pragma once + + +// From: https://github.com/s-matyukevich/raspberry-pi-os/blob/master/docs/lesson06/rpi-os.md +/* + * Memory region attributes: + * + * n = AttrIndx[2:0] + * n MAIR + * DEVICE_nGnRnE 000 00000000 + * NORMAL_NC 001 01000100 + */ +#define MT_DEVICE_nGnRnE 0x0 +#define MT_NORMAL_NC 0x1 +#define MT_DEVICE_nGnRnE_FLAGS 0x00 +#define MT_NORMAL_NC_FLAGS 0x44 +#define MAIR_VALUE (MT_DEVICE_nGnRnE_FLAGS << (8 * MT_DEVICE_nGnRnE)) | (MT_NORMAL_NC_FLAGS << (8 * MT_NORMAL_NC)) + + +#define TCR_T0SZ (64 - 35) +#define TCR_PS (0x01 << 16) // 36-bit physical address +#define TCR_TG0_4K (0 << 14) +#define TCR_SH0_OUTER_SHAREABLE (0x2 << 12) +#define TCR_VALUE (TCR_T0SZ | TCR_PS | TCR_TG0_4K | TCR_SH0_OUTER_SHAREABLE) + +#define ENTRY_TYPE_TABLE_DESCRIPTOR 0x11 +#define ENTRY_TYPE_BLOCK_ENTRY 0x01 +#define ENTRY_TYPE_TABLE_ENTRY 0x11 +#define ENTRY_TYPE_INVALID 0x00 + +#define MM_DESCRIPTOR_VALID (0x1) + +#define MM_DESCRIPTOR_BLOCK (0x0 << 1) +#define MM_DESCRIPTOR_TABLE (0x1 << 1) + +// Block attributes +#define MM_DESCRIPTOR_EXECUTE_NEVER (0x1ull << 54) +#define MM_DESCRIPTOR_CONTIGUOUS (0x1ull << 52) + +#define MM_DESCRIPTOR_MAIR_INDEX(index) (index << 2) + +#define MM_TTBR_CNP (0x1) + +void setup_mmu_flat_map(void); From 0a6ca65e3f8a113c182c7df0a05889b123ba67a2 Mon Sep 17 00:00:00 2001 From: Scott Shawcroft Date: Fri, 24 Sep 2021 16:14:01 -0700 Subject: [PATCH 03/51] MMU works --- cortex-a.py | 157 ++++++++++++++++++ hw/mcu/broadcom/bcm2711/io.c | 2 + hw/mcu/broadcom/bcm2711/mmu.c | 12 +- hw/mcu/broadcom/bcm2711/mmu.h | 5 +- src/portable/broadcom/synopsys/dcd_synopsys.c | 8 +- 5 files changed, 177 insertions(+), 7 deletions(-) create mode 100644 cortex-a.py diff --git a/cortex-a.py b/cortex-a.py new file mode 100644 index 000000000..9de16bae9 --- /dev/null +++ b/cortex-a.py @@ -0,0 +1,157 @@ +class Armv8AException(gdb.Command): + def __init__ (self): + super (Armv8AException, self).__init__ ("armv8a-exception", gdb.COMMAND_USER) + + def print_data_abort(self, frame, iss): + isv = (iss >> 23) & 0x1 + sas = (iss >> 21) & 0x3 + sse = (iss >> 20) & 0x1 + srt = (iss >> 15) & 0x1f + sf = (iss >> 14) & 0x1 + ar = (iss >> 13) & 0x1 + vncr = (iss >> 12) & 0x1 + _set = (iss >> 10) & 0x3 + fnv = (iss >> 9) & 0x1 + ea = (iss >> 8) & 0x1 + cm = (iss >> 7) & 0x1 + s1ptw = (iss >> 6) & 0x1 + wnr = (iss >> 5) & 0x1 + dfsc = iss & 0x1f + if isv: + # print("isv valid", sas, sse, srt, sf, ar) + access_sizes = ("Byte", "Halfword", "Word", "Doubleword") + print("Access size:", access_sizes[sas]) + print("Sign extended:", "Yes" if sse else "No") + print("Register:", hex(srt), "64-bit" if sf else "32-bit") + print("Acquire/Release:", "Yes" if ar else "No") + if dfsc == 0b010000: + print("Not on translation table walk") + if not fnv: + value = int(frame.read_register("FAR_EL2")) + print("FAR", hex(value)) + elif dfsc == 0b000101: + print("translation fault level 1") + elif dfsc == 0b010001: + print("tag check fault") + elif dfsc == 0b100001: + print("alignment fault") + else: + print(bin(dfsc)) + print(vncr, _set, fnv, ea, cm, s1ptw, wnr, dfsc) + + def print_instruction_abort(self, frame, iss): + _set = (iss >> 10) & 0x3 + fnv = (iss >> 9) & 0x1 + ea = (iss >> 8) & 0x1 + s1ptw = (iss >> 6) & 0x1 + ifsc = iss & 0x1f + if ifsc == 0b010000: + print("Not on translation table walk") + if not fnv: + value = int(frame.read_register("FAR_EL2")) + print("FAR", hex(value)) + elif ifsc == 0b00101: + print("translation fault level 1") + elif ifsc == 0b01001: + print("access flag fault level 1") + # elif dfsc == 0b100001: + # print("alignment fault") + else: + print(bin(ifsc)) + + def invoke (self, arg, from_tty): + frame = gdb.selected_frame() + value = int(frame.read_register("ESR_EL2")) + if value == 0: + return None + iss2 = (value >> 32) & 0x1ff + ec = (value >> 26) & 0x3ff + il = (value >> 25) & 0x1 + iss = value & 0xffffff + if ec == 0b000000: + print("Unknown fault") + elif ec == 0b000001: + print("Trapped WF*") + elif ec == 0b000011: + print("Trapped MCR or MRC") + elif ec == 0b000100: + print("Trapped MCRR or MRRC") + elif ec == 0b000101: + print("Trapped MCR or MRC") + elif ec == 0b000110: + print("Trapped LDC or STC") + elif ec == 0b000111: + print("Trapped SIMD") + elif ec == 0b001000: + print("Trapped VMRS") + elif ec == 0b001001: + print("Trapped pointer authentication") + elif ec == 0b001010: + print("Trapped LD64B or ST64B*") + elif ec == 0b001100: + print("Trapped MRRC") + elif ec == 0b001101: + print("Branch target exception") + elif ec == 0b001110: + print("Illegal execution state") + elif ec == 0b010001: + print("SVC instruction") + elif ec == 0b010010: + print("HVC instruction") + elif ec == 0b010011: + print("SMC instruction") + elif ec == 0b010101: + print("SVC instruction") + elif ec == 0b010110: + print("HVC instruction") + elif ec == 0b010111: + print("SMC instruction") + elif ec == 0b011000: + print("Trapped MRS, MRS or system instruction") + elif ec == 0b011001: + print("Trapped SVE") + elif ec == 0b011010: + print("Trapped ERET") + elif ec == 0b011100: + print("Failed pointer authentication") + elif ec == 0b100000: + print("Instruction abort from lower level") + elif ec == 0b100001: + print("Instruction abort from same level") + self.print_instruction_abort(frame, iss) + elif ec == 0b100010: + print("PC alignment failure") + elif ec == 0b100100: + print("Data abort from lower level") + elif ec == 0b100101: + print("Data abort from same level") + self.print_data_abort(frame, iss) + elif ec == 0b100110: + print("SP alignment fault") + elif ec == 0b101000: + print("32-bit floating point exception") + elif ec == 0b101100: + print("64-bit floating point exception") + elif ec == 0b101111: + print("SError interrupt") + elif ec == 0b110000: + print("Breakpoint from lower level") + elif ec == 0b110001: + print("Breakpoint from same level") + elif ec == 0b110010: + print("Software step from lower level") + elif ec == 0b110011: + print("Software step from same level") + elif ec == 0b110100: + print ("Watch point from same level") + elif ec == 0b110101: + print("Watch point from lower level") + elif ec == 0b111000: + print("Breakpoint in aarch32 mode") + elif ec == 0b111010: + print("Vector catch in aarch32") + elif ec == 0b111100: + print("Brk instruction in aarch64") + print(hex(int(value)), iss2, bin(ec), il, iss) + +Armv8AException() diff --git a/hw/mcu/broadcom/bcm2711/io.c b/hw/mcu/broadcom/bcm2711/io.c index 213d6f2fb..8ccfdc692 100644 --- a/hw/mcu/broadcom/bcm2711/io.c +++ b/hw/mcu/broadcom/bcm2711/io.c @@ -3,6 +3,8 @@ // GPIO +// Pi 4 base address: 0xFE000000 +// Pi 3 base address: 0x3F000000 enum { PERIPHERAL_BASE = 0xFE000000, GPFSEL0 = PERIPHERAL_BASE + 0x200000, diff --git a/hw/mcu/broadcom/bcm2711/mmu.c b/hw/mcu/broadcom/bcm2711/mmu.c index 3c20436e6..e5ae236bd 100644 --- a/hw/mcu/broadcom/bcm2711/mmu.c +++ b/hw/mcu/broadcom/bcm2711/mmu.c @@ -5,7 +5,7 @@ #include "mmu.h" // Each entry is a gig. -volatile uint64_t level_1_table[32] __attribute__((aligned(4096))); +volatile uint64_t level_1_table[512] __attribute__((aligned(4096))); // Third gig has peripherals uint64_t level_2_0x0_c000_0000_to_0x1_0000_0000[512] __attribute__((aligned(4096))); @@ -14,9 +14,10 @@ void setup_mmu_flat_map(void) { // Set the first gig to regular access. level_1_table[0] = 0x0000000000000000 | MM_DESCRIPTOR_MAIR_INDEX(MT_NORMAL_NC) | + MM_DESCRIPTOR_ACCESS_FLAG | MM_DESCRIPTOR_BLOCK | MM_DESCRIPTOR_VALID; - level_1_table[2] = ((uint64_t) level_2_0x0_c000_0000_to_0x1_0000_0000) | + level_1_table[3] = ((uint64_t) level_2_0x0_c000_0000_to_0x1_0000_0000) | MM_DESCRIPTOR_TABLE | MM_DESCRIPTOR_VALID; // Set peripherals to register access. @@ -24,6 +25,7 @@ void setup_mmu_flat_map(void) { level_2_0x0_c000_0000_to_0x1_0000_0000[i] = (0x00000000c0000000 + (i << 21)) | MM_DESCRIPTOR_EXECUTE_NEVER | MM_DESCRIPTOR_MAIR_INDEX(MT_DEVICE_nGnRnE) | + MM_DESCRIPTOR_ACCESS_FLAG | MM_DESCRIPTOR_BLOCK | MM_DESCRIPTOR_VALID; } @@ -47,12 +49,14 @@ void setup_mmu_flat_map(void) { // Set [M] bit and enable the MMU. "MSR SCTLR_EL2, %[sctlr]\n\t" // The ISB forces these changes to be seen by the next instruction - "ISB" + "ISB\n\t" + // "AT S1EL2R %[ttbr0]" : /* No outputs. */ : [mair] "r" (mair), [tcr] "r" (tcr), [ttbr0] "r" (ttbr0), [sctlr] "r" (sctlr) ); - while (true) {} + //__asm__ ("brk #123"); + //while (true) {} } diff --git a/hw/mcu/broadcom/bcm2711/mmu.h b/hw/mcu/broadcom/bcm2711/mmu.h index 9f0a7db49..1fe081f34 100644 --- a/hw/mcu/broadcom/bcm2711/mmu.h +++ b/hw/mcu/broadcom/bcm2711/mmu.h @@ -13,11 +13,11 @@ #define MT_DEVICE_nGnRnE 0x0 #define MT_NORMAL_NC 0x1 #define MT_DEVICE_nGnRnE_FLAGS 0x00 -#define MT_NORMAL_NC_FLAGS 0x44 +#define MT_NORMAL_NC_FLAGS 0xff #define MAIR_VALUE (MT_DEVICE_nGnRnE_FLAGS << (8 * MT_DEVICE_nGnRnE)) | (MT_NORMAL_NC_FLAGS << (8 * MT_NORMAL_NC)) -#define TCR_T0SZ (64 - 35) +#define TCR_T0SZ (64 - 36) #define TCR_PS (0x01 << 16) // 36-bit physical address #define TCR_TG0_4K (0 << 14) #define TCR_SH0_OUTER_SHAREABLE (0x2 << 12) @@ -36,6 +36,7 @@ // Block attributes #define MM_DESCRIPTOR_EXECUTE_NEVER (0x1ull << 54) #define MM_DESCRIPTOR_CONTIGUOUS (0x1ull << 52) +#define MM_DESCRIPTOR_ACCESS_FLAG (0x1ull << 10) #define MM_DESCRIPTOR_MAIR_INDEX(index) (index << 2) diff --git a/src/portable/broadcom/synopsys/dcd_synopsys.c b/src/portable/broadcom/synopsys/dcd_synopsys.c index 5967565a5..aecae503c 100644 --- a/src/portable/broadcom/synopsys/dcd_synopsys.c +++ b/src/portable/broadcom/synopsys/dcd_synopsys.c @@ -114,7 +114,7 @@ // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ -#define RHPORT_REGS_BASE 0x7e980000 +#define RHPORT_REGS_BASE 0xfe980000 #define GLOBAL_BASE(_port) ((USB_OTG_GlobalTypeDef*) RHPORT_REGS_BASE) #define DEVICE_BASE(_port) (USB_OTG_DeviceTypeDef *) (RHPORT_REGS_BASE + USB_OTG_DEVICE_BASE) @@ -438,6 +438,7 @@ void dcd_init (uint8_t rhport) { // Programming model begins in the last section of the chapter on the USB // peripheral in each Reference Manual. + TU_LOG(2, " dcd_init"); USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); @@ -477,9 +478,14 @@ void dcd_init (uint8_t rhport) // Reset core after selecting PHY // Wait AHB IDLE, reset then wait until it is cleared while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U) {} + + TU_LOG(2, " resetting"); usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; + TU_LOG(2, " waiting"); while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST) {} + TU_LOG(2, " reset done"); + // Restart PHY clock *((volatile uint32_t *)(RHPORT_REGS_BASE + USB_OTG_PCGCCTL_BASE)) = 0; From 0932d502c78796762a7d4ec7ee709707ede83dc8 Mon Sep 17 00:00:00 2001 From: Scott Shawcroft Date: Thu, 30 Sep 2021 14:50:38 -0700 Subject: [PATCH 04/51] remove bcm files --- hw/mcu/broadcom/bcm2711/boot.s | 172 --------------------------- hw/mcu/broadcom/bcm2711/interrupts.c | 26 ---- hw/mcu/broadcom/bcm2711/interrupts.h | 8 -- hw/mcu/broadcom/bcm2711/io.c | 170 -------------------------- hw/mcu/broadcom/bcm2711/io.h | 13 -- hw/mcu/broadcom/bcm2711/link.ld | 28 ----- hw/mcu/broadcom/bcm2711/mmu.c | 62 ---------- hw/mcu/broadcom/bcm2711/mmu.h | 45 ------- 8 files changed, 524 deletions(-) delete mode 100644 hw/mcu/broadcom/bcm2711/boot.s delete mode 100644 hw/mcu/broadcom/bcm2711/interrupts.c delete mode 100644 hw/mcu/broadcom/bcm2711/interrupts.h delete mode 100644 hw/mcu/broadcom/bcm2711/io.c delete mode 100644 hw/mcu/broadcom/bcm2711/io.h delete mode 100644 hw/mcu/broadcom/bcm2711/link.ld delete mode 100644 hw/mcu/broadcom/bcm2711/mmu.c delete mode 100644 hw/mcu/broadcom/bcm2711/mmu.h diff --git a/hw/mcu/broadcom/bcm2711/boot.s b/hw/mcu/broadcom/bcm2711/boot.s deleted file mode 100644 index dcc588924..000000000 --- a/hw/mcu/broadcom/bcm2711/boot.s +++ /dev/null @@ -1,172 +0,0 @@ -.section ".text.boot" // Make sure the linker puts this at the start of the kernel image - -.global _start // Execution starts here - -_start: - // Check processor ID is zero (executing on main core), else hang - mrs x1, mpidr_el1 - and x1, x1, #3 - cbz x1, 2f - // We're not on the main core, so hang in an infinite wait loop -1: wfe - b 1b -2: // We're on the main core! - - // Set stack to start below our code - ldr x1, =_start - mov sp, x1 - - adr x0, vectors // load VBAR_EL1 with virtual - // msr vbar_el3, x0 // vector table address - msr vbar_el1, x0 // vector table address - msr vbar_el2, x0 // vector table address - isb - - // Clean the BSS section - ldr x1, =__bss_start // Start address - ldr w2, =__bss_size // Size of the section -3: cbz w2, 4f // Quit loop if zero - str xzr, [x1], #8 - sub w2, w2, #1 - cbnz w2, 3b // Loop if non-zero - - // Jump to our main() routine in C (make sure it doesn't return) -4: bl main - // In case it does return, halt the master core too - b 1b - -.macro ventry label -.align 7 -b \label -.endm - -.macro handle_invalid_entry type -irq_entry -mov x0, #\type -mrs x1, esr_el1 -mrs x2, elr_el1 -mrs x3, esr_el2 -mrs x4, elr_el2 -b err_hang -.endm - -.macro irq_entry -sub sp, sp, #272 -stp x0, x1, [sp, #16 * 0] -stp x2, x3, [sp, #16 * 1] -stp x4, x5, [sp, #16 * 2] -stp x6, x7, [sp, #16 * 3] -stp x8, x9, [sp, #16 * 4] -stp x10, x11, [sp, #16 * 5] -stp x12, x13, [sp, #16 * 6] -stp x14, x15, [sp, #16 * 7] -stp x16, x17, [sp, #16 * 8] -stp x18, x19, [sp, #16 * 9] -stp x20, x21, [sp, #16 * 10] -stp x22, x23, [sp, #16 * 11] -stp x24, x25, [sp, #16 * 12] -stp x26, x27, [sp, #16 * 13] -stp x28, x29, [sp, #16 * 14] -str x30, [sp, #16 * 15] -.endm - -.macro irq_exit -ldp x0, x1, [sp, #16 * 0] -ldp x2, x3, [sp, #16 * 1] -ldp x4, x5, [sp, #16 * 2] -ldp x6, x7, [sp, #16 * 3] -ldp x8, x9, [sp, #16 * 4] -ldp x10, x11, [sp, #16 * 5] -ldp x12, x13, [sp, #16 * 6] -ldp x14, x15, [sp, #16 * 7] -ldp x16, x17, [sp, #16 * 8] -ldp x18, x19, [sp, #16 * 9] -ldp x20, x21, [sp, #16 * 10] -ldp x22, x23, [sp, #16 * 11] -ldp x24, x25, [sp, #16 * 12] -ldp x26, x27, [sp, #16 * 13] -ldp x28, x29, [sp, #16 * 14] -ldr x30, [sp, #16 * 15] -add sp, sp, #272 -eret -.endm - - -/* - * Exception vectors. - */ -.align 11 -.globl vectors -vectors: - ventry sync_invalid_el1t // Synchronous EL1t - ventry irq_invalid_el1t // IRQ EL1t - ventry fiq_invalid_el1t // FIQ EL1t - ventry error_invalid_el1t // Error EL1t - - ventry sync_invalid_el1h // Synchronous EL1h - ventry el1_irq // IRQ EL1h - ventry fiq_invalid_el1h // FIQ EL1h - ventry error_invalid_el1h // Error EL1h - - ventry sync_invalid_el0_64 // Synchronous 64-bit EL0 - ventry irq_invalid_el0_64 // IRQ 64-bit EL0 - ventry fiq_invalid_el0_64 // FIQ 64-bit EL0 - ventry error_invalid_el0_64 // Error 64-bit EL0 - - ventry sync_invalid_el0_32 // Synchronous 32-bit EL0 - ventry irq_invalid_el0_32 // IRQ 32-bit EL0 - ventry fiq_invalid_el0_32 // FIQ 32-bit EL0 - ventry error_invalid_el0_32 // Error 32-bit EL0 - -sync_invalid_el1t: - handle_invalid_entry 0 - -irq_invalid_el1t: - handle_invalid_entry 1 - -fiq_invalid_el1t: - handle_invalid_entry 2 - -error_invalid_el1t: - handle_invalid_entry 3 - -sync_invalid_el1h: - handle_invalid_entry 4 - -fiq_invalid_el1h: - handle_invalid_entry 5 - -error_invalid_el1h: - handle_invalid_entry 6 - -sync_invalid_el0_64: - handle_invalid_entry 7 - -irq_invalid_el0_64: - handle_invalid_entry 8 - -fiq_invalid_el0_64: - handle_invalid_entry 9 - -error_invalid_el0_64: - handle_invalid_entry 10 - -sync_invalid_el0_32: - handle_invalid_entry 11 - -irq_invalid_el0_32: - handle_invalid_entry 12 - -fiq_invalid_el0_32: - handle_invalid_entry 13 - -error_invalid_el0_32: - handle_invalid_entry 14 - -el1_irq: - irq_entry - bl handle_irq - irq_exit - -.globl err_hang -err_hang: b err_hang diff --git a/hw/mcu/broadcom/bcm2711/interrupts.c b/hw/mcu/broadcom/bcm2711/interrupts.c deleted file mode 100644 index cb5607526..000000000 --- a/hw/mcu/broadcom/bcm2711/interrupts.c +++ /dev/null @@ -1,26 +0,0 @@ -#include -#include - -void disable_async_interrupts(void) { - -} - -void enable_async_interrupts(void) { - -} - -void Default_Handler(void) { - while (true) {} -} - -__attribute__((weak)) void handle_irq(void) { - unsigned int irq = *((volatile uint32_t*) 0x3F00B204); - switch (irq) { - // case (SYSTEM_TIMER_IRQ_1): - // handle_timer_irq(); - // break; - default: - // printf("Unknown pending irq: %x\r\n", irq); - Default_Handler(); - } -} \ No newline at end of file diff --git a/hw/mcu/broadcom/bcm2711/interrupts.h b/hw/mcu/broadcom/bcm2711/interrupts.h deleted file mode 100644 index 5f36d6daa..000000000 --- a/hw/mcu/broadcom/bcm2711/interrupts.h +++ /dev/null @@ -1,8 +0,0 @@ -#pragma once - -void disable_async_interrupts(void); -void enable_async_interrupts(void); - -#define GIC_BASE 0x4c0040000 -#define NUM_CPUS 4 -#define NUM_SPIS 192 diff --git a/hw/mcu/broadcom/bcm2711/io.c b/hw/mcu/broadcom/bcm2711/io.c deleted file mode 100644 index 8ccfdc692..000000000 --- a/hw/mcu/broadcom/bcm2711/io.c +++ /dev/null @@ -1,170 +0,0 @@ -// From: https://github.com/isometimes/rpi4-osdev/blob/master/part4-miniuart/io.c -// CC-0 License - -// GPIO - -// Pi 4 base address: 0xFE000000 -// Pi 3 base address: 0x3F000000 -enum { - PERIPHERAL_BASE = 0xFE000000, - GPFSEL0 = PERIPHERAL_BASE + 0x200000, - GPSET0 = PERIPHERAL_BASE + 0x20001C, - GPCLR0 = PERIPHERAL_BASE + 0x200028, - GPPUPPDN0 = PERIPHERAL_BASE + 0x2000E4 -}; - -enum { - GPIO_MAX_PIN = 53, - GPIO_FUNCTION_OUT = 1, - GPIO_FUNCTION_ALT5 = 2, - GPIO_FUNCTION_ALT3 = 7 -}; - -enum { - Pull_None = 0, - Pull_Down = 1, // Are down and up the right way around? - Pull_Up = 2 -}; - -void mmio_write(long reg, unsigned int val) { *(volatile unsigned int *)reg = val; } -unsigned int mmio_read(long reg) { return *(volatile unsigned int *)reg; } - -unsigned int gpio_call(unsigned int pin_number, unsigned int value, unsigned int base, unsigned int field_size, unsigned int field_max) { - unsigned int field_mask = (1 << field_size) - 1; - - if (pin_number > field_max) return 0; - if (value > field_mask) return 0; - - unsigned int num_fields = 32 / field_size; - unsigned int reg = base + ((pin_number / num_fields) * 4); - unsigned int shift = (pin_number % num_fields) * field_size; - - unsigned int curval = mmio_read(reg); - curval &= ~(field_mask << shift); - curval |= value << shift; - mmio_write(reg, curval); - - return 1; -} - -unsigned int gpio_set (unsigned int pin_number, unsigned int value) { return gpio_call(pin_number, value, GPSET0, 1, GPIO_MAX_PIN); } -unsigned int gpio_clear (unsigned int pin_number, unsigned int value) { return gpio_call(pin_number, value, GPCLR0, 1, GPIO_MAX_PIN); } -unsigned int gpio_pull (unsigned int pin_number, unsigned int value) { return gpio_call(pin_number, value, GPPUPPDN0, 2, GPIO_MAX_PIN); } -unsigned int gpio_function(unsigned int pin_number, unsigned int value) { return gpio_call(pin_number, value, GPFSEL0, 3, GPIO_MAX_PIN); } - -void gpio_useAsAlt3(unsigned int pin_number) { - gpio_pull(pin_number, Pull_None); - gpio_function(pin_number, GPIO_FUNCTION_ALT3); -} - -void gpio_useAsAlt5(unsigned int pin_number) { - gpio_pull(pin_number, Pull_None); - gpio_function(pin_number, GPIO_FUNCTION_ALT5); -} - -void gpio_initOutputPinWithPullNone(unsigned int pin_number) { - gpio_pull(pin_number, Pull_None); - gpio_function(pin_number, GPIO_FUNCTION_OUT); -} - -void gpio_setPinOutputBool(unsigned int pin_number, unsigned int onOrOff) { - if (onOrOff) { - gpio_set(pin_number, 1); - } else { - gpio_clear(pin_number, 1); - } -} - -// UART - -enum { - AUX_BASE = PERIPHERAL_BASE + 0x215000, - AUX_IRQ = AUX_BASE, - AUX_ENABLES = AUX_BASE + 4, - AUX_MU_IO_REG = AUX_BASE + 64, - AUX_MU_IER_REG = AUX_BASE + 68, - AUX_MU_IIR_REG = AUX_BASE + 72, - AUX_MU_LCR_REG = AUX_BASE + 76, - AUX_MU_MCR_REG = AUX_BASE + 80, - AUX_MU_LSR_REG = AUX_BASE + 84, - AUX_MU_MSR_REG = AUX_BASE + 88, - AUX_MU_SCRATCH = AUX_BASE + 92, - AUX_MU_CNTL_REG = AUX_BASE + 96, - AUX_MU_STAT_REG = AUX_BASE + 100, - AUX_MU_BAUD_REG = AUX_BASE + 104, - AUX_UART_CLOCK = 500000000, - UART_MAX_QUEUE = 16 * 1024 -}; - -#define AUX_MU_BAUD(baud) ((AUX_UART_CLOCK/(baud*8))-1) - -unsigned char uart_output_queue[UART_MAX_QUEUE]; -unsigned int uart_output_queue_write = 0; -unsigned int uart_output_queue_read = 0; - -void uart_init(void) { - mmio_write(AUX_ENABLES, 1); //enable UART1 - mmio_write(AUX_MU_IER_REG, 0); - mmio_write(AUX_MU_CNTL_REG, 0); - mmio_write(AUX_MU_LCR_REG, 3); //8 bits - mmio_write(AUX_MU_MCR_REG, 0); - mmio_write(AUX_MU_IER_REG, 0); - mmio_write(AUX_MU_IIR_REG, 0xC6); //disable interrupts - mmio_write(AUX_MU_BAUD_REG, AUX_MU_BAUD(115200)); - gpio_useAsAlt5(14); - gpio_useAsAlt5(15); - mmio_write(AUX_MU_CNTL_REG, 3); //enable RX/TX -} - -unsigned int uart_isOutputQueueEmpty(void) { - return uart_output_queue_read == uart_output_queue_write; -} - -unsigned int uart_isReadByteReady(void) { return mmio_read(AUX_MU_LSR_REG) & 0x01; } -unsigned int uart_isWriteByteReady(void) { return mmio_read(AUX_MU_LSR_REG) & 0x20; } - -unsigned char uart_readByte(void) { - while (!uart_isReadByteReady()); - return (unsigned char)mmio_read(AUX_MU_IO_REG); -} - -void uart_writeByteBlockingActual(unsigned char ch) { - while (!uart_isWriteByteReady()); - mmio_write(AUX_MU_IO_REG, (unsigned int)ch); -} - -void uart_loadOutputFifo(void) { - while (!uart_isOutputQueueEmpty() && uart_isWriteByteReady()) { - uart_writeByteBlockingActual(uart_output_queue[uart_output_queue_read]); - uart_output_queue_read = (uart_output_queue_read + 1) & (UART_MAX_QUEUE - 1); // Don't overrun - } -} - -void uart_writeByteBlocking(unsigned char ch) { - unsigned int next = (uart_output_queue_write + 1) & (UART_MAX_QUEUE - 1); // Don't overrun - - while (next == uart_output_queue_read) uart_loadOutputFifo(); - - uart_output_queue[uart_output_queue_write] = ch; - uart_output_queue_write = next; -} - -void uart_writeText(const char *buffer) { - while (*buffer) { - if (*buffer == '\n') uart_writeByteBlocking('\r'); - uart_writeByteBlocking(*buffer++); - } -} - -void uart_drainOutputQueue(void) { - while (!uart_isOutputQueueEmpty()) uart_loadOutputFifo(); -} - -void uart_update(void) { - uart_loadOutputFifo(); - - if (uart_isReadByteReady()) { - unsigned char ch = uart_readByte(); - if (ch == '\r') uart_writeText("\n"); else uart_writeByteBlocking(ch); - } -} diff --git a/hw/mcu/broadcom/bcm2711/io.h b/hw/mcu/broadcom/bcm2711/io.h deleted file mode 100644 index 9f70ce504..000000000 --- a/hw/mcu/broadcom/bcm2711/io.h +++ /dev/null @@ -1,13 +0,0 @@ -// From: https://github.com/isometimes/rpi4-osdev/blob/master/part4-miniuart/io.h -// CC-0 License - -void uart_init(void); -void uart_writeText(const char *buffer); -void uart_loadOutputFifo(void); -unsigned char uart_readByte(void); -unsigned int uart_isReadByteReady(void); -void uart_writeByteBlocking(unsigned char ch); -void uart_update(void); -void gpio_setPinOutputBool(unsigned int pin_number, unsigned int onOrOff); -void uart_writeByteBlockingActual(unsigned char ch); -void gpio_initOutputPinWithPullNone(unsigned int pin_number); diff --git a/hw/mcu/broadcom/bcm2711/link.ld b/hw/mcu/broadcom/bcm2711/link.ld deleted file mode 100644 index 43c4e722f..000000000 --- a/hw/mcu/broadcom/bcm2711/link.ld +++ /dev/null @@ -1,28 +0,0 @@ -SECTIONS -{ - . = 0x80000; /* Kernel load address for AArch64 */ - .text : { - KEEP(*(.text.boot)) - *(.text .text.* .gnu.linkonce.t*) - } - .rodata : { - . = ALIGN(4096); - *(.rodata .rodata.* .gnu.linkonce.r*) - } - PROVIDE(_data = .); - .data : { - . = ALIGN(4096); - *(.data .data.* .gnu.linkonce.d*) - } - .bss (NOLOAD) : { - __bss_start = .; - *(.bss .bss.*) - *(COMMON) - __bss_end = .; - } - _end = .; - end = .; - - /DISCARD/ : { *(.comment) *(.gnu*) *(.note*) *(.eh_frame*) } -} -__bss_size = (__bss_end - __bss_start)>>3; diff --git a/hw/mcu/broadcom/bcm2711/mmu.c b/hw/mcu/broadcom/bcm2711/mmu.c deleted file mode 100644 index e5ae236bd..000000000 --- a/hw/mcu/broadcom/bcm2711/mmu.c +++ /dev/null @@ -1,62 +0,0 @@ -#include -#include - - -#include "mmu.h" - -// Each entry is a gig. -volatile uint64_t level_1_table[512] __attribute__((aligned(4096))); - -// Third gig has peripherals -uint64_t level_2_0x0_c000_0000_to_0x1_0000_0000[512] __attribute__((aligned(4096))); - -void setup_mmu_flat_map(void) { - // Set the first gig to regular access. - level_1_table[0] = 0x0000000000000000 | - MM_DESCRIPTOR_MAIR_INDEX(MT_NORMAL_NC) | - MM_DESCRIPTOR_ACCESS_FLAG | - MM_DESCRIPTOR_BLOCK | - MM_DESCRIPTOR_VALID; - level_1_table[3] = ((uint64_t) level_2_0x0_c000_0000_to_0x1_0000_0000) | - MM_DESCRIPTOR_TABLE | - MM_DESCRIPTOR_VALID; - // Set peripherals to register access. - for (uint64_t i = 480; i < 512; i++) { - level_2_0x0_c000_0000_to_0x1_0000_0000[i] = (0x00000000c0000000 + (i << 21)) | - MM_DESCRIPTOR_EXECUTE_NEVER | - MM_DESCRIPTOR_MAIR_INDEX(MT_DEVICE_nGnRnE) | - MM_DESCRIPTOR_ACCESS_FLAG | - MM_DESCRIPTOR_BLOCK | - MM_DESCRIPTOR_VALID; - } - uint64_t mair = MAIR_VALUE; - uint64_t tcr = TCR_VALUE; - uint64_t ttbr0 = ((uint64_t) level_1_table) | MM_TTBR_CNP; - uint64_t sctlr = 0; - __asm__ volatile ( - // Set MAIR - "MSR MAIR_EL2, %[mair]\n\t" - // Set TTBR0 - "MSR TTBR0_EL2, %[ttbr0]\n\t" - // Set TCR - "MSR TCR_EL2, %[tcr]\n\t" - // The ISB forces these changes to be seen before the MMU is enabled. - "ISB\n\t" - // Read System Control Register configuration data - "MRS %[sctlr], SCTLR_EL2\n\t" - // Write System Control Register configuration data - "ORR %[sctlr], %[sctlr], #1\n\t" - // Set [M] bit and enable the MMU. - "MSR SCTLR_EL2, %[sctlr]\n\t" - // The ISB forces these changes to be seen by the next instruction - "ISB\n\t" - // "AT S1EL2R %[ttbr0]" - : /* No outputs. */ - : [mair] "r" (mair), - [tcr] "r" (tcr), - [ttbr0] "r" (ttbr0), - [sctlr] "r" (sctlr) - ); - //__asm__ ("brk #123"); - //while (true) {} -} diff --git a/hw/mcu/broadcom/bcm2711/mmu.h b/hw/mcu/broadcom/bcm2711/mmu.h deleted file mode 100644 index 1fe081f34..000000000 --- a/hw/mcu/broadcom/bcm2711/mmu.h +++ /dev/null @@ -1,45 +0,0 @@ -#pragma once - - -// From: https://github.com/s-matyukevich/raspberry-pi-os/blob/master/docs/lesson06/rpi-os.md -/* - * Memory region attributes: - * - * n = AttrIndx[2:0] - * n MAIR - * DEVICE_nGnRnE 000 00000000 - * NORMAL_NC 001 01000100 - */ -#define MT_DEVICE_nGnRnE 0x0 -#define MT_NORMAL_NC 0x1 -#define MT_DEVICE_nGnRnE_FLAGS 0x00 -#define MT_NORMAL_NC_FLAGS 0xff -#define MAIR_VALUE (MT_DEVICE_nGnRnE_FLAGS << (8 * MT_DEVICE_nGnRnE)) | (MT_NORMAL_NC_FLAGS << (8 * MT_NORMAL_NC)) - - -#define TCR_T0SZ (64 - 36) -#define TCR_PS (0x01 << 16) // 36-bit physical address -#define TCR_TG0_4K (0 << 14) -#define TCR_SH0_OUTER_SHAREABLE (0x2 << 12) -#define TCR_VALUE (TCR_T0SZ | TCR_PS | TCR_TG0_4K | TCR_SH0_OUTER_SHAREABLE) - -#define ENTRY_TYPE_TABLE_DESCRIPTOR 0x11 -#define ENTRY_TYPE_BLOCK_ENTRY 0x01 -#define ENTRY_TYPE_TABLE_ENTRY 0x11 -#define ENTRY_TYPE_INVALID 0x00 - -#define MM_DESCRIPTOR_VALID (0x1) - -#define MM_DESCRIPTOR_BLOCK (0x0 << 1) -#define MM_DESCRIPTOR_TABLE (0x1 << 1) - -// Block attributes -#define MM_DESCRIPTOR_EXECUTE_NEVER (0x1ull << 54) -#define MM_DESCRIPTOR_CONTIGUOUS (0x1ull << 52) -#define MM_DESCRIPTOR_ACCESS_FLAG (0x1ull << 10) - -#define MM_DESCRIPTOR_MAIR_INDEX(index) (index << 2) - -#define MM_TTBR_CNP (0x1) - -void setup_mmu_flat_map(void); From 98ab8117d68f05bb36b9aeb857273e896199bc6a Mon Sep 17 00:00:00 2001 From: Scott Shawcroft Date: Tue, 5 Oct 2021 18:20:44 -0700 Subject: [PATCH 05/51] USB seems to init ok --- .gitmodules | 4 ++++ hw/bsp/raspberrypi4/family.c | 18 ++++++++++++------ hw/bsp/raspberrypi4/family.mk | 16 +++++++++------- hw/mcu/broadcom | 1 + 4 files changed, 26 insertions(+), 13 deletions(-) create mode 160000 hw/mcu/broadcom diff --git a/.gitmodules b/.gitmodules index 4c86fd55c..95f35d270 100644 --- a/.gitmodules +++ b/.gitmodules @@ -127,3 +127,7 @@ [submodule "hw/mcu/gd/nuclei-sdk"] path = hw/mcu/gd/nuclei-sdk url = https://github.com/Nuclei-Software/nuclei-sdk.git +[submodule "hw/mcu/broadcom"] + path = hw/mcu/broadcom + url = git@github.com:adafruit/broadcom-peripherals.git + branch = main-build diff --git a/hw/bsp/raspberrypi4/family.c b/hw/bsp/raspberrypi4/family.c index 6266d5a35..fe7e429d6 100644 --- a/hw/bsp/raspberrypi4/family.c +++ b/hw/bsp/raspberrypi4/family.c @@ -27,8 +27,9 @@ #include "bsp/board.h" #include "board.h" -#include "io.h" -#include "mmu.h" +#include "broadcom/io.h" +#include "broadcom/mmu.h" +#include "broadcom/vcmailbox.h" //--------------------------------------------------------------------+ // Forward USB interrupt events to TinyUSB IRQ Handler @@ -46,9 +47,8 @@ void OTG_FS_IRQHandler(void) // Board porting API //--------------------------------------------------------------------+ -void print(void) { - const char* greeting2 = "hello from cm100\r\n"; - board_uart_write(greeting2, strlen(greeting2)); +void print(const char* str) { + board_uart_write(str, strlen(str)); } void board_init(void) @@ -83,7 +83,7 @@ void board_init(void) board_uart_write(greeting, strlen(greeting)); // gpio_setPinOutputBool(24, false); // gpio_setPinOutputBool(25, true); - print(); + // print(); // gpio_setPinOutputBool(25, false); // while (true) { // // for (size_t i = 0; i < 5; i++) { @@ -97,6 +97,12 @@ void board_init(void) // gpio_setPinOutputBool(42, false); // } // while (1) uart_update(); + + // Turn on USB peripheral. + print("Turning on USB power\r\n"); + + vcmailbox_set_power_state(VCMAILBOX_DEVICE_USB_HCD, true); + print("USB power on\r\n"); } void board_led_write(bool state) diff --git a/hw/bsp/raspberrypi4/family.mk b/hw/bsp/raspberrypi4/family.mk index 1547beee1..b36a83b48 100644 --- a/hw/bsp/raspberrypi4/family.mk +++ b/hw/bsp/raspberrypi4/family.mk @@ -2,7 +2,7 @@ UF2_FAMILY_ID = 0x57755a57 include $(TOP)/$(BOARD_PATH)/board.mk -MCU_DIR = hw/mcu/broadcom/bcm2711 +MCU_DIR = hw/mcu/broadcom CC = clang @@ -18,21 +18,23 @@ CFLAGS += \ SRC_C += \ src/portable/broadcom/synopsys/dcd_synopsys.c \ - $(MCU_DIR)/interrupts.c \ - $(MCU_DIR)/io.c \ - $(MCU_DIR)/mmu.c + $(MCU_DIR)/broadcom/interrupts.c \ + $(MCU_DIR)/broadcom/io.c \ + $(MCU_DIR)/broadcom/mmu.c \ + $(MCU_DIR)/broadcom/vcmailbox.c CROSS_COMPILE = aarch64-none-elf- SKIP_NANOLIB = 1 -LD_FILE = $(MCU_DIR)/link.ld +LD_FILE = $(MCU_DIR)/broadcom/link.ld INC += \ $(TOP)/$(BOARD_PATH) \ - $(TOP)/$(MCU_DIR) + $(TOP)/$(MCU_DIR) \ + $(TOP)/lib/CMSIS_5/CMSIS/Core_A/Include -SRC_S += $(MCU_DIR)/boot.S +SRC_S += $(MCU_DIR)/broadcom/boot.S $(BUILD)/kernel8.img: $(BUILD)/$(PROJECT).elf $(OBJCOPY) -O binary $^ $@ diff --git a/hw/mcu/broadcom b/hw/mcu/broadcom new file mode 160000 index 000000000..c24e8f689 --- /dev/null +++ b/hw/mcu/broadcom @@ -0,0 +1 @@ +Subproject commit c24e8f6898d7cf8e2884eb70dbabd97480526450 From 4ab14867daf1d9df414f1175cbaac70c0d799257 Mon Sep 17 00:00:00 2001 From: Scott Shawcroft Date: Tue, 12 Oct 2021 16:47:53 -0700 Subject: [PATCH 06/51] Trying to get USB init --- hw/bsp/raspberrypi4/family.c | 27 +++++- hw/bsp/raspberrypi4/family.mk | 1 + hw/mcu/broadcom | 2 +- src/portable/broadcom/synopsys/dcd_synopsys.c | 88 ++++++++++--------- 4 files changed, 71 insertions(+), 47 deletions(-) diff --git a/hw/bsp/raspberrypi4/family.c b/hw/bsp/raspberrypi4/family.c index fe7e429d6..ffeb05f9f 100644 --- a/hw/bsp/raspberrypi4/family.c +++ b/hw/bsp/raspberrypi4/family.c @@ -27,14 +27,17 @@ #include "bsp/board.h" #include "board.h" +#include "broadcom/interrupts.h" #include "broadcom/io.h" #include "broadcom/mmu.h" #include "broadcom/vcmailbox.h" +uint32_t SystemCoreClock = 700 * 1000 * 1000; + //--------------------------------------------------------------------+ // Forward USB interrupt events to TinyUSB IRQ Handler //--------------------------------------------------------------------+ -void OTG_FS_IRQHandler(void) +void USB_IRQHandler(void) { tud_int_handler(0); } @@ -54,6 +57,9 @@ void print(const char* str) { void board_init(void) { gpio_initOutputPinWithPullNone(18); + gpio_initOutputPinWithPullNone(19); + gpio_initOutputPinWithPullNone(20); + gpio_initOutputPinWithPullNone(21); gpio_setPinOutputBool(18, true); gpio_initOutputPinWithPullNone(42); setup_mmu_flat_map(); @@ -72,11 +78,17 @@ void board_init(void) } gpio_setPinOutputBool(42, true); gpio_setPinOutputBool(18, true); + gpio_setPinOutputBool(19, true); + gpio_setPinOutputBool(20, true); + gpio_setPinOutputBool(21, true); for (size_t j = 0; j < 1000000; j++) { __asm__("nop"); } gpio_setPinOutputBool(42, false); gpio_setPinOutputBool(18, false); + gpio_setPinOutputBool(19, false); + gpio_setPinOutputBool(20, false); + gpio_setPinOutputBool(21, false); } // uart_writeText("hello from io\n"); // gpio_setPinOutputBool(24, true); @@ -98,11 +110,18 @@ void board_init(void) // } // while (1) uart_update(); + printf("hello %d\r\n", 21); + // Turn on USB peripheral. print("Turning on USB power\r\n"); vcmailbox_set_power_state(VCMAILBOX_DEVICE_USB_HCD, true); print("USB power on\r\n"); + + BP_SetPriority(USB_IRQn, 0x00); + BP_ClearPendingIRQ(USB_IRQn); + BP_EnableIRQ(USB_IRQn); + BP_EnableIRQs(); } void board_led_write(bool state) @@ -125,10 +144,12 @@ int board_uart_write(void const * buf, int len) { for (int i = 0; i < len; i++) { const char* cbuf = buf; + while (!UART1->STAT_b.TX_READY) {} if (cbuf[i] == '\n') { - uart_writeByteBlockingActual('\r'); + UART1->IO = '\r'; + while (!UART1->STAT_b.TX_READY) {} } - uart_writeByteBlockingActual(cbuf[i]); + UART1->IO = cbuf[i]; } return len; } diff --git a/hw/bsp/raspberrypi4/family.mk b/hw/bsp/raspberrypi4/family.mk index b36a83b48..0424b2154 100644 --- a/hw/bsp/raspberrypi4/family.mk +++ b/hw/bsp/raspberrypi4/family.mk @@ -18,6 +18,7 @@ CFLAGS += \ SRC_C += \ src/portable/broadcom/synopsys/dcd_synopsys.c \ + $(MCU_DIR)/broadcom/gen/interrupt_handlers.c \ $(MCU_DIR)/broadcom/interrupts.c \ $(MCU_DIR)/broadcom/io.c \ $(MCU_DIR)/broadcom/mmu.c \ diff --git a/hw/mcu/broadcom b/hw/mcu/broadcom index c24e8f689..e5343acda 160000 --- a/hw/mcu/broadcom +++ b/hw/mcu/broadcom @@ -1 +1 @@ -Subproject commit c24e8f6898d7cf8e2884eb70dbabd97480526450 +Subproject commit e5343acdad77b8cf4a8d09b732a11ecef17d148a diff --git a/src/portable/broadcom/synopsys/dcd_synopsys.c b/src/portable/broadcom/synopsys/dcd_synopsys.c index aecae503c..ff4ab9fb6 100644 --- a/src/portable/broadcom/synopsys/dcd_synopsys.c +++ b/src/portable/broadcom/synopsys/dcd_synopsys.c @@ -434,60 +434,63 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c /*------------------------------------------------------------------*/ /* Controller API *------------------------------------------------------------------*/ + +static void reset_core(USB_OTG_GlobalTypeDef * usb_otg) { + while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0) {} + + TU_LOG(2, " resetting\r\n"); + usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; + TU_LOG(2, " waiting\r\n"); + while ((usb_otg->GRSTCTL & (USB_OTG_GRSTCTL_AHBIDL | USB_OTG_GRSTCTL_CSRST)) != USB_OTG_GRSTCTL_AHBIDL) {} + TU_LOG(2, " reset done\r\n"); +} + void dcd_init (uint8_t rhport) { + printf("test done\r\n"); // Programming model begins in the last section of the chapter on the USB // peripheral in each Reference Manual. - TU_LOG(2, " dcd_init"); + TU_LOG(2, " dcd_init\r\n"); + + TU_LOG2("Test 123\r\n"); USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); - // No HNP/SRP (no OTG support), program timeout later. - if ( rhport == 1 ) - { - // On selected MCUs HS port1 can be used with external PHY via ULPI interface -#if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED - // deactivate internal PHY - usb_otg->GCCFG &= ~USB_OTG_GCCFG_PWRDWN; - // Init The UTMI Interface - usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); + // ReadBackReg(&Core->Usb); + // Core->Usb.UlpiDriveExternalVbus = 0; + // Core->Usb.TsDlinePulseEnable = 0; + // WriteThroughReg(&Core->Usb); - // Select default internal VBUS Indicator and Drive for ULPI - usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); -#else - usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; -#endif + // This sequence is modeled after: https://github.com/Chadderz121/csud/blob/e13b9355d043a9cdd384b335060f1bc0416df61e/source/hcd/dwc/designware20.c#L689 + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIEVBUSD); + reset_core(usb_otg); -#if defined(USB_HS_PHYC) - // Highspeed with embedded UTMI PHYC + // Core->Usb.ModeSelect = UTMI; + // LOG_DEBUG("HCD: Interface: UTMI+.\n"); + // Core->Usb.PhyInterface = false; - // Select UTMI Interface - usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_ULPI_UTMI_SEL; - usb_otg->GCCFG |= USB_OTG_GCCFG_PHYHSEN; + // HcdReset(); + TU_LOG2("init phy\r\n"); + usb_otg->GUSBCFG |= (1 << 4); // bit four sets UTMI+ mode + usb_otg->GUSBCFG &= ~(1 << 3); // bit three disables phy interface + reset_core(usb_otg); - // Enables control of a High Speed USB PHY - USB_HS_PHYCInit(); -#endif - } else - { - // Enable internal PHY - usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; - } + // LOG_DEBUG("HCD: ULPI FSLS configuration: disabled.\n"); + // Core->Usb.UlpiFsls = false; + // Core->Usb.ulpi_clk_sus_m = false; + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_ULPICSM); - // Reset core after selecting PHY - // Wait AHB IDLE, reset then wait until it is cleared - while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U) {} - - TU_LOG(2, " resetting"); - usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; - TU_LOG(2, " waiting"); - while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST) {} - - TU_LOG(2, " reset done"); - - // Restart PHY clock - *((volatile uint32_t *)(RHPORT_REGS_BASE + USB_OTG_PCGCCTL_BASE)) = 0; + // LOG_DEBUG("HCD: DMA configuration: enabled.\n"); + // Core->Ahb.DmaEnable = true; + // Core->Ahb.DmaRemainderMode = Incremental; + usb_otg->GAHBCFG &= ~(1 << 23); // Remainder mode + usb_otg->GAHBCFG |= USB_OTG_GAHBCFG_DMAEN; + + // LOG_DEBUG("HCD: HNP/SRP configuration: HNP, SRP.\n"); + // Core->Usb.HnpCapable = true; + // Core->Usb.SrpCapable = true; + usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_SRPCAP | USB_OTG_GUSBCFG_HNPCAP; // Clear all interrupts usb_otg->GINTSTS |= usb_otg->GINTSTS; @@ -509,8 +512,7 @@ void dcd_init (uint8_t rhport) set_speed(rhport, TUSB_SPEED_FULL); #endif - // Enable internal USB transceiver, unless using HS core (port 1) with external PHY. - if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; + usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; usb_otg->GINTMSK |= USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_WUIM | From 5e437ee1861363e6b02facc5ab814abd67173680 Mon Sep 17 00:00:00 2001 From: hathach Date: Fri, 22 Oct 2021 15:37:34 +0700 Subject: [PATCH 07/51] pi cm4 enumerated as full speed device --- examples/device/cdc_msc/src/tusb_config.h | 3 +- src/common/tusb_common.h | 4 +- src/portable/broadcom/synopsys/dcd_synopsys.c | 59 ++++++++++++++++--- .../broadcom/synopsys/synopsys_common.h | 15 ++++- 4 files changed, 69 insertions(+), 12 deletions(-) diff --git a/examples/device/cdc_msc/src/tusb_config.h b/examples/device/cdc_msc/src/tusb_config.h index bf6af06bc..a3802f536 100644 --- a/examples/device/cdc_msc/src/tusb_config.h +++ b/examples/device/cdc_msc/src/tusb_config.h @@ -48,7 +48,8 @@ // Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed #ifndef BOARD_DEVICE_RHPORT_SPEED #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 || CFG_TUSB_MCU == OPT_MCU_SAMX7X) + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 || CFG_TUSB_MCU == OPT_MCU_SAMX7X || \ + CFG_TUSB_MCU == OPT_MCU_BCM2711) #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED #else #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED diff --git a/src/common/tusb_common.h b/src/common/tusb_common.h index 1899b35cc..9614c12cf 100644 --- a/src/common/tusb_common.h +++ b/src/common/tusb_common.h @@ -337,8 +337,8 @@ void tu_print_var(uint8_t const* buf, uint32_t bufsize) #define TU_LOG1 tu_printf #define TU_LOG1_MEM tu_print_mem #define TU_LOG1_VAR(_x) tu_print_var((uint8_t const*)(_x), sizeof(*(_x))) -#define TU_LOG1_INT(_x) tu_printf(#_x " = %ld\r\n", (uint32_t) (_x) ) -#define TU_LOG1_HEX(_x) tu_printf(#_x " = %lX\r\n", (uint32_t) (_x) ) +#define TU_LOG1_INT(_x) tu_printf(#_x " = %ld\r\n", (unsigned long) (_x) ) +#define TU_LOG1_HEX(_x) tu_printf(#_x " = %lX\r\n", (unsigned long) (_x) ) // Log Level 2: Warn #if CFG_TUSB_DEBUG >= 2 diff --git a/src/portable/broadcom/synopsys/dcd_synopsys.c b/src/portable/broadcom/synopsys/dcd_synopsys.c index ff4ab9fb6..e70e5d4f3 100644 --- a/src/portable/broadcom/synopsys/dcd_synopsys.c +++ b/src/portable/broadcom/synopsys/dcd_synopsys.c @@ -110,6 +110,8 @@ #include "device/dcd.h" +TU_VERIFY_STATIC(sizeof(USB_OTG_GlobalTypeDef) == 0x140, "size is incorrect"); + //--------------------------------------------------------------------+ // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ @@ -340,7 +342,10 @@ static void set_speed(uint8_t rhport, tusb_speed_t speed) dev->DCFG |= (bitvalue << USB_OTG_DCFG_DSPD_Pos); } -#if defined(USB_HS_PHYC) +#if 0 +// From CM4IO xtal to usb hub, may not be correct +#define HSE_VALUE 24000000 + static bool USB_HS_PHYCInit(void) { USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef*) USB_HS_PHYC_CONTROLLER_BASE; @@ -435,6 +440,7 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c /* Controller API *------------------------------------------------------------------*/ +TU_ATTR_UNUSED static void reset_core(USB_OTG_GlobalTypeDef * usb_otg) { while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0) {} @@ -456,6 +462,46 @@ void dcd_init (uint8_t rhport) USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); +#if 1 + // No VBUS sense + usb_otg->GCCFG &= ~(1UL << 21); // USB_OTG_GCCFG_VBDEN + + // B-peripheral session valid override enable + usb_otg->GOTGCTL |= (1UL << 6); // USB_OTG_GOTGCTL_BVALOEN + usb_otg->GOTGCTL |= (1UL << 7); // USB_OTG_GOTGCTL_BVALOVAL + + // Force device mode + usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; + usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + + // deactivate internal PHY + usb_otg->GCCFG &= ~USB_OTG_GCCFG_PWRDWN; + + // Init The UTMI Interface + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); + + // Select default internal VBUS Indicator and Drive for ULPI + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); + + // Select UTMI Interface + usb_otg->GUSBCFG &= ~(1UL << 4); // USB_OTG_GUSBCFG_ULPI_UTMI_SEL + usb_otg->GCCFG |= (1UL << 32); // USB_OTG_GCCFG_PHYHSEN + + // Enables control of a High Speed USB PHY + //USB_HS_PHYCInit(); + + // Reset core after selecting PHY + // Wait AHB IDLE, reset then wait until it is cleared +// while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U) {} +// usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; +// while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST) {} + + reset_core(usb_otg); + + // Restart PHY clock + *((volatile uint32_t *)(RHPORT_REGS_BASE + USB_OTG_PCGCCTL_BASE)) = 0; + +#else // ReadBackReg(&Core->Usb); // Core->Usb.UlpiDriveExternalVbus = 0; @@ -470,7 +516,7 @@ void dcd_init (uint8_t rhport) // LOG_DEBUG("HCD: Interface: UTMI+.\n"); // Core->Usb.PhyInterface = false; - // HcdReset(); + // HcdReset(); TU_LOG2("init phy\r\n"); usb_otg->GUSBCFG |= (1 << 4); // bit four sets UTMI+ mode usb_otg->GUSBCFG &= ~(1 << 3); // bit three disables phy interface @@ -486,12 +532,14 @@ void dcd_init (uint8_t rhport) // Core->Ahb.DmaRemainderMode = Incremental; usb_otg->GAHBCFG &= ~(1 << 23); // Remainder mode usb_otg->GAHBCFG |= USB_OTG_GAHBCFG_DMAEN; - + // LOG_DEBUG("HCD: HNP/SRP configuration: HNP, SRP.\n"); // Core->Usb.HnpCapable = true; // Core->Usb.SrpCapable = true; usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_SRPCAP | USB_OTG_GUSBCFG_HNPCAP; +#endif + // Clear all interrupts usb_otg->GINTSTS |= usb_otg->GINTSTS; @@ -506,12 +554,9 @@ void dcd_init (uint8_t rhport) // (non zero-length packet), send STALL back and discard. dev->DCFG |= USB_OTG_DCFG_NZLSOHSK; - #if TUD_OPT_HIGH_SPEED set_speed(rhport, TUSB_SPEED_HIGH); - #else - set_speed(rhport, TUSB_SPEED_FULL); - #endif + // TODO internal phy (full speed) usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; usb_otg->GINTMSK |= USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | diff --git a/src/portable/broadcom/synopsys/synopsys_common.h b/src/portable/broadcom/synopsys/synopsys_common.h index 6f0602fe9..2ec6f4487 100644 --- a/src/portable/broadcom/synopsys/synopsys_common.h +++ b/src/portable/broadcom/synopsys/synopsys_common.h @@ -60,12 +60,23 @@ typedef struct __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg Address offset: 02Ch */ uint32_t Reserved30[2]; /*!< Reserved 030h*/ __IO uint32_t GCCFG; /*!< General Purpose IO Register Address offset: 038h */ - __IO uint32_t CID; /*!< User ID Register Address offset: 03Ch */ - uint32_t Reserved40[48]; /*!< Reserved 040h-0FFh */ + __IO uint32_t CID; /*!< User ID Register 03Ch */ + __IO uint32_t GSNPSID; /* USB_OTG core ID 040h*/ + __IO uint32_t GHWCFG1; /* User HW config1 044h*/ + __IO uint32_t GHWCFG2; /* User HW config2 048h*/ + __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ + uint32_t Reserved6; /*!< Reserved 050h */ + __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ + __IO uint32_t GPWRDN; /*!< Power Down Register 058h */ + __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ + __IO uint32_t GADPCTL; /*!< ADP Timer, Control and Status Register 60Ch */ + uint32_t Reserved43[39]; /*!< Reserved 058h-0FFh */ __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg Address offset: 100h */ __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO Address offset: 0x104 */ } USB_OTG_GlobalTypeDef; + + /** * @brief __device_Registers */ From 35b62810c3a4b8e2924109905334f054425f16ba Mon Sep 17 00:00:00 2001 From: Scott Shawcroft Date: Fri, 22 Oct 2021 09:00:09 -0700 Subject: [PATCH 08/51] Update submodule --- cortex-a.py | 157 ------------------ hw/mcu/broadcom | 2 +- src/portable/broadcom/synopsys/dcd_synopsys.c | 10 +- .../broadcom/synopsys/synopsys_common.h | 6 +- 4 files changed, 10 insertions(+), 165 deletions(-) delete mode 100644 cortex-a.py diff --git a/cortex-a.py b/cortex-a.py deleted file mode 100644 index 9de16bae9..000000000 --- a/cortex-a.py +++ /dev/null @@ -1,157 +0,0 @@ -class Armv8AException(gdb.Command): - def __init__ (self): - super (Armv8AException, self).__init__ ("armv8a-exception", gdb.COMMAND_USER) - - def print_data_abort(self, frame, iss): - isv = (iss >> 23) & 0x1 - sas = (iss >> 21) & 0x3 - sse = (iss >> 20) & 0x1 - srt = (iss >> 15) & 0x1f - sf = (iss >> 14) & 0x1 - ar = (iss >> 13) & 0x1 - vncr = (iss >> 12) & 0x1 - _set = (iss >> 10) & 0x3 - fnv = (iss >> 9) & 0x1 - ea = (iss >> 8) & 0x1 - cm = (iss >> 7) & 0x1 - s1ptw = (iss >> 6) & 0x1 - wnr = (iss >> 5) & 0x1 - dfsc = iss & 0x1f - if isv: - # print("isv valid", sas, sse, srt, sf, ar) - access_sizes = ("Byte", "Halfword", "Word", "Doubleword") - print("Access size:", access_sizes[sas]) - print("Sign extended:", "Yes" if sse else "No") - print("Register:", hex(srt), "64-bit" if sf else "32-bit") - print("Acquire/Release:", "Yes" if ar else "No") - if dfsc == 0b010000: - print("Not on translation table walk") - if not fnv: - value = int(frame.read_register("FAR_EL2")) - print("FAR", hex(value)) - elif dfsc == 0b000101: - print("translation fault level 1") - elif dfsc == 0b010001: - print("tag check fault") - elif dfsc == 0b100001: - print("alignment fault") - else: - print(bin(dfsc)) - print(vncr, _set, fnv, ea, cm, s1ptw, wnr, dfsc) - - def print_instruction_abort(self, frame, iss): - _set = (iss >> 10) & 0x3 - fnv = (iss >> 9) & 0x1 - ea = (iss >> 8) & 0x1 - s1ptw = (iss >> 6) & 0x1 - ifsc = iss & 0x1f - if ifsc == 0b010000: - print("Not on translation table walk") - if not fnv: - value = int(frame.read_register("FAR_EL2")) - print("FAR", hex(value)) - elif ifsc == 0b00101: - print("translation fault level 1") - elif ifsc == 0b01001: - print("access flag fault level 1") - # elif dfsc == 0b100001: - # print("alignment fault") - else: - print(bin(ifsc)) - - def invoke (self, arg, from_tty): - frame = gdb.selected_frame() - value = int(frame.read_register("ESR_EL2")) - if value == 0: - return None - iss2 = (value >> 32) & 0x1ff - ec = (value >> 26) & 0x3ff - il = (value >> 25) & 0x1 - iss = value & 0xffffff - if ec == 0b000000: - print("Unknown fault") - elif ec == 0b000001: - print("Trapped WF*") - elif ec == 0b000011: - print("Trapped MCR or MRC") - elif ec == 0b000100: - print("Trapped MCRR or MRRC") - elif ec == 0b000101: - print("Trapped MCR or MRC") - elif ec == 0b000110: - print("Trapped LDC or STC") - elif ec == 0b000111: - print("Trapped SIMD") - elif ec == 0b001000: - print("Trapped VMRS") - elif ec == 0b001001: - print("Trapped pointer authentication") - elif ec == 0b001010: - print("Trapped LD64B or ST64B*") - elif ec == 0b001100: - print("Trapped MRRC") - elif ec == 0b001101: - print("Branch target exception") - elif ec == 0b001110: - print("Illegal execution state") - elif ec == 0b010001: - print("SVC instruction") - elif ec == 0b010010: - print("HVC instruction") - elif ec == 0b010011: - print("SMC instruction") - elif ec == 0b010101: - print("SVC instruction") - elif ec == 0b010110: - print("HVC instruction") - elif ec == 0b010111: - print("SMC instruction") - elif ec == 0b011000: - print("Trapped MRS, MRS or system instruction") - elif ec == 0b011001: - print("Trapped SVE") - elif ec == 0b011010: - print("Trapped ERET") - elif ec == 0b011100: - print("Failed pointer authentication") - elif ec == 0b100000: - print("Instruction abort from lower level") - elif ec == 0b100001: - print("Instruction abort from same level") - self.print_instruction_abort(frame, iss) - elif ec == 0b100010: - print("PC alignment failure") - elif ec == 0b100100: - print("Data abort from lower level") - elif ec == 0b100101: - print("Data abort from same level") - self.print_data_abort(frame, iss) - elif ec == 0b100110: - print("SP alignment fault") - elif ec == 0b101000: - print("32-bit floating point exception") - elif ec == 0b101100: - print("64-bit floating point exception") - elif ec == 0b101111: - print("SError interrupt") - elif ec == 0b110000: - print("Breakpoint from lower level") - elif ec == 0b110001: - print("Breakpoint from same level") - elif ec == 0b110010: - print("Software step from lower level") - elif ec == 0b110011: - print("Software step from same level") - elif ec == 0b110100: - print ("Watch point from same level") - elif ec == 0b110101: - print("Watch point from lower level") - elif ec == 0b111000: - print("Breakpoint in aarch32 mode") - elif ec == 0b111010: - print("Vector catch in aarch32") - elif ec == 0b111100: - print("Brk instruction in aarch64") - print(hex(int(value)), iss2, bin(ec), il, iss) - -Armv8AException() diff --git a/hw/mcu/broadcom b/hw/mcu/broadcom index e5343acda..7a8f4b747 160000 --- a/hw/mcu/broadcom +++ b/hw/mcu/broadcom @@ -1 +1 @@ -Subproject commit e5343acdad77b8cf4a8d09b732a11ecef17d148a +Subproject commit 7a8f4b7471ad4aad2e808b3a4cc88b4c23b529f2 diff --git a/src/portable/broadcom/synopsys/dcd_synopsys.c b/src/portable/broadcom/synopsys/dcd_synopsys.c index e70e5d4f3..32cfd6d2a 100644 --- a/src/portable/broadcom/synopsys/dcd_synopsys.c +++ b/src/portable/broadcom/synopsys/dcd_synopsys.c @@ -31,6 +31,8 @@ #include "synopsys_common.h" +#include "broadcom/interrupts.h" + // Since TinyUSB doesn't use SOF for now, and this interrupt too often (1ms interval) // We disable SOF for now until needed later on #define USE_SOF 0 @@ -116,10 +118,10 @@ TU_VERIFY_STATIC(sizeof(USB_OTG_GlobalTypeDef) == 0x140, "size is incorrect"); // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ -#define RHPORT_REGS_BASE 0xfe980000 +#define RHPORT_REGS_BASE USB_OTG_GLOBAL_BASE #define GLOBAL_BASE(_port) ((USB_OTG_GlobalTypeDef*) RHPORT_REGS_BASE) -#define DEVICE_BASE(_port) (USB_OTG_DeviceTypeDef *) (RHPORT_REGS_BASE + USB_OTG_DEVICE_BASE) +#define DEVICE_BASE(_port) (USB_OTG_DeviceTypeDef *) (USB_OTG_DEVICE_BASE) #define OUT_EP_BASE(_port) (USB_OTG_OUTEndpointTypeDef *) (RHPORT_REGS_BASE + USB_OTG_OUT_ENDPOINT_BASE) #define IN_EP_BASE(_port) (USB_OTG_INEndpointTypeDef *) (RHPORT_REGS_BASE + USB_OTG_IN_ENDPOINT_BASE) #define FIFO_BASE(_port, _x) ((volatile uint32_t *) (RHPORT_REGS_BASE + USB_OTG_FIFO_BASE + (_x) * USB_OTG_FIFO_SIZE)) @@ -572,13 +574,13 @@ void dcd_init (uint8_t rhport) void dcd_int_enable (uint8_t rhport) { (void) rhport; - // NVIC_EnableIRQ(RHPORT_IRQn); + // BP_EnableIRQ(USB_IRQn); } void dcd_int_disable (uint8_t rhport) { (void) rhport; - // NVIC_DisableIRQ(RHPORT_IRQn); + // BP_DisableIRQ(USB_IRQn); } void dcd_set_address (uint8_t rhport, uint8_t dev_addr) diff --git a/src/portable/broadcom/synopsys/synopsys_common.h b/src/portable/broadcom/synopsys/synopsys_common.h index 2ec6f4487..81ce3b4a9 100644 --- a/src/portable/broadcom/synopsys/synopsys_common.h +++ b/src/portable/broadcom/synopsys/synopsys_common.h @@ -169,12 +169,12 @@ typedef struct /*!< USB registers base address */ #define USB_OTG_FS_PERIPH_BASE 0x50000000UL -#define USB_OTG_GLOBAL_BASE 0x00000000UL -#define USB_OTG_DEVICE_BASE 0x00000800UL +// #define USB_OTG_GLOBAL_BASE 0x00000000UL +// #define USB_OTG_DEVICE_BASE 0x00000800UL #define USB_OTG_IN_ENDPOINT_BASE 0x00000900UL #define USB_OTG_OUT_ENDPOINT_BASE 0x00000B00UL #define USB_OTG_EP_REG_SIZE 0x00000020UL -#define USB_OTG_HOST_BASE 0x00000400UL +// #define USB_OTG_HOST_BASE 0x00000400UL #define USB_OTG_HOST_PORT_BASE 0x00000440UL #define USB_OTG_HOST_CHANNEL_BASE 0x00000500UL #define USB_OTG_HOST_CHANNEL_SIZE 0x00000020UL From 2ef200003d06f8e3f19e713cfbc38f474491d4d8 Mon Sep 17 00:00:00 2001 From: Scott Shawcroft Date: Fri, 22 Oct 2021 09:31:24 -0700 Subject: [PATCH 09/51] Update broadcom library --- hw/mcu/broadcom | 2 +- src/portable/broadcom/synopsys/dcd_synopsys.c | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/hw/mcu/broadcom b/hw/mcu/broadcom index 7a8f4b747..55cd6f798 160000 --- a/hw/mcu/broadcom +++ b/hw/mcu/broadcom @@ -1 +1 @@ -Subproject commit 7a8f4b7471ad4aad2e808b3a4cc88b4c23b529f2 +Subproject commit 55cd6f798a45cac905d7bf81baa2bcbf7de7c42e diff --git a/src/portable/broadcom/synopsys/dcd_synopsys.c b/src/portable/broadcom/synopsys/dcd_synopsys.c index 32cfd6d2a..87150f683 100644 --- a/src/portable/broadcom/synopsys/dcd_synopsys.c +++ b/src/portable/broadcom/synopsys/dcd_synopsys.c @@ -574,13 +574,13 @@ void dcd_init (uint8_t rhport) void dcd_int_enable (uint8_t rhport) { (void) rhport; - // BP_EnableIRQ(USB_IRQn); + BP_EnableIRQ(USB_IRQn); } void dcd_int_disable (uint8_t rhport) { (void) rhport; - // BP_DisableIRQ(USB_IRQn); + BP_DisableIRQ(USB_IRQn); } void dcd_set_address (uint8_t rhport, uint8_t dev_addr) From 06de6b725c9d1ccadce0905f85335e4708ad1524 Mon Sep 17 00:00:00 2001 From: hathach Date: Sun, 24 Oct 2021 23:24:46 +0700 Subject: [PATCH 10/51] adding generalized dwc2 driver --- hw/bsp/stm32f4/family.mk | 2 +- src/device/dcd_attr.h | 45 +- src/portable/synopsys/dwc2/dcd_dwc2.c | 1155 ++++++++++++++++++ src/portable/synopsys/dwc2/dwc2_gd32.h | 56 + src/portable/synopsys/dwc2/dwc2_stm32.h | 72 ++ src/portable/synopsys/dwc2/dwc2_type.h | 1471 +++++++++++++++++++++++ 6 files changed, 2792 insertions(+), 9 deletions(-) create mode 100644 src/portable/synopsys/dwc2/dcd_dwc2.c create mode 100644 src/portable/synopsys/dwc2/dwc2_gd32.h create mode 100644 src/portable/synopsys/dwc2/dwc2_stm32.h create mode 100644 src/portable/synopsys/dwc2/dwc2_type.h diff --git a/hw/bsp/stm32f4/family.mk b/hw/bsp/stm32f4/family.mk index 584d69405..9811d3371 100644 --- a/hw/bsp/stm32f4/family.mk +++ b/hw/bsp/stm32f4/family.mk @@ -21,7 +21,7 @@ CFLAGS += \ CFLAGS += -Wno-error=cast-align SRC_C += \ - src/portable/st/synopsys/dcd_synopsys.c \ + src/portable/synopsys/dwc2/dcd_dwc2.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 \ diff --git a/src/device/dcd_attr.h b/src/device/dcd_attr.h index 44f2cc1d6..3690985c6 100644 --- a/src/device/dcd_attr.h +++ b/src/device/dcd_attr.h @@ -85,24 +85,53 @@ #define DCD_ATTR_ENDPOINT_EXCLUSIVE_NUMBER //------------- ST -------------// -#elif TU_CHECK_MCU(STM32F0) || TU_CHECK_MCU(STM32F1) || TU_CHECK_MCU(STM32F3) || \ - TU_CHECK_MCU(STM32L0) || TU_CHECK_MCU(STM32L1) || TU_CHECK_MCU(STM32L4) - // F1: F102, F103 - // L4: L4x2, L4x3 +#elif TU_CHECK_MCU(STM32F0) #define DCD_ATTR_ENDPOINT_MAX 8 -#elif TU_CHECK_MCU(STM32F2) || TU_CHECK_MCU(STM32F4) || TU_CHECK_MCU(STM32F3) - // F1: F105, F107 only has 4 - // L4: L4x5, L4x6 has 6 - // For most mcu, FS has 4, HS has 6 +#elif TU_CHECK_MCU(STM32F1) + #if defined (STM32F105x8) || defined (STM32F105xB) || defined (STM32F105xC) || \ + defined (STM32F107xB) || defined (STM32F107xC) + #define DCD_ATTR_ENDPOINT_MAX 4 + #define DCD_ATTR_DWC2_STM32 + #else + #define DCD_ATTR_ENDPOINT_MAX 8 + #endif + +#elif TU_CHECK_MCU(STM32F2) + // FS has 4 ep, HS has 5 ep #define DCD_ATTR_ENDPOINT_MAX 6 + #define DCD_ATTR_DWC2_STM32 + +#elif TU_CHECK_MCU(STM32F3) + #define DCD_ATTR_ENDPOINT_MAX 8 + +#elif TU_CHECK_MCU(STM32F4) + // For most mcu, FS has 4, HS has 6. TODO 446/469/479 HS has 9 + #define DCD_ATTR_ENDPOINT_MAX 6 + #define DCD_ATTR_DWC2_STM32 #elif TU_CHECK_MCU(STM32F7) // FS has 6, HS has 9 #define DCD_ATTR_ENDPOINT_MAX 9 + #define DCD_ATTR_DWC2_STM32 #elif TU_CHECK_MCU(STM32H7) #define DCD_ATTR_ENDPOINT_MAX 9 + #define DCD_ATTR_DWC2_STM32 + +#elif TU_CHECK_MCU(STM32L0) || TU_CHECK_MCU(STM32L1) + #define DCD_ATTR_ENDPOINT_MAX 8 + +#elif TU_CHECK_MCU(STM32L4) + #if defined (STM32L475xx) || defined (STM32L476xx) || \ + defined (STM32L485xx) || defined (STM32L486xx) || defined (STM32L496xx) || \ + defined (STM32L4R5xx) || defined (STM32L4R7xx) || defined (STM32L4R9xx) || \ + defined (STM32L4S5xx) || defined (STM32L4S7xx) || defined (STM32L4S9xx) + #define DCD_ATTR_ENDPOINT_MAX 6 + #define DCD_ATTR_DWC2_STM32 + #else + #define DCD_ATTR_ENDPOINT_MAX 8 + #endif //------------- Sony -------------// #elif TU_CHECK_MCU(CXD56) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c new file mode 100644 index 000000000..597f4c813 --- /dev/null +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -0,0 +1,1155 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 William D. Jones + * Copyright (c) 2019 Ha Thach (tinyusb.org) + * Copyright (c) 2020 Jan Duempelmann + * Copyright (c) 2020 Reinhard Panhuber + * + * 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 "tusb_option.h" +#include "device/dcd_attr.h" + +#if TUSB_OPT_DEVICE_ENABLED && (defined(DCD_ATTR_DWC2_STM32) || TU_CHECK_MCU(GD32VF103)) + +#include "dwc2_type.h" + +#if defined(DCD_ATTR_DWC2_STM32) + #include "dwc2_stm32.h" +#elif TU_CHECK_MCU(GD32VF103) + #include "dwc2_gd32.h" +#else + #error "Unsupported MCUs" +#endif + +#include "device/dcd.h" + +// Since TinyUSB doesn't use SOF for now, and this interrupt too often (1ms interval) +// We disable SOF for now until needed later on +#define USE_SOF 0 + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM +//--------------------------------------------------------------------+ + +// On STM32 we associate Port0 to OTG_FS, and Port1 to OTG_HS +#if TUD_OPT_RHPORT == 0 +#define EP_MAX EP_MAX_FS +#define EP_FIFO_SIZE EP_FIFO_SIZE_FS +#define RHPORT_REGS_BASE USB_OTG_FS_PERIPH_BASE +#define RHPORT_IRQn OTG_FS_IRQn + +#else +#define EP_MAX EP_MAX_HS +#define EP_FIFO_SIZE EP_FIFO_SIZE_HS +#define RHPORT_REGS_BASE USB_OTG_HS_PERIPH_BASE +#define RHPORT_IRQn OTG_HS_IRQn + +#endif + +#define GLOBAL_BASE(_port) ((dwc2_core_t*) RHPORT_REGS_BASE) +#define DEVICE_BASE(_port) ((dwc2_device_t *) (RHPORT_REGS_BASE + USB_OTG_DEVICE_BASE)) +#define OUT_EP_BASE(_port) ((dwc2_epout_t *) (RHPORT_REGS_BASE + USB_OTG_OUT_ENDPOINT_BASE)) +#define IN_EP_BASE(_port) ((dwc2_epin_t *) (RHPORT_REGS_BASE + USB_OTG_IN_ENDPOINT_BASE)) +#define FIFO_BASE(_port, _x) ((volatile uint32_t *) (RHPORT_REGS_BASE + USB_OTG_FIFO_BASE + (_x) * USB_OTG_FIFO_SIZE)) + +enum +{ + DCD_HIGH_SPEED = 0, // Highspeed mode + DCD_FULL_SPEED_USE_HS = 1, // Full speed in Highspeed port (probably with internal PHY) + DCD_FULL_SPEED = 3, // Full speed with internal PHY +}; + +static TU_ATTR_ALIGNED(4) uint32_t _setup_packet[2]; + +typedef struct { + uint8_t * buffer; + tu_fifo_t * ff; + uint16_t total_len; + uint16_t max_size; + uint8_t interval; +} xfer_ctl_t; + +typedef volatile uint32_t * usb_fifo_t; + +xfer_ctl_t xfer_status[EP_MAX][2]; +#define XFER_CTL_BASE(_ep, _dir) &xfer_status[_ep][_dir] + +// EP0 transfers are limited to 1 packet - larger sizes has to be split +static uint16_t ep0_pending[2]; // Index determines direction as tusb_dir_t type + +// TX FIFO RAM allocation so far in words - RX FIFO size is readily available from usb_otg->GRXFSIZ +static uint16_t _allocated_fifo_words_tx; // TX FIFO size in words (IN EPs) +static bool _out_ep_closed; // Flag to check if RX FIFO size needs an update (reduce its size) + +// Calculate the RX FIFO size according to recommendations from reference manual +static inline uint16_t calc_rx_ff_size(uint16_t ep_size) +{ + return 15 + 2*(ep_size/4) + 2*EP_MAX; +} + +static void update_grxfsiz(uint8_t rhport) +{ + (void) rhport; + + dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + + // Determine largest EP size for RX FIFO + uint16_t max_epsize = 0; + for (uint8_t epnum = 0; epnum < EP_MAX; epnum++) + { + max_epsize = tu_max16(max_epsize, xfer_status[epnum][TUSB_DIR_OUT].max_size); + } + + // Update size of RX FIFO + usb_otg->GRXFSIZ = calc_rx_ff_size(max_epsize); +} + +// Setup the control endpoint 0. +static void bus_reset(uint8_t rhport) +{ + (void) rhport; + + dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); + dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + + tu_memclr(xfer_status, sizeof(xfer_status)); + _out_ep_closed = false; + + // clear device address + dev->DCFG &= ~USB_OTG_DCFG_DAD_Msk; + + // 1. NAK for all OUT endpoints + for(uint8_t n = 0; n < EP_MAX; n++) { + out_ep[n].DOEPCTL |= USB_OTG_DOEPCTL_SNAK; + } + + // 2. Un-mask interrupt bits + dev->DAINTMSK = (1 << USB_OTG_DAINTMSK_OEPM_Pos) | (1 << USB_OTG_DAINTMSK_IEPM_Pos); + dev->DOEPMSK = USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM; + dev->DIEPMSK = USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM; + + // "USB Data FIFOs" section in reference manual + // Peripheral FIFO architecture + // + // The FIFO is split up in a lower part where the RX FIFO is located and an upper part where the TX FIFOs start. + // We do this to allow the RX FIFO to grow dynamically which is possible since the free space is located + // between the RX and TX FIFOs. This is required by ISO OUT EPs which need a bigger FIFO than the standard + // configuration done below. + // + // Dynamically FIFO sizes are of interest only for ISO EPs since all others are usually not opened and closed. + // All EPs other than ISO are opened as soon as the driver starts up i.e. when the host sends a + // configure interface command. Hence, all IN EPs other the ISO will be located at the top. IN ISO EPs are usually + // opened when the host sends an additional command: setInterface. At this point in time + // the ISO EP will be located next to the free space and can change its size. In case more IN EPs change its size + // an additional memory + // + // --------------- 320 or 1024 ( 1280 or 4096 bytes ) + // | IN FIFO 0 | + // --------------- (320 or 1024) - 16 + // | IN FIFO 1 | + // --------------- (320 or 1024) - 16 - x + // | . . . . | + // --------------- (320 or 1024) - 16 - x - y - ... - z + // | IN FIFO MAX | + // --------------- + // | FREE | + // --------------- GRXFSIZ + // | OUT FIFO | + // | ( Shared ) | + // --------------- 0 + // + // According to "FIFO RAM allocation" section in RM, FIFO RAM are allocated as follows (each word 32-bits): + // - Each EP IN needs at least max packet size, 16 words is sufficient for EP0 IN + // + // - All EP OUT shared a unique OUT FIFO which uses + // - 13 for setup packets + control words (up to 3 setup packets). + // - 1 for global NAK (not required/used here). + // - Largest-EPsize / 4 + 1. ( FS: 64 bytes, HS: 512 bytes). Recommended is "2 x (Largest-EPsize/4) + 1" + // - 2 for each used OUT endpoint + // + // Therefore GRXFSIZ = 13 + 1 + 1 + 2 x (Largest-EPsize/4) + 2 x EPOUTnum + // - FullSpeed (64 Bytes ): GRXFSIZ = 15 + 2 x 16 + 2 x EP_MAX = 47 + 2 x EP_MAX + // - Highspeed (512 bytes): GRXFSIZ = 15 + 2 x 128 + 2 x EP_MAX = 271 + 2 x EP_MAX + // + // NOTE: Largest-EPsize & EPOUTnum is actual used endpoints in configuration. Since DCD has no knowledge + // of the overall picture yet. We will use the worst scenario: largest possible + EP_MAX + // + // For Isochronous, largest EP size can be 1023/1024 for FS/HS respectively. In addition if multiple ISO + // are enabled at least "2 x (Largest-EPsize/4) + 1" are recommended. Maybe provide a macro for application to + // overwrite this. + + usb_otg->GRXFSIZ = calc_rx_ff_size(TUD_OPT_HIGH_SPEED ? 512 : 64); + + _allocated_fifo_words_tx = 16; + + // Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) + usb_otg->DIEPTXF0_HNPTXFSIZ = (16 << USB_OTG_TX0FD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + + // Fixed control EP0 size to 64 bytes + in_ep[0].DIEPCTL &= ~(0x03 << USB_OTG_DIEPCTL_MPSIZ_Pos); + xfer_status[0][TUSB_DIR_OUT].max_size = xfer_status[0][TUSB_DIR_IN].max_size = 64; + + out_ep[0].DOEPTSIZ |= (3 << USB_OTG_DOEPTSIZ_STUPCNT_Pos); + + usb_otg->GINTMSK |= USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT; +} + +// Set turn-around timeout according to link speed +extern uint32_t SystemCoreClock; +static void set_turnaround(dwc2_core_t * usb_otg, tusb_speed_t speed) +{ + usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; + + if ( speed == TUSB_SPEED_HIGH ) + { + // Use fixed 0x09 for Highspeed + usb_otg->GUSBCFG |= (0x09 << USB_OTG_GUSBCFG_TRDT_Pos); + } + else + { + // Turnaround timeout depends on the MCU clock + uint32_t turnaround; + + if ( SystemCoreClock >= 32000000U ) + turnaround = 0x6U; + else if ( SystemCoreClock >= 27500000U ) + turnaround = 0x7U; + else if ( SystemCoreClock >= 24000000U ) + turnaround = 0x8U; + else if ( SystemCoreClock >= 21800000U ) + turnaround = 0x9U; + else if ( SystemCoreClock >= 20000000U ) + turnaround = 0xAU; + else if ( SystemCoreClock >= 18500000U ) + turnaround = 0xBU; + else if ( SystemCoreClock >= 17200000U ) + turnaround = 0xCU; + else if ( SystemCoreClock >= 16000000U ) + turnaround = 0xDU; + else if ( SystemCoreClock >= 15000000U ) + turnaround = 0xEU; + else + turnaround = 0xFU; + + // Fullspeed depends on MCU clocks, but we will use 0x06 for 32+ Mhz + usb_otg->GUSBCFG |= (turnaround << USB_OTG_GUSBCFG_TRDT_Pos); + } +} + +static tusb_speed_t get_speed(uint8_t rhport) +{ + (void) rhport; + dwc2_device_t * dev = DEVICE_BASE(rhport); + uint32_t const enum_spd = (dev->DSTS & USB_OTG_DSTS_ENUMSPD_Msk) >> USB_OTG_DSTS_ENUMSPD_Pos; + return (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL; +} + +static void set_speed(uint8_t rhport, tusb_speed_t speed) +{ + uint32_t bitvalue; + + if ( rhport == 1 ) + { + bitvalue = ((TUSB_SPEED_HIGH == speed) ? DCD_HIGH_SPEED : DCD_FULL_SPEED_USE_HS); + } + else + { + bitvalue = DCD_FULL_SPEED; + } + + dwc2_device_t * dev = DEVICE_BASE(rhport); + + // Clear and set speed bits + dev->DCFG &= ~(3 << USB_OTG_DCFG_DSPD_Pos); + dev->DCFG |= (bitvalue << USB_OTG_DCFG_DSPD_Pos); +} + +#if defined(USB_HS_PHYC) +static bool USB_HS_PHYCInit(void) +{ + USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef*) USB_HS_PHYC_CONTROLLER_BASE; + + // Enable LDO + usb_hs_phyc->USB_HS_PHYC_LDO |= USB_HS_PHYC_LDO_ENABLE; + + // Wait until LDO ready + while ( 0 == (usb_hs_phyc->USB_HS_PHYC_LDO & USB_HS_PHYC_LDO_STATUS) ) {} + + uint32_t phyc_pll = 0; + + // TODO Try to get HSE_VALUE from registers instead of depending CFLAGS + switch ( HSE_VALUE ) + { + case 12000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12MHZ ; break; + case 12500000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12_5MHZ ; break; + case 16000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_16MHZ ; break; + case 24000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_24MHZ ; break; + case 25000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_25MHZ ; break; + case 32000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_Msk ; break; // Value not defined in header + default: + TU_ASSERT(0); + } + usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll; + + // Control the tuning interface of the High Speed PHY + // Use magic value (USB_HS_PHYC_TUNE_VALUE) from ST driver + usb_hs_phyc->USB_HS_PHYC_TUNE |= 0x00000F13U; + + // Enable PLL internal PHY + usb_hs_phyc->USB_HS_PHYC_PLL |= USB_HS_PHYC_PLL_PLLEN; + + // Original ST code has 2 ms delay for PLL stabilization. + // Primitive test shows that more than 10 USB un/replug cycle showed no error with enumeration + + return true; +} +#endif + +static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t const dir, uint16_t const num_packets, uint16_t total_bytes) +{ + (void) rhport; + + dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); + dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + + // EP0 is limited to one packet each xfer + // We use multiple transaction of xfer->max_size length to get a whole transfer done + if(epnum == 0) { + xfer_ctl_t * const xfer = XFER_CTL_BASE(epnum, dir); + total_bytes = tu_min16(ep0_pending[dir], xfer->max_size); + ep0_pending[dir] -= total_bytes; + } + + // IN and OUT endpoint xfers are interrupt-driven, we just schedule them here. + if(dir == TUSB_DIR_IN) { + // A full IN transfer (multiple packets, possibly) triggers XFRC. + in_ep[epnum].DIEPTSIZ = (num_packets << USB_OTG_DIEPTSIZ_PKTCNT_Pos) | + ((total_bytes << USB_OTG_DIEPTSIZ_XFRSIZ_Pos) & USB_OTG_DIEPTSIZ_XFRSIZ_Msk); + + in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_EPENA | USB_OTG_DIEPCTL_CNAK; + // For ISO endpoint set correct odd/even bit for next frame. + if ((in_ep[epnum].DIEPCTL & USB_OTG_DIEPCTL_EPTYP) == USB_OTG_DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) + { + // Take odd/even bit from frame counter. + uint32_t const odd_frame_now = (dev->DSTS & (1u << USB_OTG_DSTS_FNSOF_Pos)); + in_ep[epnum].DIEPCTL |= (odd_frame_now ? USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Msk : USB_OTG_DIEPCTL_SODDFRM_Msk); + } + // Enable fifo empty interrupt only if there are something to put in the fifo. + if(total_bytes != 0) { + dev->DIEPEMPMSK |= (1 << epnum); + } + } else { + // A full OUT transfer (multiple packets, possibly) triggers XFRC. + out_ep[epnum].DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT_Msk | USB_OTG_DOEPTSIZ_XFRSIZ); + out_ep[epnum].DOEPTSIZ |= (num_packets << USB_OTG_DOEPTSIZ_PKTCNT_Pos) | + ((total_bytes << USB_OTG_DOEPTSIZ_XFRSIZ_Pos) & USB_OTG_DOEPTSIZ_XFRSIZ_Msk); + + out_ep[epnum].DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + if ((out_ep[epnum].DOEPCTL & USB_OTG_DOEPCTL_EPTYP) == USB_OTG_DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) + { + // Take odd/even bit from frame counter. + uint32_t const odd_frame_now = (dev->DSTS & (1u << USB_OTG_DSTS_FNSOF_Pos)); + out_ep[epnum].DOEPCTL |= (odd_frame_now ? USB_OTG_DOEPCTL_SD0PID_SEVNFRM_Msk : USB_OTG_DOEPCTL_SODDFRM_Msk); + } + } +} + +/*------------------------------------------------------------------*/ +/* Controller API + *------------------------------------------------------------------*/ +void dcd_init (uint8_t rhport) +{ + // Programming model begins in the last section of the chapter on the USB + // peripheral in each Reference Manual. + + dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + + // No HNP/SRP (no OTG support), program timeout later. + if ( rhport == 1 ) + { + // On selected MCUs HS port1 can be used with external PHY via ULPI interface +#if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED + // deactivate internal PHY + usb_otg->GCCFG &= ~USB_OTG_GCCFG_PWRDWN; + + // Init The UTMI Interface + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); + + // Select default internal VBUS Indicator and Drive for ULPI + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); +#else + usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; +#endif + +#if defined(USB_HS_PHYC) + // Highspeed with embedded UTMI PHYC + + // Select UTMI Interface + usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_ULPI_UTMI_SEL; + usb_otg->GCCFG |= USB_OTG_GCCFG_PHYHSEN; + + // Enables control of a High Speed USB PHY + USB_HS_PHYCInit(); +#endif + } else + { + // Enable internal PHY + usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; + } + + // Reset core after selecting PHY + // Wait AHB IDLE, reset then wait until it is cleared + while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U) {} + usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; + while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST) {} + + // Restart PHY clock + *((volatile uint32_t *)(RHPORT_REGS_BASE + USB_OTG_PCGCCTL_BASE)) = 0; + + // Clear all interrupts + usb_otg->GINTSTS |= usb_otg->GINTSTS; + + // Required as part of core initialization. + // TODO: How should mode mismatch be handled? It will cause + // the core to stop working/require reset. + usb_otg->GINTMSK |= USB_OTG_GINTMSK_OTGINT | USB_OTG_GINTMSK_MMISM; + + dwc2_device_t * dev = DEVICE_BASE(rhport); + + // If USB host misbehaves during status portion of control xfer + // (non zero-length packet), send STALL back and discard. + dev->DCFG |= USB_OTG_DCFG_NZLSOHSK; + + set_speed(rhport, TUD_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL); + + // Enable internal USB transceiver, unless using HS core (port 1) with external PHY. + if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; + + usb_otg->GINTMSK |= USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | + USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_WUIM | + USB_OTG_GINTMSK_RXFLVLM | (USE_SOF ? USB_OTG_GINTMSK_SOFM : 0); + + // Enable global interrupt + usb_otg->GAHBCFG |= USB_OTG_GAHBCFG_GINT; + + dcd_connect(rhport); +} + +void dcd_int_enable (uint8_t rhport) +{ + (void) rhport; + NVIC_EnableIRQ(RHPORT_IRQn); +} + +void dcd_int_disable (uint8_t rhport) +{ + (void) rhport; + NVIC_DisableIRQ(RHPORT_IRQn); +} + +void dcd_set_address (uint8_t rhport, uint8_t dev_addr) +{ + dwc2_device_t * dev = DEVICE_BASE(rhport); + dev->DCFG = (dev->DCFG & ~USB_OTG_DCFG_DAD_Msk) | (dev_addr << USB_OTG_DCFG_DAD_Pos); + + // Response with status after changing device address + dcd_edpt_xfer(rhport, tu_edpt_addr(0, TUSB_DIR_IN), NULL, 0); +} + +static void remote_wakeup_delay(void) +{ + // try to delay for 1 ms + uint32_t count = SystemCoreClock / 1000; + while ( count-- ) + { + __NOP(); + } +} + +void dcd_remote_wakeup(uint8_t rhport) +{ + (void) rhport; + + dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_device_t * dev = DEVICE_BASE(rhport); + + // set remote wakeup + dev->DCTL |= USB_OTG_DCTL_RWUSIG; + + // enable SOF to detect bus resume + usb_otg->GINTSTS = USB_OTG_GINTSTS_SOF; + usb_otg->GINTMSK |= USB_OTG_GINTMSK_SOFM; + + // Per specs: remote wakeup signal bit must be clear within 1-15ms + remote_wakeup_delay(); + + dev->DCTL &= ~USB_OTG_DCTL_RWUSIG; +} + +void dcd_connect(uint8_t rhport) +{ + (void) rhport; + dwc2_device_t * dev = DEVICE_BASE(rhport); + dev->DCTL &= ~USB_OTG_DCTL_SDIS; +} + +void dcd_disconnect(uint8_t rhport) +{ + (void) rhport; + dwc2_device_t * dev = DEVICE_BASE(rhport); + dev->DCTL |= USB_OTG_DCTL_SDIS; +} + + +/*------------------------------------------------------------------*/ +/* DCD Endpoint port + *------------------------------------------------------------------*/ + +bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) +{ + (void) rhport; + + dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); + dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + + uint8_t const epnum = tu_edpt_number(desc_edpt->bEndpointAddress); + uint8_t const dir = tu_edpt_dir(desc_edpt->bEndpointAddress); + + TU_ASSERT(epnum < EP_MAX); + + xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); + xfer->max_size = tu_edpt_packet_size(desc_edpt); + xfer->interval = desc_edpt->bInterval; + + uint16_t const fifo_size = (xfer->max_size + 3) / 4; // Round up to next full word + + if(dir == TUSB_DIR_OUT) + { + // Calculate required size of RX FIFO + uint16_t const sz = calc_rx_ff_size(4*fifo_size); + + // If size_rx needs to be extended check if possible and if so enlarge it + if (usb_otg->GRXFSIZ < sz) + { + TU_ASSERT(sz + _allocated_fifo_words_tx <= EP_FIFO_SIZE/4); + + // Enlarge RX FIFO + usb_otg->GRXFSIZ = sz; + } + + out_ep[epnum].DOEPCTL |= (1 << USB_OTG_DOEPCTL_USBAEP_Pos) | + (desc_edpt->bmAttributes.xfer << USB_OTG_DOEPCTL_EPTYP_Pos) | + (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? USB_OTG_DOEPCTL_SD0PID_SEVNFRM : 0) | + (xfer->max_size << USB_OTG_DOEPCTL_MPSIZ_Pos); + + dev->DAINTMSK |= (1 << (USB_OTG_DAINTMSK_OEPM_Pos + epnum)); + } + else + { + // "USB Data FIFOs" section in reference manual + // Peripheral FIFO architecture + // + // --------------- 320 or 1024 ( 1280 or 4096 bytes ) + // | IN FIFO 0 | + // --------------- (320 or 1024) - 16 + // | IN FIFO 1 | + // --------------- (320 or 1024) - 16 - x + // | . . . . | + // --------------- (320 or 1024) - 16 - x - y - ... - z + // | IN FIFO MAX | + // --------------- + // | FREE | + // --------------- GRXFSIZ + // | OUT FIFO | + // | ( Shared ) | + // --------------- 0 + // + // In FIFO is allocated by following rules: + // - IN EP 1 gets FIFO 1, IN EP "n" gets FIFO "n". + + // Check if free space is available + TU_ASSERT(_allocated_fifo_words_tx + fifo_size + usb_otg->GRXFSIZ <= EP_FIFO_SIZE/4); + + _allocated_fifo_words_tx += fifo_size; + + TU_LOG(2, " Allocated %u bytes at offset %u", fifo_size*4, EP_FIFO_SIZE-_allocated_fifo_words_tx*4); + + // DIEPTXF starts at FIFO #1. + // Both TXFD and TXSA are in unit of 32-bit words. + usb_otg->DIEPTXF[epnum - 1] = (fifo_size << USB_OTG_DIEPTXF_INEPTXFD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + + in_ep[epnum].DIEPCTL |= (1 << USB_OTG_DIEPCTL_USBAEP_Pos) | + (epnum << USB_OTG_DIEPCTL_TXFNUM_Pos) | + (desc_edpt->bmAttributes.xfer << USB_OTG_DIEPCTL_EPTYP_Pos) | + (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? USB_OTG_DIEPCTL_SD0PID_SEVNFRM : 0) | + (xfer->max_size << USB_OTG_DIEPCTL_MPSIZ_Pos); + + dev->DAINTMSK |= (1 << (USB_OTG_DAINTMSK_IEPM_Pos + epnum)); + } + + return true; +} + +// Close all non-control endpoints, cancel all pending transfers if any. +void dcd_edpt_close_all (uint8_t rhport) +{ + (void) rhport; + +// dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); + dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + + // Disable non-control interrupt + dev->DAINTMSK = (1 << USB_OTG_DAINTMSK_OEPM_Pos) | (1 << USB_OTG_DAINTMSK_IEPM_Pos); + + for(uint8_t n = 1; n < EP_MAX; n++) + { + // disable OUT endpoint + out_ep[n].DOEPCTL = 0; + xfer_status[n][TUSB_DIR_OUT].max_size = 0; + + // disable IN endpoint + in_ep[n].DIEPCTL = 0; + xfer_status[n][TUSB_DIR_IN].max_size = 0; + } + + // reset allocated fifo IN + _allocated_fifo_words_tx = 16; +} + +bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t total_bytes) +{ + uint8_t const epnum = tu_edpt_number(ep_addr); + uint8_t const dir = tu_edpt_dir(ep_addr); + + xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); + xfer->buffer = buffer; + xfer->ff = NULL; + xfer->total_len = total_bytes; + + // EP0 can only handle one packet + if(epnum == 0) { + ep0_pending[dir] = total_bytes; + // Schedule the first transaction for EP0 transfer + edpt_schedule_packets(rhport, epnum, dir, 1, ep0_pending[dir]); + return true; + } + + uint16_t num_packets = (total_bytes / xfer->max_size); + uint16_t const short_packet_size = total_bytes % xfer->max_size; + + // Zero-size packet is special case. + if(short_packet_size > 0 || (total_bytes == 0)) { + num_packets++; + } + + // Schedule packets to be sent within interrupt + edpt_schedule_packets(rhport, epnum, dir, num_packets, total_bytes); + + return true; +} + +// The number of bytes has to be given explicitly to allow more flexible control of how many +// bytes should be written and second to keep the return value free to give back a boolean +// success message. If total_bytes is too big, the FIFO will copy only what is available +// into the USB buffer! +bool dcd_edpt_xfer_fifo (uint8_t rhport, uint8_t ep_addr, tu_fifo_t * ff, uint16_t total_bytes) +{ + // USB buffers always work in bytes so to avoid unnecessary divisions we demand item_size = 1 + TU_ASSERT(ff->item_size == 1); + + uint8_t const epnum = tu_edpt_number(ep_addr); + uint8_t const dir = tu_edpt_dir(ep_addr); + + xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); + xfer->buffer = NULL; + xfer->ff = ff; + xfer->total_len = total_bytes; + + uint16_t num_packets = (total_bytes / xfer->max_size); + uint16_t const short_packet_size = total_bytes % xfer->max_size; + + // Zero-size packet is special case. + if(short_packet_size > 0 || (total_bytes == 0)) num_packets++; + + // Schedule packets to be sent within interrupt + edpt_schedule_packets(rhport, epnum, dir, num_packets, total_bytes); + + return true; +} + +static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) +{ + (void) rhport; + + dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); + dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + + uint8_t const epnum = tu_edpt_number(ep_addr); + uint8_t const dir = tu_edpt_dir(ep_addr); + + if(dir == TUSB_DIR_IN) { + // Only disable currently enabled non-control endpoint + if ( (epnum == 0) || !(in_ep[epnum].DIEPCTL & USB_OTG_DIEPCTL_EPENA) ){ + in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_SNAK | (stall ? USB_OTG_DIEPCTL_STALL : 0); + } else { + // Stop transmitting packets and NAK IN xfers. + in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_SNAK; + while((in_ep[epnum].DIEPINT & USB_OTG_DIEPINT_INEPNE) == 0); + + // Disable the endpoint. + in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_EPDIS | (stall ? USB_OTG_DIEPCTL_STALL : 0); + while((in_ep[epnum].DIEPINT & USB_OTG_DIEPINT_EPDISD_Msk) == 0); + in_ep[epnum].DIEPINT = USB_OTG_DIEPINT_EPDISD; + } + + // Flush the FIFO, and wait until we have confirmed it cleared. + usb_otg->GRSTCTL |= (epnum << USB_OTG_GRSTCTL_TXFNUM_Pos); + usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_TXFFLSH; + while((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH_Msk) != 0); + } else { + // Only disable currently enabled non-control endpoint + if ( (epnum == 0) || !(out_ep[epnum].DOEPCTL & USB_OTG_DOEPCTL_EPENA) ){ + out_ep[epnum].DOEPCTL |= stall ? USB_OTG_DOEPCTL_STALL : 0; + } else { + // Asserting GONAK is required to STALL an OUT endpoint. + // Simpler to use polling here, we don't use the "B"OUTNAKEFF interrupt + // anyway, and it can't be cleared by user code. If this while loop never + // finishes, we have bigger problems than just the stack. + dev->DCTL |= USB_OTG_DCTL_SGONAK; + while((usb_otg->GINTSTS & USB_OTG_GINTSTS_BOUTNAKEFF_Msk) == 0); + + // Ditto here- disable the endpoint. + out_ep[epnum].DOEPCTL |= USB_OTG_DOEPCTL_EPDIS | (stall ? USB_OTG_DOEPCTL_STALL : 0); + while((out_ep[epnum].DOEPINT & USB_OTG_DOEPINT_EPDISD_Msk) == 0); + out_ep[epnum].DOEPINT = USB_OTG_DOEPINT_EPDISD; + + // Allow other OUT endpoints to keep receiving. + dev->DCTL |= USB_OTG_DCTL_CGONAK; + } + } +} + +/** + * Close an endpoint. + */ +void dcd_edpt_close (uint8_t rhport, uint8_t ep_addr) +{ + dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + + uint8_t const epnum = tu_edpt_number(ep_addr); + uint8_t const dir = tu_edpt_dir(ep_addr); + + dcd_edpt_disable(rhport, ep_addr, false); + + // Update max_size + xfer_status[epnum][dir].max_size = 0; // max_size = 0 marks a disabled EP - required for changing FIFO allocation + + if (dir == TUSB_DIR_IN) + { + uint16_t const fifo_size = (usb_otg->DIEPTXF[epnum - 1] & USB_OTG_DIEPTXF_INEPTXFD_Msk) >> USB_OTG_DIEPTXF_INEPTXFD_Pos; + uint16_t const fifo_start = (usb_otg->DIEPTXF[epnum - 1] & USB_OTG_DIEPTXF_INEPTXSA_Msk) >> USB_OTG_DIEPTXF_INEPTXSA_Pos; + // For now only the last opened endpoint can be closed without fuss. + TU_ASSERT(fifo_start == EP_FIFO_SIZE/4 - _allocated_fifo_words_tx,); + _allocated_fifo_words_tx -= fifo_size; + } + else + { + _out_ep_closed = true; // Set flag such that RX FIFO gets reduced in size once RX FIFO is empty + } +} + +void dcd_edpt_stall (uint8_t rhport, uint8_t ep_addr) +{ + dcd_edpt_disable(rhport, ep_addr, true); +} + +void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) +{ + (void) rhport; + + dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); + dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + + uint8_t const epnum = tu_edpt_number(ep_addr); + uint8_t const dir = tu_edpt_dir(ep_addr); + + // Clear stall and reset data toggle + if(dir == TUSB_DIR_IN) { + in_ep[epnum].DIEPCTL &= ~USB_OTG_DIEPCTL_STALL; + in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; + } else { + out_ep[epnum].DOEPCTL &= ~USB_OTG_DOEPCTL_STALL; + out_ep[epnum].DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; + } +} + +/*------------------------------------------------------------------*/ + +// Read a single data packet from receive FIFO +static void read_fifo_packet(uint8_t rhport, uint8_t * dst, uint16_t len) +{ + (void) rhport; + + usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); + + // Reading full available 32 bit words from fifo + uint16_t full_words = len >> 2; + for(uint16_t i = 0; i < full_words; i++) { + uint32_t tmp = *rx_fifo; + dst[0] = tmp & 0x000000FF; + dst[1] = (tmp & 0x0000FF00) >> 8; + dst[2] = (tmp & 0x00FF0000) >> 16; + dst[3] = (tmp & 0xFF000000) >> 24; + dst += 4; + } + + // Read the remaining 1-3 bytes from fifo + uint8_t bytes_rem = len & 0x03; + if(bytes_rem != 0) { + uint32_t tmp = *rx_fifo; + dst[0] = tmp & 0x000000FF; + if(bytes_rem > 1) { + dst[1] = (tmp & 0x0000FF00) >> 8; + } + if(bytes_rem > 2) { + dst[2] = (tmp & 0x00FF0000) >> 16; + } + } +} + +// Write a single data packet to EPIN FIFO +static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, uint16_t len) +{ + (void) rhport; + + usb_fifo_t tx_fifo = FIFO_BASE(rhport, fifo_num); + + // Pushing full available 32 bit words to fifo + uint16_t full_words = len >> 2; + for(uint16_t i = 0; i < full_words; i++){ + *tx_fifo = (src[3] << 24) | (src[2] << 16) | (src[1] << 8) | src[0]; + src += 4; + } + + // Write the remaining 1-3 bytes into fifo + uint8_t bytes_rem = len & 0x03; + if(bytes_rem){ + uint32_t tmp_word = 0; + tmp_word |= src[0]; + if(bytes_rem > 1){ + tmp_word |= src[1] << 8; + } + if(bytes_rem > 2){ + tmp_word |= src[2] << 16; + } + *tx_fifo = tmp_word; + } +} + +static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { + dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); + + // Pop control word off FIFO + uint32_t ctl_word = usb_otg->GRXSTSP; + uint8_t pktsts = (ctl_word & USB_OTG_GRXSTSP_PKTSTS_Msk) >> USB_OTG_GRXSTSP_PKTSTS_Pos; + uint8_t epnum = (ctl_word & USB_OTG_GRXSTSP_EPNUM_Msk) >> USB_OTG_GRXSTSP_EPNUM_Pos; + uint16_t bcnt = (ctl_word & USB_OTG_GRXSTSP_BCNT_Msk) >> USB_OTG_GRXSTSP_BCNT_Pos; + + switch(pktsts) { + case 0x01: // Global OUT NAK (Interrupt) + break; + + case 0x02: // Out packet recvd + { + xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, TUSB_DIR_OUT); + + // Read packet off RxFIFO + if (xfer->ff) + { + // Ring buffer + tu_fifo_write_n_const_addr_full_words(xfer->ff, (const void *)(uintptr_t) rx_fifo, bcnt); + } + else + { + // Linear buffer + read_fifo_packet(rhport, xfer->buffer, bcnt); + + // Increment pointer to xfer data + xfer->buffer += bcnt; + } + + // Truncate transfer length in case of short packet + if(bcnt < xfer->max_size) { + xfer->total_len -= (out_ep[epnum].DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DOEPTSIZ_XFRSIZ_Pos; + if(epnum == 0) { + xfer->total_len -= ep0_pending[TUSB_DIR_OUT]; + ep0_pending[TUSB_DIR_OUT] = 0; + } + } + } + break; + + case 0x03: // Out packet done (Interrupt) + break; + + case 0x04: // Setup packet done (Interrupt) + out_ep[epnum].DOEPTSIZ |= (3 << USB_OTG_DOEPTSIZ_STUPCNT_Pos); + break; + + case 0x06: // Setup packet recvd + // We can receive up to three setup packets in succession, but + // only the last one is valid. + _setup_packet[0] = (* rx_fifo); + _setup_packet[1] = (* rx_fifo); + break; + + default: // Invalid + TU_BREAKPOINT(); + break; + } +} + +static void handle_epout_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epout_t * out_ep) { + // DAINT for a given EP clears when DOEPINTx is cleared. + // OEPINT will be cleared when DAINT's out bits are cleared. + for(uint8_t n = 0; n < EP_MAX; n++) { + xfer_ctl_t * xfer = XFER_CTL_BASE(n, TUSB_DIR_OUT); + + if(dev->DAINT & (1 << (USB_OTG_DAINT_OEPINT_Pos + n))) { + // SETUP packet Setup Phase done. + if(out_ep[n].DOEPINT & USB_OTG_DOEPINT_STUP) { + out_ep[n].DOEPINT = USB_OTG_DOEPINT_STUP; + dcd_event_setup_received(rhport, (uint8_t*) &_setup_packet[0], true); + } + + // OUT XFER complete + if(out_ep[n].DOEPINT & USB_OTG_DOEPINT_XFRC) { + out_ep[n].DOEPINT = USB_OTG_DOEPINT_XFRC; + + // EP0 can only handle one packet + if((n == 0) && ep0_pending[TUSB_DIR_OUT]) { + // Schedule another packet to be received. + edpt_schedule_packets(rhport, n, TUSB_DIR_OUT, 1, ep0_pending[TUSB_DIR_OUT]); + } else { + dcd_event_xfer_complete(rhport, n, xfer->total_len, XFER_RESULT_SUCCESS, true); + } + } + } + } +} + +static void handle_epin_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epin_t * in_ep) { + // DAINT for a given EP clears when DIEPINTx is cleared. + // IEPINT will be cleared when DAINT's out bits are cleared. + for ( uint8_t n = 0; n < EP_MAX; n++ ) + { + xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_IN); + + if ( dev->DAINT & (1 << (USB_OTG_DAINT_IEPINT_Pos + n)) ) + { + // IN XFER complete (entire xfer). + if ( in_ep[n].DIEPINT & USB_OTG_DIEPINT_XFRC ) + { + in_ep[n].DIEPINT = USB_OTG_DIEPINT_XFRC; + + // EP0 can only handle one packet + if((n == 0) && ep0_pending[TUSB_DIR_IN]) { + // Schedule another packet to be transmitted. + edpt_schedule_packets(rhport, n, TUSB_DIR_IN, 1, ep0_pending[TUSB_DIR_IN]); + } else { + dcd_event_xfer_complete(rhport, n | TUSB_DIR_IN_MASK, xfer->total_len, XFER_RESULT_SUCCESS, true); + } + } + + // XFER FIFO empty + if ( (in_ep[n].DIEPINT & USB_OTG_DIEPINT_TXFE) && (dev->DIEPEMPMSK & (1 << n)) ) + { + // DIEPINT's TXFE bit is read-only, software cannot clear it. + // It will only be cleared by hardware when written bytes is more than + // - 64 bytes or + // - Half of TX FIFO size (configured by DIEPTXF) + + uint16_t remaining_packets = (in_ep[n].DIEPTSIZ & USB_OTG_DIEPTSIZ_PKTCNT_Msk) >> USB_OTG_DIEPTSIZ_PKTCNT_Pos; + + // Process every single packet (only whole packets can be written to fifo) + for(uint16_t i = 0; i < remaining_packets; i++) + { + uint16_t const remaining_bytes = (in_ep[n].DIEPTSIZ & USB_OTG_DIEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DIEPTSIZ_XFRSIZ_Pos; + + // Packet can not be larger than ep max size + uint16_t const packet_size = tu_min16(remaining_bytes, xfer->max_size); + + // It's only possible to write full packets into FIFO. Therefore DTXFSTS register of current + // EP has to be checked if the buffer can take another WHOLE packet + if(packet_size > ((in_ep[n].DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV_Msk) << 2)) break; + + // Push packet to Tx-FIFO + if (xfer->ff) + { + usb_fifo_t tx_fifo = FIFO_BASE(rhport, n); + tu_fifo_read_n_const_addr_full_words(xfer->ff, (void *)(uintptr_t) tx_fifo, packet_size); + } + else + { + write_fifo_packet(rhport, n, xfer->buffer, packet_size); + + // Increment pointer to xfer data + xfer->buffer += packet_size; + } + } + + // Turn off TXFE if all bytes are written. + if (((in_ep[n].DIEPTSIZ & USB_OTG_DIEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DIEPTSIZ_XFRSIZ_Pos) == 0) + { + dev->DIEPEMPMSK &= ~(1 << n); + } + } + } + } +} + +void dcd_int_handler(uint8_t rhport) +{ + dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); + dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + + uint32_t const int_status = usb_otg->GINTSTS & usb_otg->GINTMSK; + + if(int_status & USB_OTG_GINTSTS_USBRST) + { + // USBRST is start of reset. + usb_otg->GINTSTS = USB_OTG_GINTSTS_USBRST; + bus_reset(rhport); + } + + if(int_status & USB_OTG_GINTSTS_ENUMDNE) + { + // ENUMDNE is the end of reset where speed of the link is detected + + usb_otg->GINTSTS = USB_OTG_GINTSTS_ENUMDNE; + + tusb_speed_t const speed = get_speed(rhport); + + set_turnaround(usb_otg, speed); + dcd_event_bus_reset(rhport, speed, true); + } + + if(int_status & USB_OTG_GINTSTS_USBSUSP) + { + usb_otg->GINTSTS = USB_OTG_GINTSTS_USBSUSP; + dcd_event_bus_signal(rhport, DCD_EVENT_SUSPEND, true); + } + + if(int_status & USB_OTG_GINTSTS_WKUINT) + { + usb_otg->GINTSTS = USB_OTG_GINTSTS_WKUINT; + dcd_event_bus_signal(rhport, DCD_EVENT_RESUME, true); + } + + // TODO check USB_OTG_GINTSTS_DISCINT for disconnect detection + // if(int_status & USB_OTG_GINTSTS_DISCINT) + + if(int_status & USB_OTG_GINTSTS_OTGINT) + { + // OTG INT bit is read-only + uint32_t const otg_int = usb_otg->GOTGINT; + + if (otg_int & USB_OTG_GOTGINT_SEDET) + { + dcd_event_bus_signal(rhport, DCD_EVENT_UNPLUGGED, true); + } + + usb_otg->GOTGINT = otg_int; + } + + if(int_status & USB_OTG_GINTSTS_SOF) + { + usb_otg->GINTSTS = USB_OTG_GINTSTS_SOF; + + // Disable SOF interrupt since currently only used for remote wakeup detection + usb_otg->GINTMSK &= ~USB_OTG_GINTMSK_SOFM; + + dcd_event_bus_signal(rhport, DCD_EVENT_SOF, true); + } + + // RxFIFO non-empty interrupt handling. + if(int_status & USB_OTG_GINTSTS_RXFLVL) + { + // RXFLVL bit is read-only + + // Mask out RXFLVL while reading data from FIFO + usb_otg->GINTMSK &= ~USB_OTG_GINTMSK_RXFLVLM; + + // Loop until all available packets were handled + do + { + handle_rxflvl_ints(rhport, out_ep); + } while(usb_otg->GINTSTS & USB_OTG_GINTSTS_RXFLVL); + + // Manage RX FIFO size + if (_out_ep_closed) + { + update_grxfsiz(rhport); + + // Disable flag + _out_ep_closed = false; + } + + usb_otg->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; + } + + // OUT endpoint interrupt handling. + if(int_status & USB_OTG_GINTSTS_OEPINT) + { + // OEPINT is read-only + handle_epout_ints(rhport, dev, out_ep); + } + + // IN endpoint interrupt handling. + if(int_status & USB_OTG_GINTSTS_IEPINT) + { + // IEPINT bit read-only + handle_epin_ints(rhport, dev, in_ep); + } + + // // Check for Incomplete isochronous IN transfer + // if(int_status & USB_OTG_GINTSTS_IISOIXFR) { + // printf(" IISOIXFR!\r\n"); + //// TU_LOG2(" IISOIXFR!\r\n"); + // } +} + +#endif diff --git a/src/portable/synopsys/dwc2/dwc2_gd32.h b/src/portable/synopsys/dwc2/dwc2_gd32.h new file mode 100644 index 000000000..5abbd225f --- /dev/null +++ b/src/portable/synopsys/dwc2/dwc2_gd32.h @@ -0,0 +1,56 @@ +/* + * 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 DWC2_GD32_H_ +#define DWC2_GD32_H_ + +// for remote wakeup delay +#define __NOP() __asm volatile ("nop") + +// These numbers are the same for the whole GD32VF103 family. +#define OTG_FS_IRQn 86 +#define EP_MAX_FS 4 +#define EP_FIFO_SIZE_FS 1280 + +// The GD32VF103 is a RISC-V MCU, which implements the ECLIC Core-Local +// Interrupt Controller by Nuclei. It is nearly API compatible to the +// NVIC used by ARM MCUs. +#define ECLIC_INTERRUPT_ENABLE_BASE 0xD2001001UL + +#define NVIC_EnableIRQ __eclic_enable_interrupt +#define NVIC_DisableIRQ __eclic_disable_interrupt + +static inline void __eclic_enable_interrupt (uint32_t irq) { + *(volatile uint8_t*)(ECLIC_INTERRUPT_ENABLE_BASE + (irq * 4)) = 1; +} + +static inline void __eclic_disable_interrupt (uint32_t irq){ + *(volatile uint8_t*)(ECLIC_INTERRUPT_ENABLE_BASE + (irq * 4)) = 0; +} + + +#endif /* DWC2_GD32_H_ */ diff --git a/src/portable/synopsys/dwc2/dwc2_stm32.h b/src/portable/synopsys/dwc2/dwc2_stm32.h new file mode 100644 index 000000000..efed6d14a --- /dev/null +++ b/src/portable/synopsys/dwc2/dwc2_stm32.h @@ -0,0 +1,72 @@ +/* + * 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 _TUSB_DWC2_STM32_H_ +#define _TUSB_DWC2_STM32_H_ + +// EP_MAX : Max number of bi-directional endpoints including EP0 +// EP_FIFO_SIZE : Size of dedicated USB SRAM +#if CFG_TUSB_MCU == OPT_MCU_STM32F1 + #include "stm32f1xx.h" + #define EP_MAX_FS 4 + #define EP_FIFO_SIZE_FS 1280 + +#elif CFG_TUSB_MCU == OPT_MCU_STM32F2 + #include "stm32f2xx.h" + #define EP_MAX_FS USB_OTG_FS_MAX_IN_ENDPOINTS + #define EP_FIFO_SIZE_FS USB_OTG_FS_TOTAL_FIFO_SIZE + +#elif CFG_TUSB_MCU == OPT_MCU_STM32F4 + #include "stm32f4xx.h" + #define EP_MAX_FS USB_OTG_FS_MAX_IN_ENDPOINTS + #define EP_FIFO_SIZE_FS USB_OTG_FS_TOTAL_FIFO_SIZE + #define EP_MAX_HS USB_OTG_HS_MAX_IN_ENDPOINTS + #define EP_FIFO_SIZE_HS USB_OTG_HS_TOTAL_FIFO_SIZE + +#elif CFG_TUSB_MCU == OPT_MCU_STM32H7 + #include "stm32h7xx.h" + #define EP_MAX_FS 9 + #define EP_FIFO_SIZE_FS 4096 + #define EP_MAX_HS 9 + #define EP_FIFO_SIZE_HS 4096 + +#elif CFG_TUSB_MCU == OPT_MCU_STM32F7 + #include "stm32f7xx.h" + #define EP_MAX_FS 6 + #define EP_FIFO_SIZE_FS 1280 + #define EP_MAX_HS 9 + #define EP_FIFO_SIZE_HS 4096 + +#elif CFG_TUSB_MCU == OPT_MCU_STM32L4 + #include "stm32l4xx.h" + #define EP_MAX_FS 6 + #define EP_FIFO_SIZE_FS 1280 + +#else + #error "Unsupported MCUs" +#endif + +#endif /* DWC2_STM32_H_ */ diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h new file mode 100644 index 000000000..8f48c71eb --- /dev/null +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -0,0 +1,1471 @@ +/** + * @author MCD Application Team + * Ha Thach (tinyusb.org) + * + * @attention + * + *

© Copyright (c) 2019 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + */ + +#ifndef _TUSB_DWC2_TYPES_H_ +#define _TUSB_DWC2_TYPES_H_ + +#include "stdint.h" + +#ifdef __cplusplus + extern "C" { +#endif + +#ifdef __cplusplus + #define __I volatile +#else + #define __I volatile const +#endif +#define __O volatile +#define __IO volatile +#define __IM volatile const +#define __OM volatile +#define __IOM volatile + +#if 0 +// HS PHY +typedef struct +{ + +__IO uint32_t USB_HS_PHYC_PLL; /*!< This register is used to control the PLL of the HS PHY. 000h */ +__IO uint32_t Reserved04; /*!< Reserved 004h */ +__IO uint32_t Reserved08; /*!< Reserved 008h */ +__IO uint32_t USB_HS_PHYC_TUNE; /*!< This register is used to control the tuning interface of the High Speed PHY. 00Ch */ +__IO uint32_t Reserved10; /*!< Reserved 010h */ +__IO uint32_t Reserved14; /*!< Reserved 014h */ +__IO uint32_t USB_HS_PHYC_LDO; /*!< This register is used to control the regulator (LDO). 018h */ +} USB_HS_PHYC_GlobalTypeDef; +#endif + +// Core +typedef struct +{ + __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ + __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ + __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ + __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ + __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h */ + __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ + __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ + __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ + __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ + __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ + __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ + __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ + uint32_t Reserved30[2]; /*!< Reserved 030h */ + __IO uint32_t GCCFG; /*!< General Purpose IO Register 038h */ + __IO uint32_t CID; /*!< User ID Register 03Ch */ + __IO uint32_t GSNPSID; /* USB_OTG core ID 040h*/ + __IO uint32_t GHWCFG1; /* User HW config1 044h*/ + __IO uint32_t GHWCFG2; /* User HW config2 048h*/ + __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ + uint32_t Reserved6; /*!< Reserved 050h */ + __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ + __IO uint32_t GPWRDN; /*!< Power Down Register 058h */ + __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ + __IO uint32_t GADPCTL; /*!< ADP Timer, Control and Status Register 60Ch */ + uint32_t Reserved43[39]; /*!< Reserved 058h-0FFh */ + __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ + __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO 104h-13Ch */ +} dwc2_core_t; + +// Host +typedef struct +{ + __IO uint32_t HCFG; /*!< Host Configuration Register 400h */ + __IO uint32_t HFIR; /*!< Host Frame Interval Register 404h */ + __IO uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ + uint32_t Reserved40C; /*!< Reserved 40Ch */ + __IO uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ + __IO uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ + __IO uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ +} dwc2_host_t; + +// Host Channel +typedef struct +{ + __IO uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ + __IO uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ + __IO uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ + __IO uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ + __IO uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ + __IO uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ + uint32_t Reserved[2]; /*!< Reserved */ +} dwc2_channel_t; + +// Device +typedef struct +{ + __IO uint32_t DCFG; /*!< dev Configuration Register 800h */ + __IO uint32_t DCTL; /*!< dev Control Register 804h */ + __IO uint32_t DSTS; /*!< dev Status Register (RO) 808h */ + uint32_t Reserved0C; /*!< Reserved 80Ch */ + __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ + __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ + __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ + __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ + uint32_t Reserved20; /*!< Reserved 820h */ + uint32_t Reserved9; /*!< Reserved 824h */ + __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ + __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ + __IO uint32_t DTHRCTL; /*!< dev threshold 830h */ + __IO uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ + __IO uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ + __IO uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ + uint32_t Reserved40; /*!< dedicated EP mask 840h */ + __IO uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ + uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ + __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ +} dwc2_device_t; + +// Endpoint IN +typedef struct +{ + __IO uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ + uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ + __IO uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ + uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ + __IO uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ + __IO uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ + __IO uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ + uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ +} dwc2_epin_t; + +// Endpoint OUT +typedef struct +{ + __IO uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ + uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ + __IO uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ + uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ + __IO uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ + __IO uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ + uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ +} dwc2_epout_t; + + +/*!< USB registers base address */ +#define DWC2_GLOBAL_BASE 0x00000000UL +#define DWC2_DEVICE_BASE 0x00000800UL +#define DWC2_IN_ENDPOINT_BASE 0x00000900UL +#define DWC2_OUT_ENDPOINT_BASE 0x00000B00UL +#define DWC2_EP_REG_SIZE 0x00000020UL +#define DWC2_HOST_BASE 0x00000400UL +#define DWC2_HOST_PORT_BASE 0x00000440UL +#define DWC2_HOST_CHANNEL_BASE 0x00000500UL +#define DWC2_HOST_CHANNEL_SIZE 0x00000020UL +#define DWC2_PCGCCTL_BASE 0x00000E00UL +#define DWC2_FIFO_BASE 0x00001000UL +#define DWC2_FIFO_SIZE 0x00001000UL + +#if 0 +/******************************************************************************/ +/* */ +/* USB_OTG */ +/* */ +/******************************************************************************/ +/******************** Bit definition for USB_OTG_GOTGCTL register ***********/ +#define USB_OTG_GOTGCTL_SRQSCS_Pos (0U) +#define USB_OTG_GOTGCTL_SRQSCS_Msk (0x1UL << USB_OTG_GOTGCTL_SRQSCS_Pos) /*!< 0x00000001 */ +#define USB_OTG_GOTGCTL_SRQSCS USB_OTG_GOTGCTL_SRQSCS_Msk /*!< Session request success */ +#define USB_OTG_GOTGCTL_SRQ_Pos (1U) +#define USB_OTG_GOTGCTL_SRQ_Msk (0x1UL << USB_OTG_GOTGCTL_SRQ_Pos) /*!< 0x00000002 */ +#define USB_OTG_GOTGCTL_SRQ USB_OTG_GOTGCTL_SRQ_Msk /*!< Session request */ +#define USB_OTG_GOTGCTL_HNGSCS_Pos (8U) +#define USB_OTG_GOTGCTL_HNGSCS_Msk (0x1UL << USB_OTG_GOTGCTL_HNGSCS_Pos) /*!< 0x00000100 */ +#define USB_OTG_GOTGCTL_HNGSCS USB_OTG_GOTGCTL_HNGSCS_Msk /*!< Host set HNP enable */ +#define USB_OTG_GOTGCTL_HNPRQ_Pos (9U) +#define USB_OTG_GOTGCTL_HNPRQ_Msk (0x1UL << USB_OTG_GOTGCTL_HNPRQ_Pos) /*!< 0x00000200 */ +#define USB_OTG_GOTGCTL_HNPRQ USB_OTG_GOTGCTL_HNPRQ_Msk /*!< HNP request */ +#define USB_OTG_GOTGCTL_HSHNPEN_Pos (10U) +#define USB_OTG_GOTGCTL_HSHNPEN_Msk (0x1UL << USB_OTG_GOTGCTL_HSHNPEN_Pos) /*!< 0x00000400 */ +#define USB_OTG_GOTGCTL_HSHNPEN USB_OTG_GOTGCTL_HSHNPEN_Msk /*!< Host set HNP enable */ +#define USB_OTG_GOTGCTL_DHNPEN_Pos (11U) +#define USB_OTG_GOTGCTL_DHNPEN_Msk (0x1UL << USB_OTG_GOTGCTL_DHNPEN_Pos) /*!< 0x00000800 */ +#define USB_OTG_GOTGCTL_DHNPEN USB_OTG_GOTGCTL_DHNPEN_Msk /*!< Device HNP enabled */ +#define USB_OTG_GOTGCTL_CIDSTS_Pos (16U) +#define USB_OTG_GOTGCTL_CIDSTS_Msk (0x1UL << USB_OTG_GOTGCTL_CIDSTS_Pos) /*!< 0x00010000 */ +#define USB_OTG_GOTGCTL_CIDSTS USB_OTG_GOTGCTL_CIDSTS_Msk /*!< Connector ID status */ +#define USB_OTG_GOTGCTL_DBCT_Pos (17U) +#define USB_OTG_GOTGCTL_DBCT_Msk (0x1UL << USB_OTG_GOTGCTL_DBCT_Pos) /*!< 0x00020000 */ +#define USB_OTG_GOTGCTL_DBCT USB_OTG_GOTGCTL_DBCT_Msk /*!< Long/short debounce time */ +#define USB_OTG_GOTGCTL_ASVLD_Pos (18U) +#define USB_OTG_GOTGCTL_ASVLD_Msk (0x1UL << USB_OTG_GOTGCTL_ASVLD_Pos) /*!< 0x00040000 */ +#define USB_OTG_GOTGCTL_ASVLD USB_OTG_GOTGCTL_ASVLD_Msk /*!< A-session valid */ +#define USB_OTG_GOTGCTL_BSVLD_Pos (19U) +#define USB_OTG_GOTGCTL_BSVLD_Msk (0x1UL << USB_OTG_GOTGCTL_BSVLD_Pos) /*!< 0x00080000 */ +#define USB_OTG_GOTGCTL_BSVLD USB_OTG_GOTGCTL_BSVLD_Msk /*!< B-session valid */ + +/******************** Bit definition for USB_OTG_HCFG register ********************/ + +#define USB_OTG_HCFG_FSLSPCS_Pos (0U) +#define USB_OTG_HCFG_FSLSPCS_Msk (0x3UL << USB_OTG_HCFG_FSLSPCS_Pos) /*!< 0x00000003 */ +#define USB_OTG_HCFG_FSLSPCS USB_OTG_HCFG_FSLSPCS_Msk /*!< FS/LS PHY clock select */ +#define USB_OTG_HCFG_FSLSPCS_0 (0x1UL << USB_OTG_HCFG_FSLSPCS_Pos) /*!< 0x00000001 */ +#define USB_OTG_HCFG_FSLSPCS_1 (0x2UL << USB_OTG_HCFG_FSLSPCS_Pos) /*!< 0x00000002 */ +#define USB_OTG_HCFG_FSLSS_Pos (2U) +#define USB_OTG_HCFG_FSLSS_Msk (0x1UL << USB_OTG_HCFG_FSLSS_Pos) /*!< 0x00000004 */ +#define USB_OTG_HCFG_FSLSS USB_OTG_HCFG_FSLSS_Msk /*!< FS- and LS-only support */ + +/******************** Bit definition for USB_OTG_DCFG register ********************/ + +#define USB_OTG_DCFG_DSPD_Pos (0U) +#define USB_OTG_DCFG_DSPD_Msk (0x3UL << USB_OTG_DCFG_DSPD_Pos) /*!< 0x00000003 */ +#define USB_OTG_DCFG_DSPD USB_OTG_DCFG_DSPD_Msk /*!< Device speed */ +#define USB_OTG_DCFG_DSPD_0 (0x1UL << USB_OTG_DCFG_DSPD_Pos) /*!< 0x00000001 */ +#define USB_OTG_DCFG_DSPD_1 (0x2UL << USB_OTG_DCFG_DSPD_Pos) /*!< 0x00000002 */ +#define USB_OTG_DCFG_NZLSOHSK_Pos (2U) +#define USB_OTG_DCFG_NZLSOHSK_Msk (0x1UL << USB_OTG_DCFG_NZLSOHSK_Pos) /*!< 0x00000004 */ +#define USB_OTG_DCFG_NZLSOHSK USB_OTG_DCFG_NZLSOHSK_Msk /*!< Nonzero-length status OUT handshake */ + +#define USB_OTG_DCFG_DAD_Pos (4U) +#define USB_OTG_DCFG_DAD_Msk (0x7FUL << USB_OTG_DCFG_DAD_Pos) /*!< 0x000007F0 */ +#define USB_OTG_DCFG_DAD USB_OTG_DCFG_DAD_Msk /*!< Device address */ +#define USB_OTG_DCFG_DAD_0 (0x01UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000010 */ +#define USB_OTG_DCFG_DAD_1 (0x02UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000020 */ +#define USB_OTG_DCFG_DAD_2 (0x04UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000040 */ +#define USB_OTG_DCFG_DAD_3 (0x08UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000080 */ +#define USB_OTG_DCFG_DAD_4 (0x10UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000100 */ +#define USB_OTG_DCFG_DAD_5 (0x20UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000200 */ +#define USB_OTG_DCFG_DAD_6 (0x40UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000400 */ + +#define USB_OTG_DCFG_PFIVL_Pos (11U) +#define USB_OTG_DCFG_PFIVL_Msk (0x3UL << USB_OTG_DCFG_PFIVL_Pos) /*!< 0x00001800 */ +#define USB_OTG_DCFG_PFIVL USB_OTG_DCFG_PFIVL_Msk /*!< Periodic (micro)frame interval */ +#define USB_OTG_DCFG_PFIVL_0 (0x1UL << USB_OTG_DCFG_PFIVL_Pos) /*!< 0x00000800 */ +#define USB_OTG_DCFG_PFIVL_1 (0x2UL << USB_OTG_DCFG_PFIVL_Pos) /*!< 0x00001000 */ + +#define USB_OTG_DCFG_PERSCHIVL_Pos (24U) +#define USB_OTG_DCFG_PERSCHIVL_Msk (0x3UL << USB_OTG_DCFG_PERSCHIVL_Pos) /*!< 0x03000000 */ +#define USB_OTG_DCFG_PERSCHIVL USB_OTG_DCFG_PERSCHIVL_Msk /*!< Periodic scheduling interval */ +#define USB_OTG_DCFG_PERSCHIVL_0 (0x1UL << USB_OTG_DCFG_PERSCHIVL_Pos) /*!< 0x01000000 */ +#define USB_OTG_DCFG_PERSCHIVL_1 (0x2UL << USB_OTG_DCFG_PERSCHIVL_Pos) /*!< 0x02000000 */ + +/******************** Bit definition for USB_OTG_PCGCR register ********************/ +#define USB_OTG_PCGCR_STPPCLK_Pos (0U) +#define USB_OTG_PCGCR_STPPCLK_Msk (0x1UL << USB_OTG_PCGCR_STPPCLK_Pos) /*!< 0x00000001 */ +#define USB_OTG_PCGCR_STPPCLK USB_OTG_PCGCR_STPPCLK_Msk /*!< Stop PHY clock */ +#define USB_OTG_PCGCR_GATEHCLK_Pos (1U) +#define USB_OTG_PCGCR_GATEHCLK_Msk (0x1UL << USB_OTG_PCGCR_GATEHCLK_Pos) /*!< 0x00000002 */ +#define USB_OTG_PCGCR_GATEHCLK USB_OTG_PCGCR_GATEHCLK_Msk /*!< Gate HCLK */ +#define USB_OTG_PCGCR_PHYSUSP_Pos (4U) +#define USB_OTG_PCGCR_PHYSUSP_Msk (0x1UL << USB_OTG_PCGCR_PHYSUSP_Pos) /*!< 0x00000010 */ +#define USB_OTG_PCGCR_PHYSUSP USB_OTG_PCGCR_PHYSUSP_Msk /*!< PHY suspended */ + +/******************** Bit definition for USB_OTG_GOTGINT register ********************/ +#define USB_OTG_GOTGINT_SEDET_Pos (2U) +#define USB_OTG_GOTGINT_SEDET_Msk (0x1UL << USB_OTG_GOTGINT_SEDET_Pos) /*!< 0x00000004 */ +#define USB_OTG_GOTGINT_SEDET USB_OTG_GOTGINT_SEDET_Msk /*!< Session end detected */ +#define USB_OTG_GOTGINT_SRSSCHG_Pos (8U) +#define USB_OTG_GOTGINT_SRSSCHG_Msk (0x1UL << USB_OTG_GOTGINT_SRSSCHG_Pos) /*!< 0x00000100 */ +#define USB_OTG_GOTGINT_SRSSCHG USB_OTG_GOTGINT_SRSSCHG_Msk /*!< Session request success status change */ +#define USB_OTG_GOTGINT_HNSSCHG_Pos (9U) +#define USB_OTG_GOTGINT_HNSSCHG_Msk (0x1UL << USB_OTG_GOTGINT_HNSSCHG_Pos) /*!< 0x00000200 */ +#define USB_OTG_GOTGINT_HNSSCHG USB_OTG_GOTGINT_HNSSCHG_Msk /*!< Host negotiation success status change */ +#define USB_OTG_GOTGINT_HNGDET_Pos (17U) +#define USB_OTG_GOTGINT_HNGDET_Msk (0x1UL << USB_OTG_GOTGINT_HNGDET_Pos) /*!< 0x00020000 */ +#define USB_OTG_GOTGINT_HNGDET USB_OTG_GOTGINT_HNGDET_Msk /*!< Host negotiation detected */ +#define USB_OTG_GOTGINT_ADTOCHG_Pos (18U) +#define USB_OTG_GOTGINT_ADTOCHG_Msk (0x1UL << USB_OTG_GOTGINT_ADTOCHG_Pos) /*!< 0x00040000 */ +#define USB_OTG_GOTGINT_ADTOCHG USB_OTG_GOTGINT_ADTOCHG_Msk /*!< A-device timeout change */ +#define USB_OTG_GOTGINT_DBCDNE_Pos (19U) +#define USB_OTG_GOTGINT_DBCDNE_Msk (0x1UL << USB_OTG_GOTGINT_DBCDNE_Pos) /*!< 0x00080000 */ +#define USB_OTG_GOTGINT_DBCDNE USB_OTG_GOTGINT_DBCDNE_Msk /*!< Debounce done */ + +/******************** Bit definition for USB_OTG_DCTL register ********************/ +#define USB_OTG_DCTL_RWUSIG_Pos (0U) +#define USB_OTG_DCTL_RWUSIG_Msk (0x1UL << USB_OTG_DCTL_RWUSIG_Pos) /*!< 0x00000001 */ +#define USB_OTG_DCTL_RWUSIG USB_OTG_DCTL_RWUSIG_Msk /*!< Remote wakeup signaling */ +#define USB_OTG_DCTL_SDIS_Pos (1U) +#define USB_OTG_DCTL_SDIS_Msk (0x1UL << USB_OTG_DCTL_SDIS_Pos) /*!< 0x00000002 */ +#define USB_OTG_DCTL_SDIS USB_OTG_DCTL_SDIS_Msk /*!< Soft disconnect */ +#define USB_OTG_DCTL_GINSTS_Pos (2U) +#define USB_OTG_DCTL_GINSTS_Msk (0x1UL << USB_OTG_DCTL_GINSTS_Pos) /*!< 0x00000004 */ +#define USB_OTG_DCTL_GINSTS USB_OTG_DCTL_GINSTS_Msk /*!< Global IN NAK status */ +#define USB_OTG_DCTL_GONSTS_Pos (3U) +#define USB_OTG_DCTL_GONSTS_Msk (0x1UL << USB_OTG_DCTL_GONSTS_Pos) /*!< 0x00000008 */ +#define USB_OTG_DCTL_GONSTS USB_OTG_DCTL_GONSTS_Msk /*!< Global OUT NAK status */ + +#define USB_OTG_DCTL_TCTL_Pos (4U) +#define USB_OTG_DCTL_TCTL_Msk (0x7UL << USB_OTG_DCTL_TCTL_Pos) /*!< 0x00000070 */ +#define USB_OTG_DCTL_TCTL USB_OTG_DCTL_TCTL_Msk /*!< Test control */ +#define USB_OTG_DCTL_TCTL_0 (0x1UL << USB_OTG_DCTL_TCTL_Pos) /*!< 0x00000010 */ +#define USB_OTG_DCTL_TCTL_1 (0x2UL << USB_OTG_DCTL_TCTL_Pos) /*!< 0x00000020 */ +#define USB_OTG_DCTL_TCTL_2 (0x4UL << USB_OTG_DCTL_TCTL_Pos) /*!< 0x00000040 */ +#define USB_OTG_DCTL_SGINAK_Pos (7U) +#define USB_OTG_DCTL_SGINAK_Msk (0x1UL << USB_OTG_DCTL_SGINAK_Pos) /*!< 0x00000080 */ +#define USB_OTG_DCTL_SGINAK USB_OTG_DCTL_SGINAK_Msk /*!< Set global IN NAK */ +#define USB_OTG_DCTL_CGINAK_Pos (8U) +#define USB_OTG_DCTL_CGINAK_Msk (0x1UL << USB_OTG_DCTL_CGINAK_Pos) /*!< 0x00000100 */ +#define USB_OTG_DCTL_CGINAK USB_OTG_DCTL_CGINAK_Msk /*!< Clear global IN NAK */ +#define USB_OTG_DCTL_SGONAK_Pos (9U) +#define USB_OTG_DCTL_SGONAK_Msk (0x1UL << USB_OTG_DCTL_SGONAK_Pos) /*!< 0x00000200 */ +#define USB_OTG_DCTL_SGONAK USB_OTG_DCTL_SGONAK_Msk /*!< Set global OUT NAK */ +#define USB_OTG_DCTL_CGONAK_Pos (10U) +#define USB_OTG_DCTL_CGONAK_Msk (0x1UL << USB_OTG_DCTL_CGONAK_Pos) /*!< 0x00000400 */ +#define USB_OTG_DCTL_CGONAK USB_OTG_DCTL_CGONAK_Msk /*!< Clear global OUT NAK */ +#define USB_OTG_DCTL_POPRGDNE_Pos (11U) +#define USB_OTG_DCTL_POPRGDNE_Msk (0x1UL << USB_OTG_DCTL_POPRGDNE_Pos) /*!< 0x00000800 */ +#define USB_OTG_DCTL_POPRGDNE USB_OTG_DCTL_POPRGDNE_Msk /*!< Power-on programming done */ + +/******************** Bit definition for USB_OTG_HFIR register ********************/ +#define USB_OTG_HFIR_FRIVL_Pos (0U) +#define USB_OTG_HFIR_FRIVL_Msk (0xFFFFUL << USB_OTG_HFIR_FRIVL_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_HFIR_FRIVL USB_OTG_HFIR_FRIVL_Msk /*!< Frame interval */ + +/******************** Bit definition for USB_OTG_HFNUM register ********************/ +#define USB_OTG_HFNUM_FRNUM_Pos (0U) +#define USB_OTG_HFNUM_FRNUM_Msk (0xFFFFUL << USB_OTG_HFNUM_FRNUM_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_HFNUM_FRNUM USB_OTG_HFNUM_FRNUM_Msk /*!< Frame number */ +#define USB_OTG_HFNUM_FTREM_Pos (16U) +#define USB_OTG_HFNUM_FTREM_Msk (0xFFFFUL << USB_OTG_HFNUM_FTREM_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_HFNUM_FTREM USB_OTG_HFNUM_FTREM_Msk /*!< Frame time remaining */ + +/******************** Bit definition for USB_OTG_DSTS register ********************/ +#define USB_OTG_DSTS_SUSPSTS_Pos (0U) +#define USB_OTG_DSTS_SUSPSTS_Msk (0x1UL << USB_OTG_DSTS_SUSPSTS_Pos) /*!< 0x00000001 */ +#define USB_OTG_DSTS_SUSPSTS USB_OTG_DSTS_SUSPSTS_Msk /*!< Suspend status */ + +#define USB_OTG_DSTS_ENUMSPD_Pos (1U) +#define USB_OTG_DSTS_ENUMSPD_Msk (0x3UL << USB_OTG_DSTS_ENUMSPD_Pos) /*!< 0x00000006 */ +#define USB_OTG_DSTS_ENUMSPD USB_OTG_DSTS_ENUMSPD_Msk /*!< Enumerated speed */ +#define USB_OTG_DSTS_ENUMSPD_0 (0x1UL << USB_OTG_DSTS_ENUMSPD_Pos) /*!< 0x00000002 */ +#define USB_OTG_DSTS_ENUMSPD_1 (0x2UL << USB_OTG_DSTS_ENUMSPD_Pos) /*!< 0x00000004 */ +#define USB_OTG_DSTS_EERR_Pos (3U) +#define USB_OTG_DSTS_EERR_Msk (0x1UL << USB_OTG_DSTS_EERR_Pos) /*!< 0x00000008 */ +#define USB_OTG_DSTS_EERR USB_OTG_DSTS_EERR_Msk /*!< Erratic error */ +#define USB_OTG_DSTS_FNSOF_Pos (8U) +#define USB_OTG_DSTS_FNSOF_Msk (0x3FFFUL << USB_OTG_DSTS_FNSOF_Pos) /*!< 0x003FFF00 */ +#define USB_OTG_DSTS_FNSOF USB_OTG_DSTS_FNSOF_Msk /*!< Frame number of the received SOF */ + +/******************** Bit definition for USB_OTG_GAHBCFG register ********************/ +#define USB_OTG_GAHBCFG_GINT_Pos (0U) +#define USB_OTG_GAHBCFG_GINT_Msk (0x1UL << USB_OTG_GAHBCFG_GINT_Pos) /*!< 0x00000001 */ +#define USB_OTG_GAHBCFG_GINT USB_OTG_GAHBCFG_GINT_Msk /*!< Global interrupt mask */ +#define USB_OTG_GAHBCFG_HBSTLEN_Pos (1U) +#define USB_OTG_GAHBCFG_HBSTLEN_Msk (0xFUL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< 0x0000001E */ +#define USB_OTG_GAHBCFG_HBSTLEN USB_OTG_GAHBCFG_HBSTLEN_Msk /*!< Burst length/type */ +#define USB_OTG_GAHBCFG_HBSTLEN_0 (0x0UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< Single */ +#define USB_OTG_GAHBCFG_HBSTLEN_1 (0x1UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< INCR */ +#define USB_OTG_GAHBCFG_HBSTLEN_2 (0x3UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< INCR4 */ +#define USB_OTG_GAHBCFG_HBSTLEN_3 (0x5UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< INCR8 */ +#define USB_OTG_GAHBCFG_HBSTLEN_4 (0x7UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< INCR16 */ +#define USB_OTG_GAHBCFG_DMAEN_Pos (5U) +#define USB_OTG_GAHBCFG_DMAEN_Msk (0x1UL << USB_OTG_GAHBCFG_DMAEN_Pos) /*!< 0x00000020 */ +#define USB_OTG_GAHBCFG_DMAEN USB_OTG_GAHBCFG_DMAEN_Msk /*!< DMA enable */ +#define USB_OTG_GAHBCFG_TXFELVL_Pos (7U) +#define USB_OTG_GAHBCFG_TXFELVL_Msk (0x1UL << USB_OTG_GAHBCFG_TXFELVL_Pos) /*!< 0x00000080 */ +#define USB_OTG_GAHBCFG_TXFELVL USB_OTG_GAHBCFG_TXFELVL_Msk /*!< TxFIFO empty level */ +#define USB_OTG_GAHBCFG_PTXFELVL_Pos (8U) +#define USB_OTG_GAHBCFG_PTXFELVL_Msk (0x1UL << USB_OTG_GAHBCFG_PTXFELVL_Pos) /*!< 0x00000100 */ +#define USB_OTG_GAHBCFG_PTXFELVL USB_OTG_GAHBCFG_PTXFELVL_Msk /*!< Periodic TxFIFO empty level */ + +/******************** Bit definition for USB_OTG_GUSBCFG register ********************/ + +#define USB_OTG_GUSBCFG_TOCAL_Pos (0U) +#define USB_OTG_GUSBCFG_TOCAL_Msk (0x7UL << USB_OTG_GUSBCFG_TOCAL_Pos) /*!< 0x00000007 */ +#define USB_OTG_GUSBCFG_TOCAL USB_OTG_GUSBCFG_TOCAL_Msk /*!< FS timeout calibration */ +#define USB_OTG_GUSBCFG_TOCAL_0 (0x1UL << USB_OTG_GUSBCFG_TOCAL_Pos) /*!< 0x00000001 */ +#define USB_OTG_GUSBCFG_TOCAL_1 (0x2UL << USB_OTG_GUSBCFG_TOCAL_Pos) /*!< 0x00000002 */ +#define USB_OTG_GUSBCFG_TOCAL_2 (0x4UL << USB_OTG_GUSBCFG_TOCAL_Pos) /*!< 0x00000004 */ +#define USB_OTG_GUSBCFG_PHYSEL_Pos (6U) +#define USB_OTG_GUSBCFG_PHYSEL_Msk (0x1UL << USB_OTG_GUSBCFG_PHYSEL_Pos) /*!< 0x00000040 */ +#define USB_OTG_GUSBCFG_PHYSEL USB_OTG_GUSBCFG_PHYSEL_Msk /*!< USB 2.0 high-speed ULPI PHY or USB 1.1 full-speed serial transceiver select */ +#define USB_OTG_GUSBCFG_SRPCAP_Pos (8U) +#define USB_OTG_GUSBCFG_SRPCAP_Msk (0x1UL << USB_OTG_GUSBCFG_SRPCAP_Pos) /*!< 0x00000100 */ +#define USB_OTG_GUSBCFG_SRPCAP USB_OTG_GUSBCFG_SRPCAP_Msk /*!< SRP-capable */ +#define USB_OTG_GUSBCFG_HNPCAP_Pos (9U) +#define USB_OTG_GUSBCFG_HNPCAP_Msk (0x1UL << USB_OTG_GUSBCFG_HNPCAP_Pos) /*!< 0x00000200 */ +#define USB_OTG_GUSBCFG_HNPCAP USB_OTG_GUSBCFG_HNPCAP_Msk /*!< HNP-capable */ +#define USB_OTG_GUSBCFG_TRDT_Pos (10U) +#define USB_OTG_GUSBCFG_TRDT_Msk (0xFUL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00003C00 */ +#define USB_OTG_GUSBCFG_TRDT USB_OTG_GUSBCFG_TRDT_Msk /*!< USB turnaround time */ +#define USB_OTG_GUSBCFG_TRDT_0 (0x1UL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00000400 */ +#define USB_OTG_GUSBCFG_TRDT_1 (0x2UL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00000800 */ +#define USB_OTG_GUSBCFG_TRDT_2 (0x4UL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00001000 */ +#define USB_OTG_GUSBCFG_TRDT_3 (0x8UL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00002000 */ +#define USB_OTG_GUSBCFG_PHYLPCS_Pos (15U) +#define USB_OTG_GUSBCFG_PHYLPCS_Msk (0x1UL << USB_OTG_GUSBCFG_PHYLPCS_Pos) /*!< 0x00008000 */ +#define USB_OTG_GUSBCFG_PHYLPCS USB_OTG_GUSBCFG_PHYLPCS_Msk /*!< PHY Low-power clock select */ +#define USB_OTG_GUSBCFG_ULPIFSLS_Pos (17U) +#define USB_OTG_GUSBCFG_ULPIFSLS_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIFSLS_Pos) /*!< 0x00020000 */ +#define USB_OTG_GUSBCFG_ULPIFSLS USB_OTG_GUSBCFG_ULPIFSLS_Msk /*!< ULPI FS/LS select */ +#define USB_OTG_GUSBCFG_ULPIAR_Pos (18U) +#define USB_OTG_GUSBCFG_ULPIAR_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIAR_Pos) /*!< 0x00040000 */ +#define USB_OTG_GUSBCFG_ULPIAR USB_OTG_GUSBCFG_ULPIAR_Msk /*!< ULPI Auto-resume */ +#define USB_OTG_GUSBCFG_ULPICSM_Pos (19U) +#define USB_OTG_GUSBCFG_ULPICSM_Msk (0x1UL << USB_OTG_GUSBCFG_ULPICSM_Pos) /*!< 0x00080000 */ +#define USB_OTG_GUSBCFG_ULPICSM USB_OTG_GUSBCFG_ULPICSM_Msk /*!< ULPI Clock SuspendM */ +#define USB_OTG_GUSBCFG_ULPIEVBUSD_Pos (20U) +#define USB_OTG_GUSBCFG_ULPIEVBUSD_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIEVBUSD_Pos) /*!< 0x00100000 */ +#define USB_OTG_GUSBCFG_ULPIEVBUSD USB_OTG_GUSBCFG_ULPIEVBUSD_Msk /*!< ULPI External VBUS Drive */ +#define USB_OTG_GUSBCFG_ULPIEVBUSI_Pos (21U) +#define USB_OTG_GUSBCFG_ULPIEVBUSI_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIEVBUSI_Pos) /*!< 0x00200000 */ +#define USB_OTG_GUSBCFG_ULPIEVBUSI USB_OTG_GUSBCFG_ULPIEVBUSI_Msk /*!< ULPI external VBUS indicator */ +#define USB_OTG_GUSBCFG_TSDPS_Pos (22U) +#define USB_OTG_GUSBCFG_TSDPS_Msk (0x1UL << USB_OTG_GUSBCFG_TSDPS_Pos) /*!< 0x00400000 */ +#define USB_OTG_GUSBCFG_TSDPS USB_OTG_GUSBCFG_TSDPS_Msk /*!< TermSel DLine pulsing selection */ +#define USB_OTG_GUSBCFG_PCCI_Pos (23U) +#define USB_OTG_GUSBCFG_PCCI_Msk (0x1UL << USB_OTG_GUSBCFG_PCCI_Pos) /*!< 0x00800000 */ +#define USB_OTG_GUSBCFG_PCCI USB_OTG_GUSBCFG_PCCI_Msk /*!< Indicator complement */ +#define USB_OTG_GUSBCFG_PTCI_Pos (24U) +#define USB_OTG_GUSBCFG_PTCI_Msk (0x1UL << USB_OTG_GUSBCFG_PTCI_Pos) /*!< 0x01000000 */ +#define USB_OTG_GUSBCFG_PTCI USB_OTG_GUSBCFG_PTCI_Msk /*!< Indicator pass through */ +#define USB_OTG_GUSBCFG_ULPIIPD_Pos (25U) +#define USB_OTG_GUSBCFG_ULPIIPD_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIIPD_Pos) /*!< 0x02000000 */ +#define USB_OTG_GUSBCFG_ULPIIPD USB_OTG_GUSBCFG_ULPIIPD_Msk /*!< ULPI interface protect disable */ +#define USB_OTG_GUSBCFG_FHMOD_Pos (29U) +#define USB_OTG_GUSBCFG_FHMOD_Msk (0x1UL << USB_OTG_GUSBCFG_FHMOD_Pos) /*!< 0x20000000 */ +#define USB_OTG_GUSBCFG_FHMOD USB_OTG_GUSBCFG_FHMOD_Msk /*!< Forced host mode */ +#define USB_OTG_GUSBCFG_FDMOD_Pos (30U) +#define USB_OTG_GUSBCFG_FDMOD_Msk (0x1UL << USB_OTG_GUSBCFG_FDMOD_Pos) /*!< 0x40000000 */ +#define USB_OTG_GUSBCFG_FDMOD USB_OTG_GUSBCFG_FDMOD_Msk /*!< Forced peripheral mode */ +#define USB_OTG_GUSBCFG_CTXPKT_Pos (31U) +#define USB_OTG_GUSBCFG_CTXPKT_Msk (0x1UL << USB_OTG_GUSBCFG_CTXPKT_Pos) /*!< 0x80000000 */ +#define USB_OTG_GUSBCFG_CTXPKT USB_OTG_GUSBCFG_CTXPKT_Msk /*!< Corrupt Tx packet */ + +/******************** Bit definition for USB_OTG_GRSTCTL register ********************/ +#define USB_OTG_GRSTCTL_CSRST_Pos (0U) +#define USB_OTG_GRSTCTL_CSRST_Msk (0x1UL << USB_OTG_GRSTCTL_CSRST_Pos) /*!< 0x00000001 */ +#define USB_OTG_GRSTCTL_CSRST USB_OTG_GRSTCTL_CSRST_Msk /*!< Core soft reset */ +#define USB_OTG_GRSTCTL_HSRST_Pos (1U) +#define USB_OTG_GRSTCTL_HSRST_Msk (0x1UL << USB_OTG_GRSTCTL_HSRST_Pos) /*!< 0x00000002 */ +#define USB_OTG_GRSTCTL_HSRST USB_OTG_GRSTCTL_HSRST_Msk /*!< HCLK soft reset */ +#define USB_OTG_GRSTCTL_FCRST_Pos (2U) +#define USB_OTG_GRSTCTL_FCRST_Msk (0x1UL << USB_OTG_GRSTCTL_FCRST_Pos) /*!< 0x00000004 */ +#define USB_OTG_GRSTCTL_FCRST USB_OTG_GRSTCTL_FCRST_Msk /*!< Host frame counter reset */ +#define USB_OTG_GRSTCTL_RXFFLSH_Pos (4U) +#define USB_OTG_GRSTCTL_RXFFLSH_Msk (0x1UL << USB_OTG_GRSTCTL_RXFFLSH_Pos) /*!< 0x00000010 */ +#define USB_OTG_GRSTCTL_RXFFLSH USB_OTG_GRSTCTL_RXFFLSH_Msk /*!< RxFIFO flush */ +#define USB_OTG_GRSTCTL_TXFFLSH_Pos (5U) +#define USB_OTG_GRSTCTL_TXFFLSH_Msk (0x1UL << USB_OTG_GRSTCTL_TXFFLSH_Pos) /*!< 0x00000020 */ +#define USB_OTG_GRSTCTL_TXFFLSH USB_OTG_GRSTCTL_TXFFLSH_Msk /*!< TxFIFO flush */ + + +#define USB_OTG_GRSTCTL_TXFNUM_Pos (6U) +#define USB_OTG_GRSTCTL_TXFNUM_Msk (0x1FUL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x000007C0 */ +#define USB_OTG_GRSTCTL_TXFNUM USB_OTG_GRSTCTL_TXFNUM_Msk /*!< TxFIFO number */ +#define USB_OTG_GRSTCTL_TXFNUM_0 (0x01UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000040 */ +#define USB_OTG_GRSTCTL_TXFNUM_1 (0x02UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000080 */ +#define USB_OTG_GRSTCTL_TXFNUM_2 (0x04UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000100 */ +#define USB_OTG_GRSTCTL_TXFNUM_3 (0x08UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000200 */ +#define USB_OTG_GRSTCTL_TXFNUM_4 (0x10UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000400 */ +#define USB_OTG_GRSTCTL_DMAREQ_Pos (30U) +#define USB_OTG_GRSTCTL_DMAREQ_Msk (0x1UL << USB_OTG_GRSTCTL_DMAREQ_Pos) /*!< 0x40000000 */ +#define USB_OTG_GRSTCTL_DMAREQ USB_OTG_GRSTCTL_DMAREQ_Msk /*!< DMA request signal */ +#define USB_OTG_GRSTCTL_AHBIDL_Pos (31U) +#define USB_OTG_GRSTCTL_AHBIDL_Msk (0x1UL << USB_OTG_GRSTCTL_AHBIDL_Pos) /*!< 0x80000000 */ +#define USB_OTG_GRSTCTL_AHBIDL USB_OTG_GRSTCTL_AHBIDL_Msk /*!< AHB master idle */ + +/******************** Bit definition for USB_OTG_DIEPMSK register ********************/ +#define USB_OTG_DIEPMSK_XFRCM_Pos (0U) +#define USB_OTG_DIEPMSK_XFRCM_Msk (0x1UL << USB_OTG_DIEPMSK_XFRCM_Pos) /*!< 0x00000001 */ +#define USB_OTG_DIEPMSK_XFRCM USB_OTG_DIEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define USB_OTG_DIEPMSK_EPDM_Pos (1U) +#define USB_OTG_DIEPMSK_EPDM_Msk (0x1UL << USB_OTG_DIEPMSK_EPDM_Pos) /*!< 0x00000002 */ +#define USB_OTG_DIEPMSK_EPDM USB_OTG_DIEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define USB_OTG_DIEPMSK_TOM_Pos (3U) +#define USB_OTG_DIEPMSK_TOM_Msk (0x1UL << USB_OTG_DIEPMSK_TOM_Pos) /*!< 0x00000008 */ +#define USB_OTG_DIEPMSK_TOM USB_OTG_DIEPMSK_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ +#define USB_OTG_DIEPMSK_ITTXFEMSK_Pos (4U) +#define USB_OTG_DIEPMSK_ITTXFEMSK_Msk (0x1UL << USB_OTG_DIEPMSK_ITTXFEMSK_Pos) /*!< 0x00000010 */ +#define USB_OTG_DIEPMSK_ITTXFEMSK USB_OTG_DIEPMSK_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define USB_OTG_DIEPMSK_INEPNMM_Pos (5U) +#define USB_OTG_DIEPMSK_INEPNMM_Msk (0x1UL << USB_OTG_DIEPMSK_INEPNMM_Pos) /*!< 0x00000020 */ +#define USB_OTG_DIEPMSK_INEPNMM USB_OTG_DIEPMSK_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define USB_OTG_DIEPMSK_INEPNEM_Pos (6U) +#define USB_OTG_DIEPMSK_INEPNEM_Msk (0x1UL << USB_OTG_DIEPMSK_INEPNEM_Pos) /*!< 0x00000040 */ +#define USB_OTG_DIEPMSK_INEPNEM USB_OTG_DIEPMSK_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define USB_OTG_DIEPMSK_TXFURM_Pos (8U) +#define USB_OTG_DIEPMSK_TXFURM_Msk (0x1UL << USB_OTG_DIEPMSK_TXFURM_Pos) /*!< 0x00000100 */ +#define USB_OTG_DIEPMSK_TXFURM USB_OTG_DIEPMSK_TXFURM_Msk /*!< FIFO underrun mask */ +#define USB_OTG_DIEPMSK_BIM_Pos (9U) +#define USB_OTG_DIEPMSK_BIM_Msk (0x1UL << USB_OTG_DIEPMSK_BIM_Pos) /*!< 0x00000200 */ +#define USB_OTG_DIEPMSK_BIM USB_OTG_DIEPMSK_BIM_Msk /*!< BNA interrupt mask */ + +/******************** Bit definition for USB_OTG_HPTXSTS register ********************/ +#define USB_OTG_HPTXSTS_PTXFSAVL_Pos (0U) +#define USB_OTG_HPTXSTS_PTXFSAVL_Msk (0xFFFFUL << USB_OTG_HPTXSTS_PTXFSAVL_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_HPTXSTS_PTXFSAVL USB_OTG_HPTXSTS_PTXFSAVL_Msk /*!< Periodic transmit data FIFO space available */ +#define USB_OTG_HPTXSTS_PTXQSAV_Pos (16U) +#define USB_OTG_HPTXSTS_PTXQSAV_Msk (0xFFUL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00FF0000 */ +#define USB_OTG_HPTXSTS_PTXQSAV USB_OTG_HPTXSTS_PTXQSAV_Msk /*!< Periodic transmit request queue space available */ +#define USB_OTG_HPTXSTS_PTXQSAV_0 (0x01UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00010000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_1 (0x02UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00020000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_2 (0x04UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00040000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_3 (0x08UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00080000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_4 (0x10UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00100000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_5 (0x20UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00200000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_6 (0x40UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00400000 */ +#define USB_OTG_HPTXSTS_PTXQSAV_7 (0x80UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00800000 */ + +#define USB_OTG_HPTXSTS_PTXQTOP_Pos (24U) +#define USB_OTG_HPTXSTS_PTXQTOP_Msk (0xFFUL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0xFF000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP USB_OTG_HPTXSTS_PTXQTOP_Msk /*!< Top of the periodic transmit request queue */ +#define USB_OTG_HPTXSTS_PTXQTOP_0 (0x01UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x01000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_1 (0x02UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x02000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_2 (0x04UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x04000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_3 (0x08UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x08000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_4 (0x10UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x10000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_5 (0x20UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x20000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_6 (0x40UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x40000000 */ +#define USB_OTG_HPTXSTS_PTXQTOP_7 (0x80UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for USB_OTG_HAINT register ********************/ +#define USB_OTG_HAINT_HAINT_Pos (0U) +#define USB_OTG_HAINT_HAINT_Msk (0xFFFFUL << USB_OTG_HAINT_HAINT_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_HAINT_HAINT USB_OTG_HAINT_HAINT_Msk /*!< Channel interrupts */ + +/******************** Bit definition for USB_OTG_DOEPMSK register ********************/ +#define USB_OTG_DOEPMSK_XFRCM_Pos (0U) +#define USB_OTG_DOEPMSK_XFRCM_Msk (0x1UL << USB_OTG_DOEPMSK_XFRCM_Pos) /*!< 0x00000001 */ +#define USB_OTG_DOEPMSK_XFRCM USB_OTG_DOEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define USB_OTG_DOEPMSK_EPDM_Pos (1U) +#define USB_OTG_DOEPMSK_EPDM_Msk (0x1UL << USB_OTG_DOEPMSK_EPDM_Pos) /*!< 0x00000002 */ +#define USB_OTG_DOEPMSK_EPDM USB_OTG_DOEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define USB_OTG_DOEPMSK_AHBERRM_Pos (2U) +#define USB_OTG_DOEPMSK_AHBERRM_Msk (0x1UL << USB_OTG_DOEPMSK_AHBERRM_Pos) /*!< 0x00000004 */ +#define USB_OTG_DOEPMSK_AHBERRM USB_OTG_DOEPMSK_AHBERRM_Msk /*!< OUT transaction AHB Error interrupt mask */ +#define USB_OTG_DOEPMSK_STUPM_Pos (3U) +#define USB_OTG_DOEPMSK_STUPM_Msk (0x1UL << USB_OTG_DOEPMSK_STUPM_Pos) /*!< 0x00000008 */ +#define USB_OTG_DOEPMSK_STUPM USB_OTG_DOEPMSK_STUPM_Msk /*!< SETUP phase done mask */ +#define USB_OTG_DOEPMSK_OTEPDM_Pos (4U) +#define USB_OTG_DOEPMSK_OTEPDM_Msk (0x1UL << USB_OTG_DOEPMSK_OTEPDM_Pos) /*!< 0x00000010 */ +#define USB_OTG_DOEPMSK_OTEPDM USB_OTG_DOEPMSK_OTEPDM_Msk /*!< OUT token received when endpoint disabled mask */ +#define USB_OTG_DOEPMSK_OTEPSPRM_Pos (5U) +#define USB_OTG_DOEPMSK_OTEPSPRM_Msk (0x1UL << USB_OTG_DOEPMSK_OTEPSPRM_Pos) /*!< 0x00000020 */ +#define USB_OTG_DOEPMSK_OTEPSPRM USB_OTG_DOEPMSK_OTEPSPRM_Msk /*!< Status Phase Received mask */ +#define USB_OTG_DOEPMSK_B2BSTUP_Pos (6U) +#define USB_OTG_DOEPMSK_B2BSTUP_Msk (0x1UL << USB_OTG_DOEPMSK_B2BSTUP_Pos) /*!< 0x00000040 */ +#define USB_OTG_DOEPMSK_B2BSTUP USB_OTG_DOEPMSK_B2BSTUP_Msk /*!< Back-to-back SETUP packets received mask */ +#define USB_OTG_DOEPMSK_OPEM_Pos (8U) +#define USB_OTG_DOEPMSK_OPEM_Msk (0x1UL << USB_OTG_DOEPMSK_OPEM_Pos) /*!< 0x00000100 */ +#define USB_OTG_DOEPMSK_OPEM USB_OTG_DOEPMSK_OPEM_Msk /*!< OUT packet error mask */ +#define USB_OTG_DOEPMSK_BOIM_Pos (9U) +#define USB_OTG_DOEPMSK_BOIM_Msk (0x1UL << USB_OTG_DOEPMSK_BOIM_Pos) /*!< 0x00000200 */ +#define USB_OTG_DOEPMSK_BOIM USB_OTG_DOEPMSK_BOIM_Msk /*!< BNA interrupt mask */ +#define USB_OTG_DOEPMSK_BERRM_Pos (12U) +#define USB_OTG_DOEPMSK_BERRM_Msk (0x1UL << USB_OTG_DOEPMSK_BERRM_Pos) /*!< 0x00001000 */ +#define USB_OTG_DOEPMSK_BERRM USB_OTG_DOEPMSK_BERRM_Msk /*!< Babble error interrupt mask */ +#define USB_OTG_DOEPMSK_NAKM_Pos (13U) +#define USB_OTG_DOEPMSK_NAKM_Msk (0x1UL << USB_OTG_DOEPMSK_NAKM_Pos) /*!< 0x00002000 */ +#define USB_OTG_DOEPMSK_NAKM USB_OTG_DOEPMSK_NAKM_Msk /*!< OUT Packet NAK interrupt mask */ +#define USB_OTG_DOEPMSK_NYETM_Pos (14U) +#define USB_OTG_DOEPMSK_NYETM_Msk (0x1UL << USB_OTG_DOEPMSK_NYETM_Pos) /*!< 0x00004000 */ +#define USB_OTG_DOEPMSK_NYETM USB_OTG_DOEPMSK_NYETM_Msk /*!< NYET interrupt mask */ +/******************** Bit definition for USB_OTG_GINTSTS register ********************/ +#define USB_OTG_GINTSTS_CMOD_Pos (0U) +#define USB_OTG_GINTSTS_CMOD_Msk (0x1UL << USB_OTG_GINTSTS_CMOD_Pos) /*!< 0x00000001 */ +#define USB_OTG_GINTSTS_CMOD USB_OTG_GINTSTS_CMOD_Msk /*!< Current mode of operation */ +#define USB_OTG_GINTSTS_MMIS_Pos (1U) +#define USB_OTG_GINTSTS_MMIS_Msk (0x1UL << USB_OTG_GINTSTS_MMIS_Pos) /*!< 0x00000002 */ +#define USB_OTG_GINTSTS_MMIS USB_OTG_GINTSTS_MMIS_Msk /*!< Mode mismatch interrupt */ +#define USB_OTG_GINTSTS_OTGINT_Pos (2U) +#define USB_OTG_GINTSTS_OTGINT_Msk (0x1UL << USB_OTG_GINTSTS_OTGINT_Pos) /*!< 0x00000004 */ +#define USB_OTG_GINTSTS_OTGINT USB_OTG_GINTSTS_OTGINT_Msk /*!< OTG interrupt */ +#define USB_OTG_GINTSTS_SOF_Pos (3U) +#define USB_OTG_GINTSTS_SOF_Msk (0x1UL << USB_OTG_GINTSTS_SOF_Pos) /*!< 0x00000008 */ +#define USB_OTG_GINTSTS_SOF USB_OTG_GINTSTS_SOF_Msk /*!< Start of frame */ +#define USB_OTG_GINTSTS_RXFLVL_Pos (4U) +#define USB_OTG_GINTSTS_RXFLVL_Msk (0x1UL << USB_OTG_GINTSTS_RXFLVL_Pos) /*!< 0x00000010 */ +#define USB_OTG_GINTSTS_RXFLVL USB_OTG_GINTSTS_RXFLVL_Msk /*!< RxFIFO nonempty */ +#define USB_OTG_GINTSTS_NPTXFE_Pos (5U) +#define USB_OTG_GINTSTS_NPTXFE_Msk (0x1UL << USB_OTG_GINTSTS_NPTXFE_Pos) /*!< 0x00000020 */ +#define USB_OTG_GINTSTS_NPTXFE USB_OTG_GINTSTS_NPTXFE_Msk /*!< Nonperiodic TxFIFO empty */ +#define USB_OTG_GINTSTS_GINAKEFF_Pos (6U) +#define USB_OTG_GINTSTS_GINAKEFF_Msk (0x1UL << USB_OTG_GINTSTS_GINAKEFF_Pos) /*!< 0x00000040 */ +#define USB_OTG_GINTSTS_GINAKEFF USB_OTG_GINTSTS_GINAKEFF_Msk /*!< Global IN nonperiodic NAK effective */ +#define USB_OTG_GINTSTS_BOUTNAKEFF_Pos (7U) +#define USB_OTG_GINTSTS_BOUTNAKEFF_Msk (0x1UL << USB_OTG_GINTSTS_BOUTNAKEFF_Pos) /*!< 0x00000080 */ +#define USB_OTG_GINTSTS_BOUTNAKEFF USB_OTG_GINTSTS_BOUTNAKEFF_Msk /*!< Global OUT NAK effective */ +#define USB_OTG_GINTSTS_ESUSP_Pos (10U) +#define USB_OTG_GINTSTS_ESUSP_Msk (0x1UL << USB_OTG_GINTSTS_ESUSP_Pos) /*!< 0x00000400 */ +#define USB_OTG_GINTSTS_ESUSP USB_OTG_GINTSTS_ESUSP_Msk /*!< Early suspend */ +#define USB_OTG_GINTSTS_USBSUSP_Pos (11U) +#define USB_OTG_GINTSTS_USBSUSP_Msk (0x1UL << USB_OTG_GINTSTS_USBSUSP_Pos) /*!< 0x00000800 */ +#define USB_OTG_GINTSTS_USBSUSP USB_OTG_GINTSTS_USBSUSP_Msk /*!< USB suspend */ +#define USB_OTG_GINTSTS_USBRST_Pos (12U) +#define USB_OTG_GINTSTS_USBRST_Msk (0x1UL << USB_OTG_GINTSTS_USBRST_Pos) /*!< 0x00001000 */ +#define USB_OTG_GINTSTS_USBRST USB_OTG_GINTSTS_USBRST_Msk /*!< USB reset */ +#define USB_OTG_GINTSTS_ENUMDNE_Pos (13U) +#define USB_OTG_GINTSTS_ENUMDNE_Msk (0x1UL << USB_OTG_GINTSTS_ENUMDNE_Pos) /*!< 0x00002000 */ +#define USB_OTG_GINTSTS_ENUMDNE USB_OTG_GINTSTS_ENUMDNE_Msk /*!< Enumeration done */ +#define USB_OTG_GINTSTS_ISOODRP_Pos (14U) +#define USB_OTG_GINTSTS_ISOODRP_Msk (0x1UL << USB_OTG_GINTSTS_ISOODRP_Pos) /*!< 0x00004000 */ +#define USB_OTG_GINTSTS_ISOODRP USB_OTG_GINTSTS_ISOODRP_Msk /*!< Isochronous OUT packet dropped interrupt */ +#define USB_OTG_GINTSTS_EOPF_Pos (15U) +#define USB_OTG_GINTSTS_EOPF_Msk (0x1UL << USB_OTG_GINTSTS_EOPF_Pos) /*!< 0x00008000 */ +#define USB_OTG_GINTSTS_EOPF USB_OTG_GINTSTS_EOPF_Msk /*!< End of periodic frame interrupt */ +#define USB_OTG_GINTSTS_IEPINT_Pos (18U) +#define USB_OTG_GINTSTS_IEPINT_Msk (0x1UL << USB_OTG_GINTSTS_IEPINT_Pos) /*!< 0x00040000 */ +#define USB_OTG_GINTSTS_IEPINT USB_OTG_GINTSTS_IEPINT_Msk /*!< IN endpoint interrupt */ +#define USB_OTG_GINTSTS_OEPINT_Pos (19U) +#define USB_OTG_GINTSTS_OEPINT_Msk (0x1UL << USB_OTG_GINTSTS_OEPINT_Pos) /*!< 0x00080000 */ +#define USB_OTG_GINTSTS_OEPINT USB_OTG_GINTSTS_OEPINT_Msk /*!< OUT endpoint interrupt */ +#define USB_OTG_GINTSTS_IISOIXFR_Pos (20U) +#define USB_OTG_GINTSTS_IISOIXFR_Msk (0x1UL << USB_OTG_GINTSTS_IISOIXFR_Pos) /*!< 0x00100000 */ +#define USB_OTG_GINTSTS_IISOIXFR USB_OTG_GINTSTS_IISOIXFR_Msk /*!< Incomplete isochronous IN transfer */ +#define USB_OTG_GINTSTS_PXFR_INCOMPISOOUT_Pos (21U) +#define USB_OTG_GINTSTS_PXFR_INCOMPISOOUT_Msk (0x1UL << USB_OTG_GINTSTS_PXFR_INCOMPISOOUT_Pos) /*!< 0x00200000 */ +#define USB_OTG_GINTSTS_PXFR_INCOMPISOOUT USB_OTG_GINTSTS_PXFR_INCOMPISOOUT_Msk /*!< Incomplete periodic transfer */ +#define USB_OTG_GINTSTS_DATAFSUSP_Pos (22U) +#define USB_OTG_GINTSTS_DATAFSUSP_Msk (0x1UL << USB_OTG_GINTSTS_DATAFSUSP_Pos) /*!< 0x00400000 */ +#define USB_OTG_GINTSTS_DATAFSUSP USB_OTG_GINTSTS_DATAFSUSP_Msk /*!< Data fetch suspended */ +#define USB_OTG_GINTSTS_HPRTINT_Pos (24U) +#define USB_OTG_GINTSTS_HPRTINT_Msk (0x1UL << USB_OTG_GINTSTS_HPRTINT_Pos) /*!< 0x01000000 */ +#define USB_OTG_GINTSTS_HPRTINT USB_OTG_GINTSTS_HPRTINT_Msk /*!< Host port interrupt */ +#define USB_OTG_GINTSTS_HCINT_Pos (25U) +#define USB_OTG_GINTSTS_HCINT_Msk (0x1UL << USB_OTG_GINTSTS_HCINT_Pos) /*!< 0x02000000 */ +#define USB_OTG_GINTSTS_HCINT USB_OTG_GINTSTS_HCINT_Msk /*!< Host channels interrupt */ +#define USB_OTG_GINTSTS_PTXFE_Pos (26U) +#define USB_OTG_GINTSTS_PTXFE_Msk (0x1UL << USB_OTG_GINTSTS_PTXFE_Pos) /*!< 0x04000000 */ +#define USB_OTG_GINTSTS_PTXFE USB_OTG_GINTSTS_PTXFE_Msk /*!< Periodic TxFIFO empty */ +#define USB_OTG_GINTSTS_CIDSCHG_Pos (28U) +#define USB_OTG_GINTSTS_CIDSCHG_Msk (0x1UL << USB_OTG_GINTSTS_CIDSCHG_Pos) /*!< 0x10000000 */ +#define USB_OTG_GINTSTS_CIDSCHG USB_OTG_GINTSTS_CIDSCHG_Msk /*!< Connector ID status change */ +#define USB_OTG_GINTSTS_DISCINT_Pos (29U) +#define USB_OTG_GINTSTS_DISCINT_Msk (0x1UL << USB_OTG_GINTSTS_DISCINT_Pos) /*!< 0x20000000 */ +#define USB_OTG_GINTSTS_DISCINT USB_OTG_GINTSTS_DISCINT_Msk /*!< Disconnect detected interrupt */ +#define USB_OTG_GINTSTS_SRQINT_Pos (30U) +#define USB_OTG_GINTSTS_SRQINT_Msk (0x1UL << USB_OTG_GINTSTS_SRQINT_Pos) /*!< 0x40000000 */ +#define USB_OTG_GINTSTS_SRQINT USB_OTG_GINTSTS_SRQINT_Msk /*!< Session request/new session detected interrupt */ +#define USB_OTG_GINTSTS_WKUINT_Pos (31U) +#define USB_OTG_GINTSTS_WKUINT_Msk (0x1UL << USB_OTG_GINTSTS_WKUINT_Pos) /*!< 0x80000000 */ +#define USB_OTG_GINTSTS_WKUINT USB_OTG_GINTSTS_WKUINT_Msk /*!< Resume/remote wakeup detected interrupt */ + +/******************** Bit definition for USB_OTG_GINTMSK register ********************/ +#define USB_OTG_GINTMSK_MMISM_Pos (1U) +#define USB_OTG_GINTMSK_MMISM_Msk (0x1UL << USB_OTG_GINTMSK_MMISM_Pos) /*!< 0x00000002 */ +#define USB_OTG_GINTMSK_MMISM USB_OTG_GINTMSK_MMISM_Msk /*!< Mode mismatch interrupt mask */ +#define USB_OTG_GINTMSK_OTGINT_Pos (2U) +#define USB_OTG_GINTMSK_OTGINT_Msk (0x1UL << USB_OTG_GINTMSK_OTGINT_Pos) /*!< 0x00000004 */ +#define USB_OTG_GINTMSK_OTGINT USB_OTG_GINTMSK_OTGINT_Msk /*!< OTG interrupt mask */ +#define USB_OTG_GINTMSK_SOFM_Pos (3U) +#define USB_OTG_GINTMSK_SOFM_Msk (0x1UL << USB_OTG_GINTMSK_SOFM_Pos) /*!< 0x00000008 */ +#define USB_OTG_GINTMSK_SOFM USB_OTG_GINTMSK_SOFM_Msk /*!< Start of frame mask */ +#define USB_OTG_GINTMSK_RXFLVLM_Pos (4U) +#define USB_OTG_GINTMSK_RXFLVLM_Msk (0x1UL << USB_OTG_GINTMSK_RXFLVLM_Pos) /*!< 0x00000010 */ +#define USB_OTG_GINTMSK_RXFLVLM USB_OTG_GINTMSK_RXFLVLM_Msk /*!< Receive FIFO nonempty mask */ +#define USB_OTG_GINTMSK_NPTXFEM_Pos (5U) +#define USB_OTG_GINTMSK_NPTXFEM_Msk (0x1UL << USB_OTG_GINTMSK_NPTXFEM_Pos) /*!< 0x00000020 */ +#define USB_OTG_GINTMSK_NPTXFEM USB_OTG_GINTMSK_NPTXFEM_Msk /*!< Nonperiodic TxFIFO empty mask */ +#define USB_OTG_GINTMSK_GINAKEFFM_Pos (6U) +#define USB_OTG_GINTMSK_GINAKEFFM_Msk (0x1UL << USB_OTG_GINTMSK_GINAKEFFM_Pos) /*!< 0x00000040 */ +#define USB_OTG_GINTMSK_GINAKEFFM USB_OTG_GINTMSK_GINAKEFFM_Msk /*!< Global nonperiodic IN NAK effective mask */ +#define USB_OTG_GINTMSK_GONAKEFFM_Pos (7U) +#define USB_OTG_GINTMSK_GONAKEFFM_Msk (0x1UL << USB_OTG_GINTMSK_GONAKEFFM_Pos) /*!< 0x00000080 */ +#define USB_OTG_GINTMSK_GONAKEFFM USB_OTG_GINTMSK_GONAKEFFM_Msk /*!< Global OUT NAK effective mask */ +#define USB_OTG_GINTMSK_ESUSPM_Pos (10U) +#define USB_OTG_GINTMSK_ESUSPM_Msk (0x1UL << USB_OTG_GINTMSK_ESUSPM_Pos) /*!< 0x00000400 */ +#define USB_OTG_GINTMSK_ESUSPM USB_OTG_GINTMSK_ESUSPM_Msk /*!< Early suspend mask */ +#define USB_OTG_GINTMSK_USBSUSPM_Pos (11U) +#define USB_OTG_GINTMSK_USBSUSPM_Msk (0x1UL << USB_OTG_GINTMSK_USBSUSPM_Pos) /*!< 0x00000800 */ +#define USB_OTG_GINTMSK_USBSUSPM USB_OTG_GINTMSK_USBSUSPM_Msk /*!< USB suspend mask */ +#define USB_OTG_GINTMSK_USBRST_Pos (12U) +#define USB_OTG_GINTMSK_USBRST_Msk (0x1UL << USB_OTG_GINTMSK_USBRST_Pos) /*!< 0x00001000 */ +#define USB_OTG_GINTMSK_USBRST USB_OTG_GINTMSK_USBRST_Msk /*!< USB reset mask */ +#define USB_OTG_GINTMSK_ENUMDNEM_Pos (13U) +#define USB_OTG_GINTMSK_ENUMDNEM_Msk (0x1UL << USB_OTG_GINTMSK_ENUMDNEM_Pos) /*!< 0x00002000 */ +#define USB_OTG_GINTMSK_ENUMDNEM USB_OTG_GINTMSK_ENUMDNEM_Msk /*!< Enumeration done mask */ +#define USB_OTG_GINTMSK_ISOODRPM_Pos (14U) +#define USB_OTG_GINTMSK_ISOODRPM_Msk (0x1UL << USB_OTG_GINTMSK_ISOODRPM_Pos) /*!< 0x00004000 */ +#define USB_OTG_GINTMSK_ISOODRPM USB_OTG_GINTMSK_ISOODRPM_Msk /*!< Isochronous OUT packet dropped interrupt mask */ +#define USB_OTG_GINTMSK_EOPFM_Pos (15U) +#define USB_OTG_GINTMSK_EOPFM_Msk (0x1UL << USB_OTG_GINTMSK_EOPFM_Pos) /*!< 0x00008000 */ +#define USB_OTG_GINTMSK_EOPFM USB_OTG_GINTMSK_EOPFM_Msk /*!< End of periodic frame interrupt mask */ +#define USB_OTG_GINTMSK_EPMISM_Pos (17U) +#define USB_OTG_GINTMSK_EPMISM_Msk (0x1UL << USB_OTG_GINTMSK_EPMISM_Pos) /*!< 0x00020000 */ +#define USB_OTG_GINTMSK_EPMISM USB_OTG_GINTMSK_EPMISM_Msk /*!< Endpoint mismatch interrupt mask */ +#define USB_OTG_GINTMSK_IEPINT_Pos (18U) +#define USB_OTG_GINTMSK_IEPINT_Msk (0x1UL << USB_OTG_GINTMSK_IEPINT_Pos) /*!< 0x00040000 */ +#define USB_OTG_GINTMSK_IEPINT USB_OTG_GINTMSK_IEPINT_Msk /*!< IN endpoints interrupt mask */ +#define USB_OTG_GINTMSK_OEPINT_Pos (19U) +#define USB_OTG_GINTMSK_OEPINT_Msk (0x1UL << USB_OTG_GINTMSK_OEPINT_Pos) /*!< 0x00080000 */ +#define USB_OTG_GINTMSK_OEPINT USB_OTG_GINTMSK_OEPINT_Msk /*!< OUT endpoints interrupt mask */ +#define USB_OTG_GINTMSK_IISOIXFRM_Pos (20U) +#define USB_OTG_GINTMSK_IISOIXFRM_Msk (0x1UL << USB_OTG_GINTMSK_IISOIXFRM_Pos) /*!< 0x00100000 */ +#define USB_OTG_GINTMSK_IISOIXFRM USB_OTG_GINTMSK_IISOIXFRM_Msk /*!< Incomplete isochronous IN transfer mask */ +#define USB_OTG_GINTMSK_PXFRM_IISOOXFRM_Pos (21U) +#define USB_OTG_GINTMSK_PXFRM_IISOOXFRM_Msk (0x1UL << USB_OTG_GINTMSK_PXFRM_IISOOXFRM_Pos) /*!< 0x00200000 */ +#define USB_OTG_GINTMSK_PXFRM_IISOOXFRM USB_OTG_GINTMSK_PXFRM_IISOOXFRM_Msk /*!< Incomplete periodic transfer mask */ +#define USB_OTG_GINTMSK_FSUSPM_Pos (22U) +#define USB_OTG_GINTMSK_FSUSPM_Msk (0x1UL << USB_OTG_GINTMSK_FSUSPM_Pos) /*!< 0x00400000 */ +#define USB_OTG_GINTMSK_FSUSPM USB_OTG_GINTMSK_FSUSPM_Msk /*!< Data fetch suspended mask */ +#define USB_OTG_GINTMSK_PRTIM_Pos (24U) +#define USB_OTG_GINTMSK_PRTIM_Msk (0x1UL << USB_OTG_GINTMSK_PRTIM_Pos) /*!< 0x01000000 */ +#define USB_OTG_GINTMSK_PRTIM USB_OTG_GINTMSK_PRTIM_Msk /*!< Host port interrupt mask */ +#define USB_OTG_GINTMSK_HCIM_Pos (25U) +#define USB_OTG_GINTMSK_HCIM_Msk (0x1UL << USB_OTG_GINTMSK_HCIM_Pos) /*!< 0x02000000 */ +#define USB_OTG_GINTMSK_HCIM USB_OTG_GINTMSK_HCIM_Msk /*!< Host channels interrupt mask */ +#define USB_OTG_GINTMSK_PTXFEM_Pos (26U) +#define USB_OTG_GINTMSK_PTXFEM_Msk (0x1UL << USB_OTG_GINTMSK_PTXFEM_Pos) /*!< 0x04000000 */ +#define USB_OTG_GINTMSK_PTXFEM USB_OTG_GINTMSK_PTXFEM_Msk /*!< Periodic TxFIFO empty mask */ +#define USB_OTG_GINTMSK_CIDSCHGM_Pos (28U) +#define USB_OTG_GINTMSK_CIDSCHGM_Msk (0x1UL << USB_OTG_GINTMSK_CIDSCHGM_Pos) /*!< 0x10000000 */ +#define USB_OTG_GINTMSK_CIDSCHGM USB_OTG_GINTMSK_CIDSCHGM_Msk /*!< Connector ID status change mask */ +#define USB_OTG_GINTMSK_DISCINT_Pos (29U) +#define USB_OTG_GINTMSK_DISCINT_Msk (0x1UL << USB_OTG_GINTMSK_DISCINT_Pos) /*!< 0x20000000 */ +#define USB_OTG_GINTMSK_DISCINT USB_OTG_GINTMSK_DISCINT_Msk /*!< Disconnect detected interrupt mask */ +#define USB_OTG_GINTMSK_SRQIM_Pos (30U) +#define USB_OTG_GINTMSK_SRQIM_Msk (0x1UL << USB_OTG_GINTMSK_SRQIM_Pos) /*!< 0x40000000 */ +#define USB_OTG_GINTMSK_SRQIM USB_OTG_GINTMSK_SRQIM_Msk /*!< Session request/new session detected interrupt mask */ +#define USB_OTG_GINTMSK_WUIM_Pos (31U) +#define USB_OTG_GINTMSK_WUIM_Msk (0x1UL << USB_OTG_GINTMSK_WUIM_Pos) /*!< 0x80000000 */ +#define USB_OTG_GINTMSK_WUIM USB_OTG_GINTMSK_WUIM_Msk /*!< Resume/remote wakeup detected interrupt mask */ + +/******************** Bit definition for USB_OTG_DAINT register ********************/ +#define USB_OTG_DAINT_IEPINT_Pos (0U) +#define USB_OTG_DAINT_IEPINT_Msk (0xFFFFUL << USB_OTG_DAINT_IEPINT_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_DAINT_IEPINT USB_OTG_DAINT_IEPINT_Msk /*!< IN endpoint interrupt bits */ +#define USB_OTG_DAINT_OEPINT_Pos (16U) +#define USB_OTG_DAINT_OEPINT_Msk (0xFFFFUL << USB_OTG_DAINT_OEPINT_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_DAINT_OEPINT USB_OTG_DAINT_OEPINT_Msk /*!< OUT endpoint interrupt bits */ + +/******************** Bit definition for USB_OTG_HAINTMSK register ********************/ +#define USB_OTG_HAINTMSK_HAINTM_Pos (0U) +#define USB_OTG_HAINTMSK_HAINTM_Msk (0xFFFFUL << USB_OTG_HAINTMSK_HAINTM_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_HAINTMSK_HAINTM USB_OTG_HAINTMSK_HAINTM_Msk /*!< Channel interrupt mask */ + +/******************** Bit definition for USB_OTG_GRXSTSP register ********************/ +#define USB_OTG_GRXSTSP_EPNUM_Pos (0U) +#define USB_OTG_GRXSTSP_EPNUM_Msk (0xFUL << USB_OTG_GRXSTSP_EPNUM_Pos) /*!< 0x0000000F */ +#define USB_OTG_GRXSTSP_EPNUM USB_OTG_GRXSTSP_EPNUM_Msk /*!< IN EP interrupt mask bits */ +#define USB_OTG_GRXSTSP_BCNT_Pos (4U) +#define USB_OTG_GRXSTSP_BCNT_Msk (0x7FFUL << USB_OTG_GRXSTSP_BCNT_Pos) /*!< 0x00007FF0 */ +#define USB_OTG_GRXSTSP_BCNT USB_OTG_GRXSTSP_BCNT_Msk /*!< OUT EP interrupt mask bits */ +#define USB_OTG_GRXSTSP_DPID_Pos (15U) +#define USB_OTG_GRXSTSP_DPID_Msk (0x3UL << USB_OTG_GRXSTSP_DPID_Pos) /*!< 0x00018000 */ +#define USB_OTG_GRXSTSP_DPID USB_OTG_GRXSTSP_DPID_Msk /*!< OUT EP interrupt mask bits */ +#define USB_OTG_GRXSTSP_PKTSTS_Pos (17U) +#define USB_OTG_GRXSTSP_PKTSTS_Msk (0xFUL << USB_OTG_GRXSTSP_PKTSTS_Pos) /*!< 0x001E0000 */ +#define USB_OTG_GRXSTSP_PKTSTS USB_OTG_GRXSTSP_PKTSTS_Msk /*!< OUT EP interrupt mask bits */ + +/******************** Bit definition for USB_OTG_DAINTMSK register ********************/ +#define USB_OTG_DAINTMSK_IEPM_Pos (0U) +#define USB_OTG_DAINTMSK_IEPM_Msk (0xFFFFUL << USB_OTG_DAINTMSK_IEPM_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_DAINTMSK_IEPM USB_OTG_DAINTMSK_IEPM_Msk /*!< IN EP interrupt mask bits */ +#define USB_OTG_DAINTMSK_OEPM_Pos (16U) +#define USB_OTG_DAINTMSK_OEPM_Msk (0xFFFFUL << USB_OTG_DAINTMSK_OEPM_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_DAINTMSK_OEPM USB_OTG_DAINTMSK_OEPM_Msk /*!< OUT EP interrupt mask bits */ + +/******************** Bit definition for USB_OTG_GRXFSIZ register ********************/ +#define USB_OTG_GRXFSIZ_RXFD_Pos (0U) +#define USB_OTG_GRXFSIZ_RXFD_Msk (0xFFFFUL << USB_OTG_GRXFSIZ_RXFD_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_GRXFSIZ_RXFD USB_OTG_GRXFSIZ_RXFD_Msk /*!< RxFIFO depth */ + +/******************** Bit definition for USB_OTG_DVBUSDIS register ********************/ +#define USB_OTG_DVBUSDIS_VBUSDT_Pos (0U) +#define USB_OTG_DVBUSDIS_VBUSDT_Msk (0xFFFFUL << USB_OTG_DVBUSDIS_VBUSDT_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_DVBUSDIS_VBUSDT USB_OTG_DVBUSDIS_VBUSDT_Msk /*!< Device VBUS discharge time */ + +/******************** Bit definition for OTG register ********************/ +#define USB_OTG_NPTXFSA_Pos (0U) +#define USB_OTG_NPTXFSA_Msk (0xFFFFUL << USB_OTG_NPTXFSA_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_NPTXFSA USB_OTG_NPTXFSA_Msk /*!< Nonperiodic transmit RAM start address */ +#define USB_OTG_NPTXFD_Pos (16U) +#define USB_OTG_NPTXFD_Msk (0xFFFFUL << USB_OTG_NPTXFD_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_NPTXFD USB_OTG_NPTXFD_Msk /*!< Nonperiodic TxFIFO depth */ +#define USB_OTG_TX0FSA_Pos (0U) +#define USB_OTG_TX0FSA_Msk (0xFFFFUL << USB_OTG_TX0FSA_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_TX0FSA USB_OTG_TX0FSA_Msk /*!< Endpoint 0 transmit RAM start address */ +#define USB_OTG_TX0FD_Pos (16U) +#define USB_OTG_TX0FD_Msk (0xFFFFUL << USB_OTG_TX0FD_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_TX0FD USB_OTG_TX0FD_Msk /*!< Endpoint 0 TxFIFO depth */ + +/******************** Bit definition for USB_OTG_DVBUSPULSE register ********************/ +#define USB_OTG_DVBUSPULSE_DVBUSP_Pos (0U) +#define USB_OTG_DVBUSPULSE_DVBUSP_Msk (0xFFFUL << USB_OTG_DVBUSPULSE_DVBUSP_Pos) /*!< 0x00000FFF */ +#define USB_OTG_DVBUSPULSE_DVBUSP USB_OTG_DVBUSPULSE_DVBUSP_Msk /*!< Device VBUS pulsing time */ + +/******************** Bit definition for USB_OTG_GNPTXSTS register ********************/ +#define USB_OTG_GNPTXSTS_NPTXFSAV_Pos (0U) +#define USB_OTG_GNPTXSTS_NPTXFSAV_Msk (0xFFFFUL << USB_OTG_GNPTXSTS_NPTXFSAV_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_GNPTXSTS_NPTXFSAV USB_OTG_GNPTXSTS_NPTXFSAV_Msk /*!< Nonperiodic TxFIFO space available */ + +#define USB_OTG_GNPTXSTS_NPTQXSAV_Pos (16U) +#define USB_OTG_GNPTXSTS_NPTQXSAV_Msk (0xFFUL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00FF0000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV USB_OTG_GNPTXSTS_NPTQXSAV_Msk /*!< Nonperiodic transmit request queue space available */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_0 (0x01UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00010000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_1 (0x02UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00020000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_2 (0x04UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00040000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_3 (0x08UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00080000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_4 (0x10UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00100000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_5 (0x20UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00200000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_6 (0x40UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00400000 */ +#define USB_OTG_GNPTXSTS_NPTQXSAV_7 (0x80UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00800000 */ + +#define USB_OTG_GNPTXSTS_NPTXQTOP_Pos (24U) +#define USB_OTG_GNPTXSTS_NPTXQTOP_Msk (0x7FUL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x7F000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP USB_OTG_GNPTXSTS_NPTXQTOP_Msk /*!< Top of the nonperiodic transmit request queue */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_0 (0x01UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x01000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_1 (0x02UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x02000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_2 (0x04UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x04000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_3 (0x08UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x08000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_4 (0x10UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x10000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_5 (0x20UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x20000000 */ +#define USB_OTG_GNPTXSTS_NPTXQTOP_6 (0x40UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x40000000 */ + +/******************** Bit definition for USB_OTG_DTHRCTL register ********************/ +#define USB_OTG_DTHRCTL_NONISOTHREN_Pos (0U) +#define USB_OTG_DTHRCTL_NONISOTHREN_Msk (0x1UL << USB_OTG_DTHRCTL_NONISOTHREN_Pos) /*!< 0x00000001 */ +#define USB_OTG_DTHRCTL_NONISOTHREN USB_OTG_DTHRCTL_NONISOTHREN_Msk /*!< Nonisochronous IN endpoints threshold enable */ +#define USB_OTG_DTHRCTL_ISOTHREN_Pos (1U) +#define USB_OTG_DTHRCTL_ISOTHREN_Msk (0x1UL << USB_OTG_DTHRCTL_ISOTHREN_Pos) /*!< 0x00000002 */ +#define USB_OTG_DTHRCTL_ISOTHREN USB_OTG_DTHRCTL_ISOTHREN_Msk /*!< ISO IN endpoint threshold enable */ + +#define USB_OTG_DTHRCTL_TXTHRLEN_Pos (2U) +#define USB_OTG_DTHRCTL_TXTHRLEN_Msk (0x1FFUL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x000007FC */ +#define USB_OTG_DTHRCTL_TXTHRLEN USB_OTG_DTHRCTL_TXTHRLEN_Msk /*!< Transmit threshold length */ +#define USB_OTG_DTHRCTL_TXTHRLEN_0 (0x001UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000004 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_1 (0x002UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000008 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_2 (0x004UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000010 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_3 (0x008UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000020 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_4 (0x010UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000040 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_5 (0x020UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000080 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_6 (0x040UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000100 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_7 (0x080UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000200 */ +#define USB_OTG_DTHRCTL_TXTHRLEN_8 (0x100UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000400 */ +#define USB_OTG_DTHRCTL_RXTHREN_Pos (16U) +#define USB_OTG_DTHRCTL_RXTHREN_Msk (0x1UL << USB_OTG_DTHRCTL_RXTHREN_Pos) /*!< 0x00010000 */ +#define USB_OTG_DTHRCTL_RXTHREN USB_OTG_DTHRCTL_RXTHREN_Msk /*!< Receive threshold enable */ + +#define USB_OTG_DTHRCTL_RXTHRLEN_Pos (17U) +#define USB_OTG_DTHRCTL_RXTHRLEN_Msk (0x1FFUL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x03FE0000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN USB_OTG_DTHRCTL_RXTHRLEN_Msk /*!< Receive threshold length */ +#define USB_OTG_DTHRCTL_RXTHRLEN_0 (0x001UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00020000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_1 (0x002UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00040000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_2 (0x004UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00080000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_3 (0x008UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00100000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_4 (0x010UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00200000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_5 (0x020UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00400000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_6 (0x040UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00800000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_7 (0x080UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x01000000 */ +#define USB_OTG_DTHRCTL_RXTHRLEN_8 (0x100UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x02000000 */ +#define USB_OTG_DTHRCTL_ARPEN_Pos (27U) +#define USB_OTG_DTHRCTL_ARPEN_Msk (0x1UL << USB_OTG_DTHRCTL_ARPEN_Pos) /*!< 0x08000000 */ +#define USB_OTG_DTHRCTL_ARPEN USB_OTG_DTHRCTL_ARPEN_Msk /*!< Arbiter parking enable */ + +/******************** Bit definition for USB_OTG_DIEPEMPMSK register ********************/ +#define USB_OTG_DIEPEMPMSK_INEPTXFEM_Pos (0U) +#define USB_OTG_DIEPEMPMSK_INEPTXFEM_Msk (0xFFFFUL << USB_OTG_DIEPEMPMSK_INEPTXFEM_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_DIEPEMPMSK_INEPTXFEM USB_OTG_DIEPEMPMSK_INEPTXFEM_Msk /*!< IN EP Tx FIFO empty interrupt mask bits */ + +/******************** Bit definition for USB_OTG_DEACHINT register ********************/ +#define USB_OTG_DEACHINT_IEP1INT_Pos (1U) +#define USB_OTG_DEACHINT_IEP1INT_Msk (0x1UL << USB_OTG_DEACHINT_IEP1INT_Pos) /*!< 0x00000002 */ +#define USB_OTG_DEACHINT_IEP1INT USB_OTG_DEACHINT_IEP1INT_Msk /*!< IN endpoint 1interrupt bit */ +#define USB_OTG_DEACHINT_OEP1INT_Pos (17U) +#define USB_OTG_DEACHINT_OEP1INT_Msk (0x1UL << USB_OTG_DEACHINT_OEP1INT_Pos) /*!< 0x00020000 */ +#define USB_OTG_DEACHINT_OEP1INT USB_OTG_DEACHINT_OEP1INT_Msk /*!< OUT endpoint 1 interrupt bit */ + +/******************** Bit definition for USB_OTG_GCCFG register ********************/ +#define USB_OTG_GCCFG_PWRDWN_Pos (16U) +#define USB_OTG_GCCFG_PWRDWN_Msk (0x1UL << USB_OTG_GCCFG_PWRDWN_Pos) /*!< 0x00010000 */ +#define USB_OTG_GCCFG_PWRDWN USB_OTG_GCCFG_PWRDWN_Msk /*!< Power down */ +#define USB_OTG_GCCFG_VBUSASEN_Pos (18U) +#define USB_OTG_GCCFG_VBUSASEN_Msk (0x1UL << USB_OTG_GCCFG_VBUSASEN_Pos) /*!< 0x00040000 */ +#define USB_OTG_GCCFG_VBUSASEN USB_OTG_GCCFG_VBUSASEN_Msk /*!< Enable the VBUS sensing device */ +#define USB_OTG_GCCFG_VBUSBSEN_Pos (19U) +#define USB_OTG_GCCFG_VBUSBSEN_Msk (0x1UL << USB_OTG_GCCFG_VBUSBSEN_Pos) /*!< 0x00080000 */ +#define USB_OTG_GCCFG_VBUSBSEN USB_OTG_GCCFG_VBUSBSEN_Msk /*!< Enable the VBUS sensing device */ +#define USB_OTG_GCCFG_SOFOUTEN_Pos (20U) +#define USB_OTG_GCCFG_SOFOUTEN_Msk (0x1UL << USB_OTG_GCCFG_SOFOUTEN_Pos) /*!< 0x00100000 */ +#define USB_OTG_GCCFG_SOFOUTEN USB_OTG_GCCFG_SOFOUTEN_Msk /*!< SOF output enable */ + +/******************** Bit definition for USB_OTG_DEACHINTMSK register ********************/ +#define USB_OTG_DEACHINTMSK_IEP1INTM_Pos (1U) +#define USB_OTG_DEACHINTMSK_IEP1INTM_Msk (0x1UL << USB_OTG_DEACHINTMSK_IEP1INTM_Pos) /*!< 0x00000002 */ +#define USB_OTG_DEACHINTMSK_IEP1INTM USB_OTG_DEACHINTMSK_IEP1INTM_Msk /*!< IN Endpoint 1 interrupt mask bit */ +#define USB_OTG_DEACHINTMSK_OEP1INTM_Pos (17U) +#define USB_OTG_DEACHINTMSK_OEP1INTM_Msk (0x1UL << USB_OTG_DEACHINTMSK_OEP1INTM_Pos) /*!< 0x00020000 */ +#define USB_OTG_DEACHINTMSK_OEP1INTM USB_OTG_DEACHINTMSK_OEP1INTM_Msk /*!< OUT Endpoint 1 interrupt mask bit */ + +/******************** Bit definition for USB_OTG_CID register ********************/ +#define USB_OTG_CID_PRODUCT_ID_Pos (0U) +#define USB_OTG_CID_PRODUCT_ID_Msk (0xFFFFFFFFUL << USB_OTG_CID_PRODUCT_ID_Pos) /*!< 0xFFFFFFFF */ +#define USB_OTG_CID_PRODUCT_ID USB_OTG_CID_PRODUCT_ID_Msk /*!< Product ID field */ + +/******************** Bit definition for USB_OTG_DIEPEACHMSK1 register ********************/ +#define USB_OTG_DIEPEACHMSK1_XFRCM_Pos (0U) +#define USB_OTG_DIEPEACHMSK1_XFRCM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ +#define USB_OTG_DIEPEACHMSK1_XFRCM USB_OTG_DIEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define USB_OTG_DIEPEACHMSK1_EPDM_Pos (1U) +#define USB_OTG_DIEPEACHMSK1_EPDM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ +#define USB_OTG_DIEPEACHMSK1_EPDM USB_OTG_DIEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define USB_OTG_DIEPEACHMSK1_TOM_Pos (3U) +#define USB_OTG_DIEPEACHMSK1_TOM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ +#define USB_OTG_DIEPEACHMSK1_TOM USB_OTG_DIEPEACHMSK1_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ +#define USB_OTG_DIEPEACHMSK1_ITTXFEMSK_Pos (4U) +#define USB_OTG_DIEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ +#define USB_OTG_DIEPEACHMSK1_ITTXFEMSK USB_OTG_DIEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define USB_OTG_DIEPEACHMSK1_INEPNMM_Pos (5U) +#define USB_OTG_DIEPEACHMSK1_INEPNMM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ +#define USB_OTG_DIEPEACHMSK1_INEPNMM USB_OTG_DIEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define USB_OTG_DIEPEACHMSK1_INEPNEM_Pos (6U) +#define USB_OTG_DIEPEACHMSK1_INEPNEM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ +#define USB_OTG_DIEPEACHMSK1_INEPNEM USB_OTG_DIEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define USB_OTG_DIEPEACHMSK1_TXFURM_Pos (8U) +#define USB_OTG_DIEPEACHMSK1_TXFURM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ +#define USB_OTG_DIEPEACHMSK1_TXFURM USB_OTG_DIEPEACHMSK1_TXFURM_Msk /*!< FIFO underrun mask */ +#define USB_OTG_DIEPEACHMSK1_BIM_Pos (9U) +#define USB_OTG_DIEPEACHMSK1_BIM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ +#define USB_OTG_DIEPEACHMSK1_BIM USB_OTG_DIEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ +#define USB_OTG_DIEPEACHMSK1_NAKM_Pos (13U) +#define USB_OTG_DIEPEACHMSK1_NAKM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ +#define USB_OTG_DIEPEACHMSK1_NAKM USB_OTG_DIEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ + +/******************** Bit definition for USB_OTG_HPRT register ********************/ +#define USB_OTG_HPRT_PCSTS_Pos (0U) +#define USB_OTG_HPRT_PCSTS_Msk (0x1UL << USB_OTG_HPRT_PCSTS_Pos) /*!< 0x00000001 */ +#define USB_OTG_HPRT_PCSTS USB_OTG_HPRT_PCSTS_Msk /*!< Port connect status */ +#define USB_OTG_HPRT_PCDET_Pos (1U) +#define USB_OTG_HPRT_PCDET_Msk (0x1UL << USB_OTG_HPRT_PCDET_Pos) /*!< 0x00000002 */ +#define USB_OTG_HPRT_PCDET USB_OTG_HPRT_PCDET_Msk /*!< Port connect detected */ +#define USB_OTG_HPRT_PENA_Pos (2U) +#define USB_OTG_HPRT_PENA_Msk (0x1UL << USB_OTG_HPRT_PENA_Pos) /*!< 0x00000004 */ +#define USB_OTG_HPRT_PENA USB_OTG_HPRT_PENA_Msk /*!< Port enable */ +#define USB_OTG_HPRT_PENCHNG_Pos (3U) +#define USB_OTG_HPRT_PENCHNG_Msk (0x1UL << USB_OTG_HPRT_PENCHNG_Pos) /*!< 0x00000008 */ +#define USB_OTG_HPRT_PENCHNG USB_OTG_HPRT_PENCHNG_Msk /*!< Port enable/disable change */ +#define USB_OTG_HPRT_POCA_Pos (4U) +#define USB_OTG_HPRT_POCA_Msk (0x1UL << USB_OTG_HPRT_POCA_Pos) /*!< 0x00000010 */ +#define USB_OTG_HPRT_POCA USB_OTG_HPRT_POCA_Msk /*!< Port overcurrent active */ +#define USB_OTG_HPRT_POCCHNG_Pos (5U) +#define USB_OTG_HPRT_POCCHNG_Msk (0x1UL << USB_OTG_HPRT_POCCHNG_Pos) /*!< 0x00000020 */ +#define USB_OTG_HPRT_POCCHNG USB_OTG_HPRT_POCCHNG_Msk /*!< Port overcurrent change */ +#define USB_OTG_HPRT_PRES_Pos (6U) +#define USB_OTG_HPRT_PRES_Msk (0x1UL << USB_OTG_HPRT_PRES_Pos) /*!< 0x00000040 */ +#define USB_OTG_HPRT_PRES USB_OTG_HPRT_PRES_Msk /*!< Port resume */ +#define USB_OTG_HPRT_PSUSP_Pos (7U) +#define USB_OTG_HPRT_PSUSP_Msk (0x1UL << USB_OTG_HPRT_PSUSP_Pos) /*!< 0x00000080 */ +#define USB_OTG_HPRT_PSUSP USB_OTG_HPRT_PSUSP_Msk /*!< Port suspend */ +#define USB_OTG_HPRT_PRST_Pos (8U) +#define USB_OTG_HPRT_PRST_Msk (0x1UL << USB_OTG_HPRT_PRST_Pos) /*!< 0x00000100 */ +#define USB_OTG_HPRT_PRST USB_OTG_HPRT_PRST_Msk /*!< Port reset */ + +#define USB_OTG_HPRT_PLSTS_Pos (10U) +#define USB_OTG_HPRT_PLSTS_Msk (0x3UL << USB_OTG_HPRT_PLSTS_Pos) /*!< 0x00000C00 */ +#define USB_OTG_HPRT_PLSTS USB_OTG_HPRT_PLSTS_Msk /*!< Port line status */ +#define USB_OTG_HPRT_PLSTS_0 (0x1UL << USB_OTG_HPRT_PLSTS_Pos) /*!< 0x00000400 */ +#define USB_OTG_HPRT_PLSTS_1 (0x2UL << USB_OTG_HPRT_PLSTS_Pos) /*!< 0x00000800 */ +#define USB_OTG_HPRT_PPWR_Pos (12U) +#define USB_OTG_HPRT_PPWR_Msk (0x1UL << USB_OTG_HPRT_PPWR_Pos) /*!< 0x00001000 */ +#define USB_OTG_HPRT_PPWR USB_OTG_HPRT_PPWR_Msk /*!< Port power */ + +#define USB_OTG_HPRT_PTCTL_Pos (13U) +#define USB_OTG_HPRT_PTCTL_Msk (0xFUL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x0001E000 */ +#define USB_OTG_HPRT_PTCTL USB_OTG_HPRT_PTCTL_Msk /*!< Port test control */ +#define USB_OTG_HPRT_PTCTL_0 (0x1UL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x00002000 */ +#define USB_OTG_HPRT_PTCTL_1 (0x2UL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x00004000 */ +#define USB_OTG_HPRT_PTCTL_2 (0x4UL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x00008000 */ +#define USB_OTG_HPRT_PTCTL_3 (0x8UL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x00010000 */ + +#define USB_OTG_HPRT_PSPD_Pos (17U) +#define USB_OTG_HPRT_PSPD_Msk (0x3UL << USB_OTG_HPRT_PSPD_Pos) /*!< 0x00060000 */ +#define USB_OTG_HPRT_PSPD USB_OTG_HPRT_PSPD_Msk /*!< Port speed */ +#define USB_OTG_HPRT_PSPD_0 (0x1UL << USB_OTG_HPRT_PSPD_Pos) /*!< 0x00020000 */ +#define USB_OTG_HPRT_PSPD_1 (0x2UL << USB_OTG_HPRT_PSPD_Pos) /*!< 0x00040000 */ + +/******************** Bit definition for USB_OTG_DOEPEACHMSK1 register ********************/ +#define USB_OTG_DOEPEACHMSK1_XFRCM_Pos (0U) +#define USB_OTG_DOEPEACHMSK1_XFRCM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ +#define USB_OTG_DOEPEACHMSK1_XFRCM USB_OTG_DOEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define USB_OTG_DOEPEACHMSK1_EPDM_Pos (1U) +#define USB_OTG_DOEPEACHMSK1_EPDM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ +#define USB_OTG_DOEPEACHMSK1_EPDM USB_OTG_DOEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define USB_OTG_DOEPEACHMSK1_TOM_Pos (3U) +#define USB_OTG_DOEPEACHMSK1_TOM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ +#define USB_OTG_DOEPEACHMSK1_TOM USB_OTG_DOEPEACHMSK1_TOM_Msk /*!< Timeout condition mask */ +#define USB_OTG_DOEPEACHMSK1_ITTXFEMSK_Pos (4U) +#define USB_OTG_DOEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ +#define USB_OTG_DOEPEACHMSK1_ITTXFEMSK USB_OTG_DOEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define USB_OTG_DOEPEACHMSK1_INEPNMM_Pos (5U) +#define USB_OTG_DOEPEACHMSK1_INEPNMM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ +#define USB_OTG_DOEPEACHMSK1_INEPNMM USB_OTG_DOEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define USB_OTG_DOEPEACHMSK1_INEPNEM_Pos (6U) +#define USB_OTG_DOEPEACHMSK1_INEPNEM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ +#define USB_OTG_DOEPEACHMSK1_INEPNEM USB_OTG_DOEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define USB_OTG_DOEPEACHMSK1_TXFURM_Pos (8U) +#define USB_OTG_DOEPEACHMSK1_TXFURM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ +#define USB_OTG_DOEPEACHMSK1_TXFURM USB_OTG_DOEPEACHMSK1_TXFURM_Msk /*!< OUT packet error mask */ +#define USB_OTG_DOEPEACHMSK1_BIM_Pos (9U) +#define USB_OTG_DOEPEACHMSK1_BIM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ +#define USB_OTG_DOEPEACHMSK1_BIM USB_OTG_DOEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ +#define USB_OTG_DOEPEACHMSK1_BERRM_Pos (12U) +#define USB_OTG_DOEPEACHMSK1_BERRM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_BERRM_Pos) /*!< 0x00001000 */ +#define USB_OTG_DOEPEACHMSK1_BERRM USB_OTG_DOEPEACHMSK1_BERRM_Msk /*!< Bubble error interrupt mask */ +#define USB_OTG_DOEPEACHMSK1_NAKM_Pos (13U) +#define USB_OTG_DOEPEACHMSK1_NAKM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ +#define USB_OTG_DOEPEACHMSK1_NAKM USB_OTG_DOEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ +#define USB_OTG_DOEPEACHMSK1_NYETM_Pos (14U) +#define USB_OTG_DOEPEACHMSK1_NYETM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_NYETM_Pos) /*!< 0x00004000 */ +#define USB_OTG_DOEPEACHMSK1_NYETM USB_OTG_DOEPEACHMSK1_NYETM_Msk /*!< NYET interrupt mask */ + +/******************** Bit definition for USB_OTG_HPTXFSIZ register ********************/ +#define USB_OTG_HPTXFSIZ_PTXSA_Pos (0U) +#define USB_OTG_HPTXFSIZ_PTXSA_Msk (0xFFFFUL << USB_OTG_HPTXFSIZ_PTXSA_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_HPTXFSIZ_PTXSA USB_OTG_HPTXFSIZ_PTXSA_Msk /*!< Host periodic TxFIFO start address */ +#define USB_OTG_HPTXFSIZ_PTXFD_Pos (16U) +#define USB_OTG_HPTXFSIZ_PTXFD_Msk (0xFFFFUL << USB_OTG_HPTXFSIZ_PTXFD_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_HPTXFSIZ_PTXFD USB_OTG_HPTXFSIZ_PTXFD_Msk /*!< Host periodic TxFIFO depth */ + +/******************** Bit definition for USB_OTG_DIEPCTL register ********************/ +#define USB_OTG_DIEPCTL_MPSIZ_Pos (0U) +#define USB_OTG_DIEPCTL_MPSIZ_Msk (0x7FFUL << USB_OTG_DIEPCTL_MPSIZ_Pos) /*!< 0x000007FF */ +#define USB_OTG_DIEPCTL_MPSIZ USB_OTG_DIEPCTL_MPSIZ_Msk /*!< Maximum packet size */ +#define USB_OTG_DIEPCTL_USBAEP_Pos (15U) +#define USB_OTG_DIEPCTL_USBAEP_Msk (0x1UL << USB_OTG_DIEPCTL_USBAEP_Pos) /*!< 0x00008000 */ +#define USB_OTG_DIEPCTL_USBAEP USB_OTG_DIEPCTL_USBAEP_Msk /*!< USB active endpoint */ +#define USB_OTG_DIEPCTL_EONUM_DPID_Pos (16U) +#define USB_OTG_DIEPCTL_EONUM_DPID_Msk (0x1UL << USB_OTG_DIEPCTL_EONUM_DPID_Pos) /*!< 0x00010000 */ +#define USB_OTG_DIEPCTL_EONUM_DPID USB_OTG_DIEPCTL_EONUM_DPID_Msk /*!< Even/odd frame */ +#define USB_OTG_DIEPCTL_NAKSTS_Pos (17U) +#define USB_OTG_DIEPCTL_NAKSTS_Msk (0x1UL << USB_OTG_DIEPCTL_NAKSTS_Pos) /*!< 0x00020000 */ +#define USB_OTG_DIEPCTL_NAKSTS USB_OTG_DIEPCTL_NAKSTS_Msk /*!< NAK status */ + +#define USB_OTG_DIEPCTL_EPTYP_Pos (18U) +#define USB_OTG_DIEPCTL_EPTYP_Msk (0x3UL << USB_OTG_DIEPCTL_EPTYP_Pos) /*!< 0x000C0000 */ +#define USB_OTG_DIEPCTL_EPTYP USB_OTG_DIEPCTL_EPTYP_Msk /*!< Endpoint type */ +#define USB_OTG_DIEPCTL_EPTYP_0 (0x1UL << USB_OTG_DIEPCTL_EPTYP_Pos) /*!< 0x00040000 */ +#define USB_OTG_DIEPCTL_EPTYP_1 (0x2UL << USB_OTG_DIEPCTL_EPTYP_Pos) /*!< 0x00080000 */ +#define USB_OTG_DIEPCTL_STALL_Pos (21U) +#define USB_OTG_DIEPCTL_STALL_Msk (0x1UL << USB_OTG_DIEPCTL_STALL_Pos) /*!< 0x00200000 */ +#define USB_OTG_DIEPCTL_STALL USB_OTG_DIEPCTL_STALL_Msk /*!< STALL handshake */ + +#define USB_OTG_DIEPCTL_TXFNUM_Pos (22U) +#define USB_OTG_DIEPCTL_TXFNUM_Msk (0xFUL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x03C00000 */ +#define USB_OTG_DIEPCTL_TXFNUM USB_OTG_DIEPCTL_TXFNUM_Msk /*!< TxFIFO number */ +#define USB_OTG_DIEPCTL_TXFNUM_0 (0x1UL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x00400000 */ +#define USB_OTG_DIEPCTL_TXFNUM_1 (0x2UL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x00800000 */ +#define USB_OTG_DIEPCTL_TXFNUM_2 (0x4UL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x01000000 */ +#define USB_OTG_DIEPCTL_TXFNUM_3 (0x8UL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x02000000 */ +#define USB_OTG_DIEPCTL_CNAK_Pos (26U) +#define USB_OTG_DIEPCTL_CNAK_Msk (0x1UL << USB_OTG_DIEPCTL_CNAK_Pos) /*!< 0x04000000 */ +#define USB_OTG_DIEPCTL_CNAK USB_OTG_DIEPCTL_CNAK_Msk /*!< Clear NAK */ +#define USB_OTG_DIEPCTL_SNAK_Pos (27U) +#define USB_OTG_DIEPCTL_SNAK_Msk (0x1UL << USB_OTG_DIEPCTL_SNAK_Pos) /*!< 0x08000000 */ +#define USB_OTG_DIEPCTL_SNAK USB_OTG_DIEPCTL_SNAK_Msk /*!< Set NAK */ +#define USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Pos (28U) +#define USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Msk (0x1UL << USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Pos) /*!< 0x10000000 */ +#define USB_OTG_DIEPCTL_SD0PID_SEVNFRM USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Msk /*!< Set DATA0 PID */ +#define USB_OTG_DIEPCTL_SODDFRM_Pos (29U) +#define USB_OTG_DIEPCTL_SODDFRM_Msk (0x1UL << USB_OTG_DIEPCTL_SODDFRM_Pos) /*!< 0x20000000 */ +#define USB_OTG_DIEPCTL_SODDFRM USB_OTG_DIEPCTL_SODDFRM_Msk /*!< Set odd frame */ +#define USB_OTG_DIEPCTL_EPDIS_Pos (30U) +#define USB_OTG_DIEPCTL_EPDIS_Msk (0x1UL << USB_OTG_DIEPCTL_EPDIS_Pos) /*!< 0x40000000 */ +#define USB_OTG_DIEPCTL_EPDIS USB_OTG_DIEPCTL_EPDIS_Msk /*!< Endpoint disable */ +#define USB_OTG_DIEPCTL_EPENA_Pos (31U) +#define USB_OTG_DIEPCTL_EPENA_Msk (0x1UL << USB_OTG_DIEPCTL_EPENA_Pos) /*!< 0x80000000 */ +#define USB_OTG_DIEPCTL_EPENA USB_OTG_DIEPCTL_EPENA_Msk /*!< Endpoint enable */ + +/******************** Bit definition for USB_OTG_HCCHAR register ********************/ +#define USB_OTG_HCCHAR_MPSIZ_Pos (0U) +#define USB_OTG_HCCHAR_MPSIZ_Msk (0x7FFUL << USB_OTG_HCCHAR_MPSIZ_Pos) /*!< 0x000007FF */ +#define USB_OTG_HCCHAR_MPSIZ USB_OTG_HCCHAR_MPSIZ_Msk /*!< Maximum packet size */ + +#define USB_OTG_HCCHAR_EPNUM_Pos (11U) +#define USB_OTG_HCCHAR_EPNUM_Msk (0xFUL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00007800 */ +#define USB_OTG_HCCHAR_EPNUM USB_OTG_HCCHAR_EPNUM_Msk /*!< Endpoint number */ +#define USB_OTG_HCCHAR_EPNUM_0 (0x1UL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00000800 */ +#define USB_OTG_HCCHAR_EPNUM_1 (0x2UL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00001000 */ +#define USB_OTG_HCCHAR_EPNUM_2 (0x4UL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00002000 */ +#define USB_OTG_HCCHAR_EPNUM_3 (0x8UL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00004000 */ +#define USB_OTG_HCCHAR_EPDIR_Pos (15U) +#define USB_OTG_HCCHAR_EPDIR_Msk (0x1UL << USB_OTG_HCCHAR_EPDIR_Pos) /*!< 0x00008000 */ +#define USB_OTG_HCCHAR_EPDIR USB_OTG_HCCHAR_EPDIR_Msk /*!< Endpoint direction */ +#define USB_OTG_HCCHAR_LSDEV_Pos (17U) +#define USB_OTG_HCCHAR_LSDEV_Msk (0x1UL << USB_OTG_HCCHAR_LSDEV_Pos) /*!< 0x00020000 */ +#define USB_OTG_HCCHAR_LSDEV USB_OTG_HCCHAR_LSDEV_Msk /*!< Low-speed device */ + +#define USB_OTG_HCCHAR_EPTYP_Pos (18U) +#define USB_OTG_HCCHAR_EPTYP_Msk (0x3UL << USB_OTG_HCCHAR_EPTYP_Pos) /*!< 0x000C0000 */ +#define USB_OTG_HCCHAR_EPTYP USB_OTG_HCCHAR_EPTYP_Msk /*!< Endpoint type */ +#define USB_OTG_HCCHAR_EPTYP_0 (0x1UL << USB_OTG_HCCHAR_EPTYP_Pos) /*!< 0x00040000 */ +#define USB_OTG_HCCHAR_EPTYP_1 (0x2UL << USB_OTG_HCCHAR_EPTYP_Pos) /*!< 0x00080000 */ + +#define USB_OTG_HCCHAR_MC_Pos (20U) +#define USB_OTG_HCCHAR_MC_Msk (0x3UL << USB_OTG_HCCHAR_MC_Pos) /*!< 0x00300000 */ +#define USB_OTG_HCCHAR_MC USB_OTG_HCCHAR_MC_Msk /*!< Multi Count (MC) / Error Count (EC) */ +#define USB_OTG_HCCHAR_MC_0 (0x1UL << USB_OTG_HCCHAR_MC_Pos) /*!< 0x00100000 */ +#define USB_OTG_HCCHAR_MC_1 (0x2UL << USB_OTG_HCCHAR_MC_Pos) /*!< 0x00200000 */ + +#define USB_OTG_HCCHAR_DAD_Pos (22U) +#define USB_OTG_HCCHAR_DAD_Msk (0x7FUL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x1FC00000 */ +#define USB_OTG_HCCHAR_DAD USB_OTG_HCCHAR_DAD_Msk /*!< Device address */ +#define USB_OTG_HCCHAR_DAD_0 (0x01UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x00400000 */ +#define USB_OTG_HCCHAR_DAD_1 (0x02UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x00800000 */ +#define USB_OTG_HCCHAR_DAD_2 (0x04UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x01000000 */ +#define USB_OTG_HCCHAR_DAD_3 (0x08UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x02000000 */ +#define USB_OTG_HCCHAR_DAD_4 (0x10UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x04000000 */ +#define USB_OTG_HCCHAR_DAD_5 (0x20UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x08000000 */ +#define USB_OTG_HCCHAR_DAD_6 (0x40UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x10000000 */ +#define USB_OTG_HCCHAR_ODDFRM_Pos (29U) +#define USB_OTG_HCCHAR_ODDFRM_Msk (0x1UL << USB_OTG_HCCHAR_ODDFRM_Pos) /*!< 0x20000000 */ +#define USB_OTG_HCCHAR_ODDFRM USB_OTG_HCCHAR_ODDFRM_Msk /*!< Odd frame */ +#define USB_OTG_HCCHAR_CHDIS_Pos (30U) +#define USB_OTG_HCCHAR_CHDIS_Msk (0x1UL << USB_OTG_HCCHAR_CHDIS_Pos) /*!< 0x40000000 */ +#define USB_OTG_HCCHAR_CHDIS USB_OTG_HCCHAR_CHDIS_Msk /*!< Channel disable */ +#define USB_OTG_HCCHAR_CHENA_Pos (31U) +#define USB_OTG_HCCHAR_CHENA_Msk (0x1UL << USB_OTG_HCCHAR_CHENA_Pos) /*!< 0x80000000 */ +#define USB_OTG_HCCHAR_CHENA USB_OTG_HCCHAR_CHENA_Msk /*!< Channel enable */ + +/******************** Bit definition for USB_OTG_HCSPLT register ********************/ + +#define USB_OTG_HCSPLT_PRTADDR_Pos (0U) +#define USB_OTG_HCSPLT_PRTADDR_Msk (0x7FUL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x0000007F */ +#define USB_OTG_HCSPLT_PRTADDR USB_OTG_HCSPLT_PRTADDR_Msk /*!< Port address */ +#define USB_OTG_HCSPLT_PRTADDR_0 (0x01UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000001 */ +#define USB_OTG_HCSPLT_PRTADDR_1 (0x02UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000002 */ +#define USB_OTG_HCSPLT_PRTADDR_2 (0x04UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000004 */ +#define USB_OTG_HCSPLT_PRTADDR_3 (0x08UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000008 */ +#define USB_OTG_HCSPLT_PRTADDR_4 (0x10UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000010 */ +#define USB_OTG_HCSPLT_PRTADDR_5 (0x20UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000020 */ +#define USB_OTG_HCSPLT_PRTADDR_6 (0x40UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000040 */ + +#define USB_OTG_HCSPLT_HUBADDR_Pos (7U) +#define USB_OTG_HCSPLT_HUBADDR_Msk (0x7FUL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00003F80 */ +#define USB_OTG_HCSPLT_HUBADDR USB_OTG_HCSPLT_HUBADDR_Msk /*!< Hub address */ +#define USB_OTG_HCSPLT_HUBADDR_0 (0x01UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000080 */ +#define USB_OTG_HCSPLT_HUBADDR_1 (0x02UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000100 */ +#define USB_OTG_HCSPLT_HUBADDR_2 (0x04UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000200 */ +#define USB_OTG_HCSPLT_HUBADDR_3 (0x08UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000400 */ +#define USB_OTG_HCSPLT_HUBADDR_4 (0x10UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000800 */ +#define USB_OTG_HCSPLT_HUBADDR_5 (0x20UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00001000 */ +#define USB_OTG_HCSPLT_HUBADDR_6 (0x40UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00002000 */ + +#define USB_OTG_HCSPLT_XACTPOS_Pos (14U) +#define USB_OTG_HCSPLT_XACTPOS_Msk (0x3UL << USB_OTG_HCSPLT_XACTPOS_Pos) /*!< 0x0000C000 */ +#define USB_OTG_HCSPLT_XACTPOS USB_OTG_HCSPLT_XACTPOS_Msk /*!< XACTPOS */ +#define USB_OTG_HCSPLT_XACTPOS_0 (0x1UL << USB_OTG_HCSPLT_XACTPOS_Pos) /*!< 0x00004000 */ +#define USB_OTG_HCSPLT_XACTPOS_1 (0x2UL << USB_OTG_HCSPLT_XACTPOS_Pos) /*!< 0x00008000 */ +#define USB_OTG_HCSPLT_COMPLSPLT_Pos (16U) +#define USB_OTG_HCSPLT_COMPLSPLT_Msk (0x1UL << USB_OTG_HCSPLT_COMPLSPLT_Pos) /*!< 0x00010000 */ +#define USB_OTG_HCSPLT_COMPLSPLT USB_OTG_HCSPLT_COMPLSPLT_Msk /*!< Do complete split */ +#define USB_OTG_HCSPLT_SPLITEN_Pos (31U) +#define USB_OTG_HCSPLT_SPLITEN_Msk (0x1UL << USB_OTG_HCSPLT_SPLITEN_Pos) /*!< 0x80000000 */ +#define USB_OTG_HCSPLT_SPLITEN USB_OTG_HCSPLT_SPLITEN_Msk /*!< Split enable */ + +/******************** Bit definition for USB_OTG_HCINT register ********************/ +#define USB_OTG_HCINT_XFRC_Pos (0U) +#define USB_OTG_HCINT_XFRC_Msk (0x1UL << USB_OTG_HCINT_XFRC_Pos) /*!< 0x00000001 */ +#define USB_OTG_HCINT_XFRC USB_OTG_HCINT_XFRC_Msk /*!< Transfer completed */ +#define USB_OTG_HCINT_CHH_Pos (1U) +#define USB_OTG_HCINT_CHH_Msk (0x1UL << USB_OTG_HCINT_CHH_Pos) /*!< 0x00000002 */ +#define USB_OTG_HCINT_CHH USB_OTG_HCINT_CHH_Msk /*!< Channel halted */ +#define USB_OTG_HCINT_AHBERR_Pos (2U) +#define USB_OTG_HCINT_AHBERR_Msk (0x1UL << USB_OTG_HCINT_AHBERR_Pos) /*!< 0x00000004 */ +#define USB_OTG_HCINT_AHBERR USB_OTG_HCINT_AHBERR_Msk /*!< AHB error */ +#define USB_OTG_HCINT_STALL_Pos (3U) +#define USB_OTG_HCINT_STALL_Msk (0x1UL << USB_OTG_HCINT_STALL_Pos) /*!< 0x00000008 */ +#define USB_OTG_HCINT_STALL USB_OTG_HCINT_STALL_Msk /*!< STALL response received interrupt */ +#define USB_OTG_HCINT_NAK_Pos (4U) +#define USB_OTG_HCINT_NAK_Msk (0x1UL << USB_OTG_HCINT_NAK_Pos) /*!< 0x00000010 */ +#define USB_OTG_HCINT_NAK USB_OTG_HCINT_NAK_Msk /*!< NAK response received interrupt */ +#define USB_OTG_HCINT_ACK_Pos (5U) +#define USB_OTG_HCINT_ACK_Msk (0x1UL << USB_OTG_HCINT_ACK_Pos) /*!< 0x00000020 */ +#define USB_OTG_HCINT_ACK USB_OTG_HCINT_ACK_Msk /*!< ACK response received/transmitted interrupt */ +#define USB_OTG_HCINT_NYET_Pos (6U) +#define USB_OTG_HCINT_NYET_Msk (0x1UL << USB_OTG_HCINT_NYET_Pos) /*!< 0x00000040 */ +#define USB_OTG_HCINT_NYET USB_OTG_HCINT_NYET_Msk /*!< Response received interrupt */ +#define USB_OTG_HCINT_TXERR_Pos (7U) +#define USB_OTG_HCINT_TXERR_Msk (0x1UL << USB_OTG_HCINT_TXERR_Pos) /*!< 0x00000080 */ +#define USB_OTG_HCINT_TXERR USB_OTG_HCINT_TXERR_Msk /*!< Transaction error */ +#define USB_OTG_HCINT_BBERR_Pos (8U) +#define USB_OTG_HCINT_BBERR_Msk (0x1UL << USB_OTG_HCINT_BBERR_Pos) /*!< 0x00000100 */ +#define USB_OTG_HCINT_BBERR USB_OTG_HCINT_BBERR_Msk /*!< Babble error */ +#define USB_OTG_HCINT_FRMOR_Pos (9U) +#define USB_OTG_HCINT_FRMOR_Msk (0x1UL << USB_OTG_HCINT_FRMOR_Pos) /*!< 0x00000200 */ +#define USB_OTG_HCINT_FRMOR USB_OTG_HCINT_FRMOR_Msk /*!< Frame overrun */ +#define USB_OTG_HCINT_DTERR_Pos (10U) +#define USB_OTG_HCINT_DTERR_Msk (0x1UL << USB_OTG_HCINT_DTERR_Pos) /*!< 0x00000400 */ +#define USB_OTG_HCINT_DTERR USB_OTG_HCINT_DTERR_Msk /*!< Data toggle error */ + +/******************** Bit definition for USB_OTG_DIEPINT register ********************/ +#define USB_OTG_DIEPINT_XFRC_Pos (0U) +#define USB_OTG_DIEPINT_XFRC_Msk (0x1UL << USB_OTG_DIEPINT_XFRC_Pos) /*!< 0x00000001 */ +#define USB_OTG_DIEPINT_XFRC USB_OTG_DIEPINT_XFRC_Msk /*!< Transfer completed interrupt */ +#define USB_OTG_DIEPINT_EPDISD_Pos (1U) +#define USB_OTG_DIEPINT_EPDISD_Msk (0x1UL << USB_OTG_DIEPINT_EPDISD_Pos) /*!< 0x00000002 */ +#define USB_OTG_DIEPINT_EPDISD USB_OTG_DIEPINT_EPDISD_Msk /*!< Endpoint disabled interrupt */ +#define USB_OTG_DIEPINT_AHBERR_Pos (2U) +#define USB_OTG_DIEPINT_AHBERR_Msk (0x1UL << USB_OTG_DIEPINT_AHBERR_Pos) /*!< 0x00000004 */ +#define USB_OTG_DIEPINT_AHBERR USB_OTG_DIEPINT_AHBERR_Msk /*!< AHB Error (AHBErr) during an IN transaction */ +#define USB_OTG_DIEPINT_TOC_Pos (3U) +#define USB_OTG_DIEPINT_TOC_Msk (0x1UL << USB_OTG_DIEPINT_TOC_Pos) /*!< 0x00000008 */ +#define USB_OTG_DIEPINT_TOC USB_OTG_DIEPINT_TOC_Msk /*!< Timeout condition */ +#define USB_OTG_DIEPINT_ITTXFE_Pos (4U) +#define USB_OTG_DIEPINT_ITTXFE_Msk (0x1UL << USB_OTG_DIEPINT_ITTXFE_Pos) /*!< 0x00000010 */ +#define USB_OTG_DIEPINT_ITTXFE USB_OTG_DIEPINT_ITTXFE_Msk /*!< IN token received when TxFIFO is empty */ +#define USB_OTG_DIEPINT_INEPNM_Pos (5U) +#define USB_OTG_DIEPINT_INEPNM_Msk (0x1UL << USB_OTG_DIEPINT_INEPNM_Pos) /*!< 0x00000004 */ +#define USB_OTG_DIEPINT_INEPNM USB_OTG_DIEPINT_INEPNM_Msk /*!< IN token received with EP mismatch */ +#define USB_OTG_DIEPINT_INEPNE_Pos (6U) +#define USB_OTG_DIEPINT_INEPNE_Msk (0x1UL << USB_OTG_DIEPINT_INEPNE_Pos) /*!< 0x00000040 */ +#define USB_OTG_DIEPINT_INEPNE USB_OTG_DIEPINT_INEPNE_Msk /*!< IN endpoint NAK effective */ +#define USB_OTG_DIEPINT_TXFE_Pos (7U) +#define USB_OTG_DIEPINT_TXFE_Msk (0x1UL << USB_OTG_DIEPINT_TXFE_Pos) /*!< 0x00000080 */ +#define USB_OTG_DIEPINT_TXFE USB_OTG_DIEPINT_TXFE_Msk /*!< Transmit FIFO empty */ +#define USB_OTG_DIEPINT_TXFIFOUDRN_Pos (8U) +#define USB_OTG_DIEPINT_TXFIFOUDRN_Msk (0x1UL << USB_OTG_DIEPINT_TXFIFOUDRN_Pos) /*!< 0x00000100 */ +#define USB_OTG_DIEPINT_TXFIFOUDRN USB_OTG_DIEPINT_TXFIFOUDRN_Msk /*!< Transmit Fifo Underrun */ +#define USB_OTG_DIEPINT_BNA_Pos (9U) +#define USB_OTG_DIEPINT_BNA_Msk (0x1UL << USB_OTG_DIEPINT_BNA_Pos) /*!< 0x00000200 */ +#define USB_OTG_DIEPINT_BNA USB_OTG_DIEPINT_BNA_Msk /*!< Buffer not available interrupt */ +#define USB_OTG_DIEPINT_PKTDRPSTS_Pos (11U) +#define USB_OTG_DIEPINT_PKTDRPSTS_Msk (0x1UL << USB_OTG_DIEPINT_PKTDRPSTS_Pos) /*!< 0x00000800 */ +#define USB_OTG_DIEPINT_PKTDRPSTS USB_OTG_DIEPINT_PKTDRPSTS_Msk /*!< Packet dropped status */ +#define USB_OTG_DIEPINT_BERR_Pos (12U) +#define USB_OTG_DIEPINT_BERR_Msk (0x1UL << USB_OTG_DIEPINT_BERR_Pos) /*!< 0x00001000 */ +#define USB_OTG_DIEPINT_BERR USB_OTG_DIEPINT_BERR_Msk /*!< Babble error interrupt */ +#define USB_OTG_DIEPINT_NAK_Pos (13U) +#define USB_OTG_DIEPINT_NAK_Msk (0x1UL << USB_OTG_DIEPINT_NAK_Pos) /*!< 0x00002000 */ +#define USB_OTG_DIEPINT_NAK USB_OTG_DIEPINT_NAK_Msk /*!< NAK interrupt */ + +/******************** Bit definition for USB_OTG_HCINTMSK register ********************/ +#define USB_OTG_HCINTMSK_XFRCM_Pos (0U) +#define USB_OTG_HCINTMSK_XFRCM_Msk (0x1UL << USB_OTG_HCINTMSK_XFRCM_Pos) /*!< 0x00000001 */ +#define USB_OTG_HCINTMSK_XFRCM USB_OTG_HCINTMSK_XFRCM_Msk /*!< Transfer completed mask */ +#define USB_OTG_HCINTMSK_CHHM_Pos (1U) +#define USB_OTG_HCINTMSK_CHHM_Msk (0x1UL << USB_OTG_HCINTMSK_CHHM_Pos) /*!< 0x00000002 */ +#define USB_OTG_HCINTMSK_CHHM USB_OTG_HCINTMSK_CHHM_Msk /*!< Channel halted mask */ +#define USB_OTG_HCINTMSK_AHBERR_Pos (2U) +#define USB_OTG_HCINTMSK_AHBERR_Msk (0x1UL << USB_OTG_HCINTMSK_AHBERR_Pos) /*!< 0x00000004 */ +#define USB_OTG_HCINTMSK_AHBERR USB_OTG_HCINTMSK_AHBERR_Msk /*!< AHB error */ +#define USB_OTG_HCINTMSK_STALLM_Pos (3U) +#define USB_OTG_HCINTMSK_STALLM_Msk (0x1UL << USB_OTG_HCINTMSK_STALLM_Pos) /*!< 0x00000008 */ +#define USB_OTG_HCINTMSK_STALLM USB_OTG_HCINTMSK_STALLM_Msk /*!< STALL response received interrupt mask */ +#define USB_OTG_HCINTMSK_NAKM_Pos (4U) +#define USB_OTG_HCINTMSK_NAKM_Msk (0x1UL << USB_OTG_HCINTMSK_NAKM_Pos) /*!< 0x00000010 */ +#define USB_OTG_HCINTMSK_NAKM USB_OTG_HCINTMSK_NAKM_Msk /*!< NAK response received interrupt mask */ +#define USB_OTG_HCINTMSK_ACKM_Pos (5U) +#define USB_OTG_HCINTMSK_ACKM_Msk (0x1UL << USB_OTG_HCINTMSK_ACKM_Pos) /*!< 0x00000020 */ +#define USB_OTG_HCINTMSK_ACKM USB_OTG_HCINTMSK_ACKM_Msk /*!< ACK response received/transmitted interrupt mask */ +#define USB_OTG_HCINTMSK_NYET_Pos (6U) +#define USB_OTG_HCINTMSK_NYET_Msk (0x1UL << USB_OTG_HCINTMSK_NYET_Pos) /*!< 0x00000040 */ +#define USB_OTG_HCINTMSK_NYET USB_OTG_HCINTMSK_NYET_Msk /*!< response received interrupt mask */ +#define USB_OTG_HCINTMSK_TXERRM_Pos (7U) +#define USB_OTG_HCINTMSK_TXERRM_Msk (0x1UL << USB_OTG_HCINTMSK_TXERRM_Pos) /*!< 0x00000080 */ +#define USB_OTG_HCINTMSK_TXERRM USB_OTG_HCINTMSK_TXERRM_Msk /*!< Transaction error mask */ +#define USB_OTG_HCINTMSK_BBERRM_Pos (8U) +#define USB_OTG_HCINTMSK_BBERRM_Msk (0x1UL << USB_OTG_HCINTMSK_BBERRM_Pos) /*!< 0x00000100 */ +#define USB_OTG_HCINTMSK_BBERRM USB_OTG_HCINTMSK_BBERRM_Msk /*!< Babble error mask */ +#define USB_OTG_HCINTMSK_FRMORM_Pos (9U) +#define USB_OTG_HCINTMSK_FRMORM_Msk (0x1UL << USB_OTG_HCINTMSK_FRMORM_Pos) /*!< 0x00000200 */ +#define USB_OTG_HCINTMSK_FRMORM USB_OTG_HCINTMSK_FRMORM_Msk /*!< Frame overrun mask */ +#define USB_OTG_HCINTMSK_DTERRM_Pos (10U) +#define USB_OTG_HCINTMSK_DTERRM_Msk (0x1UL << USB_OTG_HCINTMSK_DTERRM_Pos) /*!< 0x00000400 */ +#define USB_OTG_HCINTMSK_DTERRM USB_OTG_HCINTMSK_DTERRM_Msk /*!< Data toggle error mask */ + +/******************** Bit definition for USB_OTG_DIEPTSIZ register ********************/ + +#define USB_OTG_DIEPTSIZ_XFRSIZ_Pos (0U) +#define USB_OTG_DIEPTSIZ_XFRSIZ_Msk (0x7FFFFUL << USB_OTG_DIEPTSIZ_XFRSIZ_Pos) /*!< 0x0007FFFF */ +#define USB_OTG_DIEPTSIZ_XFRSIZ USB_OTG_DIEPTSIZ_XFRSIZ_Msk /*!< Transfer size */ +#define USB_OTG_DIEPTSIZ_PKTCNT_Pos (19U) +#define USB_OTG_DIEPTSIZ_PKTCNT_Msk (0x3FFUL << USB_OTG_DIEPTSIZ_PKTCNT_Pos) /*!< 0x1FF80000 */ +#define USB_OTG_DIEPTSIZ_PKTCNT USB_OTG_DIEPTSIZ_PKTCNT_Msk /*!< Packet count */ +#define USB_OTG_DIEPTSIZ_MULCNT_Pos (29U) +#define USB_OTG_DIEPTSIZ_MULCNT_Msk (0x3UL << USB_OTG_DIEPTSIZ_MULCNT_Pos) /*!< 0x60000000 */ +#define USB_OTG_DIEPTSIZ_MULCNT USB_OTG_DIEPTSIZ_MULCNT_Msk /*!< Packet count */ +/******************** Bit definition for USB_OTG_HCTSIZ register ********************/ +#define USB_OTG_HCTSIZ_XFRSIZ_Pos (0U) +#define USB_OTG_HCTSIZ_XFRSIZ_Msk (0x7FFFFUL << USB_OTG_HCTSIZ_XFRSIZ_Pos) /*!< 0x0007FFFF */ +#define USB_OTG_HCTSIZ_XFRSIZ USB_OTG_HCTSIZ_XFRSIZ_Msk /*!< Transfer size */ +#define USB_OTG_HCTSIZ_PKTCNT_Pos (19U) +#define USB_OTG_HCTSIZ_PKTCNT_Msk (0x3FFUL << USB_OTG_HCTSIZ_PKTCNT_Pos) /*!< 0x1FF80000 */ +#define USB_OTG_HCTSIZ_PKTCNT USB_OTG_HCTSIZ_PKTCNT_Msk /*!< Packet count */ +#define USB_OTG_HCTSIZ_DOPING_Pos (31U) +#define USB_OTG_HCTSIZ_DOPING_Msk (0x1UL << USB_OTG_HCTSIZ_DOPING_Pos) /*!< 0x80000000 */ +#define USB_OTG_HCTSIZ_DOPING USB_OTG_HCTSIZ_DOPING_Msk /*!< Do PING */ +#define USB_OTG_HCTSIZ_DPID_Pos (29U) +#define USB_OTG_HCTSIZ_DPID_Msk (0x3UL << USB_OTG_HCTSIZ_DPID_Pos) /*!< 0x60000000 */ +#define USB_OTG_HCTSIZ_DPID USB_OTG_HCTSIZ_DPID_Msk /*!< Data PID */ +#define USB_OTG_HCTSIZ_DPID_0 (0x1UL << USB_OTG_HCTSIZ_DPID_Pos) /*!< 0x20000000 */ +#define USB_OTG_HCTSIZ_DPID_1 (0x2UL << USB_OTG_HCTSIZ_DPID_Pos) /*!< 0x40000000 */ + +/******************** Bit definition for USB_OTG_DIEPDMA register ********************/ +#define USB_OTG_DIEPDMA_DMAADDR_Pos (0U) +#define USB_OTG_DIEPDMA_DMAADDR_Msk (0xFFFFFFFFUL << USB_OTG_DIEPDMA_DMAADDR_Pos) /*!< 0xFFFFFFFF */ +#define USB_OTG_DIEPDMA_DMAADDR USB_OTG_DIEPDMA_DMAADDR_Msk /*!< DMA address */ + +/******************** Bit definition for USB_OTG_HCDMA register ********************/ +#define USB_OTG_HCDMA_DMAADDR_Pos (0U) +#define USB_OTG_HCDMA_DMAADDR_Msk (0xFFFFFFFFUL << USB_OTG_HCDMA_DMAADDR_Pos) /*!< 0xFFFFFFFF */ +#define USB_OTG_HCDMA_DMAADDR USB_OTG_HCDMA_DMAADDR_Msk /*!< DMA address */ + +/******************** Bit definition for USB_OTG_DTXFSTS register ********************/ +#define USB_OTG_DTXFSTS_INEPTFSAV_Pos (0U) +#define USB_OTG_DTXFSTS_INEPTFSAV_Msk (0xFFFFUL << USB_OTG_DTXFSTS_INEPTFSAV_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_DTXFSTS_INEPTFSAV USB_OTG_DTXFSTS_INEPTFSAV_Msk /*!< IN endpoint TxFIFO space available */ + +/******************** Bit definition for USB_OTG_DIEPTXF register ********************/ +#define USB_OTG_DIEPTXF_INEPTXSA_Pos (0U) +#define USB_OTG_DIEPTXF_INEPTXSA_Msk (0xFFFFUL << USB_OTG_DIEPTXF_INEPTXSA_Pos) /*!< 0x0000FFFF */ +#define USB_OTG_DIEPTXF_INEPTXSA USB_OTG_DIEPTXF_INEPTXSA_Msk /*!< IN endpoint FIFOx transmit RAM start address */ +#define USB_OTG_DIEPTXF_INEPTXFD_Pos (16U) +#define USB_OTG_DIEPTXF_INEPTXFD_Msk (0xFFFFUL << USB_OTG_DIEPTXF_INEPTXFD_Pos) /*!< 0xFFFF0000 */ +#define USB_OTG_DIEPTXF_INEPTXFD USB_OTG_DIEPTXF_INEPTXFD_Msk /*!< IN endpoint TxFIFO depth */ + +/******************** Bit definition for USB_OTG_DOEPCTL register ********************/ + +#define USB_OTG_DOEPCTL_MPSIZ_Pos (0U) +#define USB_OTG_DOEPCTL_MPSIZ_Msk (0x7FFUL << USB_OTG_DOEPCTL_MPSIZ_Pos) /*!< 0x000007FF */ +#define USB_OTG_DOEPCTL_MPSIZ USB_OTG_DOEPCTL_MPSIZ_Msk /*!< Maximum packet size */ /*! Date: Mon, 25 Oct 2021 00:06:57 +0700 Subject: [PATCH 11/51] switch gd32 and stm32f4 to use new dwc2 driver --- hw/bsp/gd32vf103/family.mk | 2 +- src/portable/synopsys/dwc2/dcd_dwc2.c | 288 ++- src/portable/synopsys/dwc2/dwc2_gd32.h | 7 +- src/portable/synopsys/dwc2/dwc2_stm32.h | 15 + src/portable/synopsys/dwc2/dwc2_type.h | 2578 ++++++++++++----------- 5 files changed, 1516 insertions(+), 1374 deletions(-) diff --git a/hw/bsp/gd32vf103/family.mk b/hw/bsp/gd32vf103/family.mk index 9148e7f8b..4de23ac17 100644 --- a/hw/bsp/gd32vf103/family.mk +++ b/hw/bsp/gd32vf103/family.mk @@ -35,7 +35,7 @@ CFLAGS += \ CFLAGS += -Wno-error=unused-parameter SRC_C += \ - src/portable/st/synopsys/dcd_synopsys.c \ + src/portable/synopsys/dwc2/dcd_dwc2.c \ $(GD32VF103_SDK_DRIVER)/gd32vf103_rcu.c \ $(GD32VF103_SDK_DRIVER)/gd32vf103_gpio.c \ $(GD32VF103_SDK_DRIVER)/Usb/gd32vf103_usb_hw.c \ diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 597f4c813..5811afa5a 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -52,26 +52,11 @@ // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ -// On STM32 we associate Port0 to OTG_FS, and Port1 to OTG_HS -#if TUD_OPT_RHPORT == 0 -#define EP_MAX EP_MAX_FS -#define EP_FIFO_SIZE EP_FIFO_SIZE_FS -#define RHPORT_REGS_BASE USB_OTG_FS_PERIPH_BASE -#define RHPORT_IRQn OTG_FS_IRQn - -#else -#define EP_MAX EP_MAX_HS -#define EP_FIFO_SIZE EP_FIFO_SIZE_HS -#define RHPORT_REGS_BASE USB_OTG_HS_PERIPH_BASE -#define RHPORT_IRQn OTG_HS_IRQn - -#endif - -#define GLOBAL_BASE(_port) ((dwc2_core_t*) RHPORT_REGS_BASE) -#define DEVICE_BASE(_port) ((dwc2_device_t *) (RHPORT_REGS_BASE + USB_OTG_DEVICE_BASE)) -#define OUT_EP_BASE(_port) ((dwc2_epout_t *) (RHPORT_REGS_BASE + USB_OTG_OUT_ENDPOINT_BASE)) -#define IN_EP_BASE(_port) ((dwc2_epin_t *) (RHPORT_REGS_BASE + USB_OTG_IN_ENDPOINT_BASE)) -#define FIFO_BASE(_port, _x) ((volatile uint32_t *) (RHPORT_REGS_BASE + USB_OTG_FIFO_BASE + (_x) * USB_OTG_FIFO_SIZE)) +#define GLOBAL_BASE(_port) ((dwc2_core_t*) DWC2_REG_BASE) +#define DEVICE_BASE(_port) ((dwc2_device_t*) (DWC2_REG_BASE + DWC2_DEVICE_BASE)) +#define IN_EP_BASE(_port) ((dwc2_epin_t*) (DWC2_REG_BASE + DWC2_IN_ENDPOINT_BASE)) +#define OUT_EP_BASE(_port) ((dwc2_epout_t*) (DWC2_REG_BASE + DWC2_OUT_ENDPOINT_BASE)) +#define FIFO_BASE(_port, _x) ((volatile uint32_t*) (DWC2_REG_BASE + DWC2_FIFO_BASE + (_x) * DWC2_FIFO_SIZE)) enum { @@ -139,17 +124,17 @@ static void bus_reset(uint8_t rhport) _out_ep_closed = false; // clear device address - dev->DCFG &= ~USB_OTG_DCFG_DAD_Msk; + dev->DCFG &= ~DCFG_DAD_Msk; // 1. NAK for all OUT endpoints for(uint8_t n = 0; n < EP_MAX; n++) { - out_ep[n].DOEPCTL |= USB_OTG_DOEPCTL_SNAK; + out_ep[n].DOEPCTL |= DOEPCTL_SNAK; } // 2. Un-mask interrupt bits - dev->DAINTMSK = (1 << USB_OTG_DAINTMSK_OEPM_Pos) | (1 << USB_OTG_DAINTMSK_IEPM_Pos); - dev->DOEPMSK = USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM; - dev->DIEPMSK = USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM; + dev->DAINTMSK = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); + dev->DOEPMSK = DOEPMSK_STUPM | DOEPMSK_XFRCM; + dev->DIEPMSK = DIEPMSK_TOM | DIEPMSK_XFRCM; // "USB Data FIFOs" section in reference manual // Peripheral FIFO architecture @@ -206,27 +191,27 @@ static void bus_reset(uint8_t rhport) _allocated_fifo_words_tx = 16; // Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) - usb_otg->DIEPTXF0_HNPTXFSIZ = (16 << USB_OTG_TX0FD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + usb_otg->DIEPTXF0_HNPTXFSIZ = (16 << TX0FD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); // Fixed control EP0 size to 64 bytes - in_ep[0].DIEPCTL &= ~(0x03 << USB_OTG_DIEPCTL_MPSIZ_Pos); + in_ep[0].DIEPCTL &= ~(0x03 << DIEPCTL_MPSIZ_Pos); xfer_status[0][TUSB_DIR_OUT].max_size = xfer_status[0][TUSB_DIR_IN].max_size = 64; - out_ep[0].DOEPTSIZ |= (3 << USB_OTG_DOEPTSIZ_STUPCNT_Pos); + out_ep[0].DOEPTSIZ |= (3 << DOEPTSIZ_STUPCNT_Pos); - usb_otg->GINTMSK |= USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT; + usb_otg->GINTMSK |= GINTMSK_OEPINT | GINTMSK_IEPINT; } // Set turn-around timeout according to link speed extern uint32_t SystemCoreClock; static void set_turnaround(dwc2_core_t * usb_otg, tusb_speed_t speed) { - usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; + usb_otg->GUSBCFG &= ~GUSBCFG_TRDT; if ( speed == TUSB_SPEED_HIGH ) { // Use fixed 0x09 for Highspeed - usb_otg->GUSBCFG |= (0x09 << USB_OTG_GUSBCFG_TRDT_Pos); + usb_otg->GUSBCFG |= (0x09 << GUSBCFG_TRDT_Pos); } else { @@ -255,7 +240,7 @@ static void set_turnaround(dwc2_core_t * usb_otg, tusb_speed_t speed) turnaround = 0xFU; // Fullspeed depends on MCU clocks, but we will use 0x06 for 32+ Mhz - usb_otg->GUSBCFG |= (turnaround << USB_OTG_GUSBCFG_TRDT_Pos); + usb_otg->GUSBCFG |= (turnaround << GUSBCFG_TRDT_Pos); } } @@ -263,7 +248,7 @@ static tusb_speed_t get_speed(uint8_t rhport) { (void) rhport; dwc2_device_t * dev = DEVICE_BASE(rhport); - uint32_t const enum_spd = (dev->DSTS & USB_OTG_DSTS_ENUMSPD_Msk) >> USB_OTG_DSTS_ENUMSPD_Pos; + uint32_t const enum_spd = (dev->DSTS & DSTS_ENUMSPD_Msk) >> DSTS_ENUMSPD_Pos; return (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL; } @@ -283,8 +268,8 @@ static void set_speed(uint8_t rhport, tusb_speed_t speed) dwc2_device_t * dev = DEVICE_BASE(rhport); // Clear and set speed bits - dev->DCFG &= ~(3 << USB_OTG_DCFG_DSPD_Pos); - dev->DCFG |= (bitvalue << USB_OTG_DCFG_DSPD_Pos); + dev->DCFG &= ~(3 << DCFG_DSPD_Pos); + dev->DCFG |= (bitvalue << DCFG_DSPD_Pos); } #if defined(USB_HS_PHYC) @@ -347,16 +332,16 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c // IN and OUT endpoint xfers are interrupt-driven, we just schedule them here. if(dir == TUSB_DIR_IN) { // A full IN transfer (multiple packets, possibly) triggers XFRC. - in_ep[epnum].DIEPTSIZ = (num_packets << USB_OTG_DIEPTSIZ_PKTCNT_Pos) | - ((total_bytes << USB_OTG_DIEPTSIZ_XFRSIZ_Pos) & USB_OTG_DIEPTSIZ_XFRSIZ_Msk); + in_ep[epnum].DIEPTSIZ = (num_packets << DIEPTSIZ_PKTCNT_Pos) | + ((total_bytes << DIEPTSIZ_XFRSIZ_Pos) & DIEPTSIZ_XFRSIZ_Msk); - in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_EPENA | USB_OTG_DIEPCTL_CNAK; + in_ep[epnum].DIEPCTL |= DIEPCTL_EPENA | DIEPCTL_CNAK; // For ISO endpoint set correct odd/even bit for next frame. - if ((in_ep[epnum].DIEPCTL & USB_OTG_DIEPCTL_EPTYP) == USB_OTG_DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) + if ((in_ep[epnum].DIEPCTL & DIEPCTL_EPTYP) == DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) { // Take odd/even bit from frame counter. - uint32_t const odd_frame_now = (dev->DSTS & (1u << USB_OTG_DSTS_FNSOF_Pos)); - in_ep[epnum].DIEPCTL |= (odd_frame_now ? USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Msk : USB_OTG_DIEPCTL_SODDFRM_Msk); + uint32_t const odd_frame_now = (dev->DSTS & (1u << DSTS_FNSOF_Pos)); + in_ep[epnum].DIEPCTL |= (odd_frame_now ? DIEPCTL_SD0PID_SEVNFRM_Msk : DIEPCTL_SODDFRM_Msk); } // Enable fifo empty interrupt only if there are something to put in the fifo. if(total_bytes != 0) { @@ -364,16 +349,16 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c } } else { // A full OUT transfer (multiple packets, possibly) triggers XFRC. - out_ep[epnum].DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT_Msk | USB_OTG_DOEPTSIZ_XFRSIZ); - out_ep[epnum].DOEPTSIZ |= (num_packets << USB_OTG_DOEPTSIZ_PKTCNT_Pos) | - ((total_bytes << USB_OTG_DOEPTSIZ_XFRSIZ_Pos) & USB_OTG_DOEPTSIZ_XFRSIZ_Msk); + out_ep[epnum].DOEPTSIZ &= ~(DOEPTSIZ_PKTCNT_Msk | DOEPTSIZ_XFRSIZ); + out_ep[epnum].DOEPTSIZ |= (num_packets << DOEPTSIZ_PKTCNT_Pos) | + ((total_bytes << DOEPTSIZ_XFRSIZ_Pos) & DOEPTSIZ_XFRSIZ_Msk); - out_ep[epnum].DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; - if ((out_ep[epnum].DOEPCTL & USB_OTG_DOEPCTL_EPTYP) == USB_OTG_DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) + out_ep[epnum].DOEPCTL |= DOEPCTL_EPENA | DOEPCTL_CNAK; + if ((out_ep[epnum].DOEPCTL & DOEPCTL_EPTYP) == DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) { // Take odd/even bit from frame counter. - uint32_t const odd_frame_now = (dev->DSTS & (1u << USB_OTG_DSTS_FNSOF_Pos)); - out_ep[epnum].DOEPCTL |= (odd_frame_now ? USB_OTG_DOEPCTL_SD0PID_SEVNFRM_Msk : USB_OTG_DOEPCTL_SODDFRM_Msk); + uint32_t const odd_frame_now = (dev->DSTS & (1u << DSTS_FNSOF_Pos)); + out_ep[epnum].DOEPCTL |= (odd_frame_now ? DOEPCTL_SD0PID_SEVNFRM_Msk : DOEPCTL_SODDFRM_Msk); } } } @@ -385,7 +370,6 @@ void dcd_init (uint8_t rhport) { // Programming model begins in the last section of the chapter on the USB // peripheral in each Reference Manual. - dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); // No HNP/SRP (no OTG support), program timeout later. @@ -394,23 +378,23 @@ void dcd_init (uint8_t rhport) // On selected MCUs HS port1 can be used with external PHY via ULPI interface #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED // deactivate internal PHY - usb_otg->GCCFG &= ~USB_OTG_GCCFG_PWRDWN; + usb_otg->GCCFG &= ~GCCFG_PWRDWN; // Init The UTMI Interface - usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); + usb_otg->GUSBCFG &= ~(GUSBCFG_TSDPS | GUSBCFG_ULPIFSLS | GUSBCFG_PHYSEL); // Select default internal VBUS Indicator and Drive for ULPI - usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); + usb_otg->GUSBCFG &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI); #else - usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; + usb_otg->GUSBCFG |= GUSBCFG_PHYSEL; #endif #if defined(USB_HS_PHYC) // Highspeed with embedded UTMI PHYC // Select UTMI Interface - usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_ULPI_UTMI_SEL; - usb_otg->GCCFG |= USB_OTG_GCCFG_PHYHSEN; + usb_otg->GUSBCFG &= ~GUSBCFG_ULPI_UTMI_SEL; + usb_otg->GCCFG |= GCCFG_PHYHSEN; // Enables control of a High Speed USB PHY USB_HS_PHYCInit(); @@ -418,17 +402,17 @@ void dcd_init (uint8_t rhport) } else { // Enable internal PHY - usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; + usb_otg->GUSBCFG |= GUSBCFG_PHYSEL; } - // Reset core after selecting PHY + // Reset core after selecting PHYst // Wait AHB IDLE, reset then wait until it is cleared - while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U) {} - usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; - while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST) {} + while ((usb_otg->GRSTCTL & GRSTCTL_AHBIDL) == 0U) {} + usb_otg->GRSTCTL |= GRSTCTL_CSRST; + while ((usb_otg->GRSTCTL & GRSTCTL_CSRST) == GRSTCTL_CSRST) {} // Restart PHY clock - *((volatile uint32_t *)(RHPORT_REGS_BASE + USB_OTG_PCGCCTL_BASE)) = 0; + *((volatile uint32_t *)(DWC2_REG_BASE + DWC2_PCGCCTL_BASE)) = 0; // Clear all interrupts usb_otg->GINTSTS |= usb_otg->GINTSTS; @@ -436,25 +420,25 @@ void dcd_init (uint8_t rhport) // Required as part of core initialization. // TODO: How should mode mismatch be handled? It will cause // the core to stop working/require reset. - usb_otg->GINTMSK |= USB_OTG_GINTMSK_OTGINT | USB_OTG_GINTMSK_MMISM; + usb_otg->GINTMSK |= GINTMSK_OTGINT | GINTMSK_MMISM; dwc2_device_t * dev = DEVICE_BASE(rhport); // If USB host misbehaves during status portion of control xfer // (non zero-length packet), send STALL back and discard. - dev->DCFG |= USB_OTG_DCFG_NZLSOHSK; + dev->DCFG |= DCFG_NZLSOHSK; set_speed(rhport, TUD_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL); // Enable internal USB transceiver, unless using HS core (port 1) with external PHY. - if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; + if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) usb_otg->GCCFG |= GCCFG_PWRDWN; - usb_otg->GINTMSK |= USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | - USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_WUIM | - USB_OTG_GINTMSK_RXFLVLM | (USE_SOF ? USB_OTG_GINTMSK_SOFM : 0); + usb_otg->GINTMSK |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | + GINTMSK_USBSUSPM | GINTMSK_WUIM | + GINTMSK_RXFLVLM | (USE_SOF ? GINTMSK_SOFM : 0); // Enable global interrupt - usb_otg->GAHBCFG |= USB_OTG_GAHBCFG_GINT; + usb_otg->GAHBCFG |= GAHBCFG_GINT; dcd_connect(rhport); } @@ -474,7 +458,7 @@ void dcd_int_disable (uint8_t rhport) void dcd_set_address (uint8_t rhport, uint8_t dev_addr) { dwc2_device_t * dev = DEVICE_BASE(rhport); - dev->DCFG = (dev->DCFG & ~USB_OTG_DCFG_DAD_Msk) | (dev_addr << USB_OTG_DCFG_DAD_Pos); + dev->DCFG = (dev->DCFG & ~DCFG_DAD_Msk) | (dev_addr << DCFG_DAD_Pos); // Response with status after changing device address dcd_edpt_xfer(rhport, tu_edpt_addr(0, TUSB_DIR_IN), NULL, 0); @@ -498,30 +482,30 @@ void dcd_remote_wakeup(uint8_t rhport) dwc2_device_t * dev = DEVICE_BASE(rhport); // set remote wakeup - dev->DCTL |= USB_OTG_DCTL_RWUSIG; + dev->DCTL |= DCTL_RWUSIG; // enable SOF to detect bus resume - usb_otg->GINTSTS = USB_OTG_GINTSTS_SOF; - usb_otg->GINTMSK |= USB_OTG_GINTMSK_SOFM; + usb_otg->GINTSTS = GINTSTS_SOF; + usb_otg->GINTMSK |= GINTMSK_SOFM; // Per specs: remote wakeup signal bit must be clear within 1-15ms remote_wakeup_delay(); - dev->DCTL &= ~USB_OTG_DCTL_RWUSIG; + dev->DCTL &= ~DCTL_RWUSIG; } void dcd_connect(uint8_t rhport) { (void) rhport; dwc2_device_t * dev = DEVICE_BASE(rhport); - dev->DCTL &= ~USB_OTG_DCTL_SDIS; + dev->DCTL &= ~DCTL_SDIS; } void dcd_disconnect(uint8_t rhport) { (void) rhport; dwc2_device_t * dev = DEVICE_BASE(rhport); - dev->DCTL |= USB_OTG_DCTL_SDIS; + dev->DCTL |= DCTL_SDIS; } @@ -563,12 +547,12 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) usb_otg->GRXFSIZ = sz; } - out_ep[epnum].DOEPCTL |= (1 << USB_OTG_DOEPCTL_USBAEP_Pos) | - (desc_edpt->bmAttributes.xfer << USB_OTG_DOEPCTL_EPTYP_Pos) | - (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? USB_OTG_DOEPCTL_SD0PID_SEVNFRM : 0) | - (xfer->max_size << USB_OTG_DOEPCTL_MPSIZ_Pos); + out_ep[epnum].DOEPCTL |= (1 << DOEPCTL_USBAEP_Pos) | + (desc_edpt->bmAttributes.xfer << DOEPCTL_EPTYP_Pos) | + (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DOEPCTL_SD0PID_SEVNFRM : 0) | + (xfer->max_size << DOEPCTL_MPSIZ_Pos); - dev->DAINTMSK |= (1 << (USB_OTG_DAINTMSK_OEPM_Pos + epnum)); + dev->DAINTMSK |= (1 << (DAINTMSK_OEPM_Pos + epnum)); } else { @@ -602,15 +586,15 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // DIEPTXF starts at FIFO #1. // Both TXFD and TXSA are in unit of 32-bit words. - usb_otg->DIEPTXF[epnum - 1] = (fifo_size << USB_OTG_DIEPTXF_INEPTXFD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + usb_otg->DIEPTXF[epnum - 1] = (fifo_size << DIEPTXF_INEPTXFD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); - in_ep[epnum].DIEPCTL |= (1 << USB_OTG_DIEPCTL_USBAEP_Pos) | - (epnum << USB_OTG_DIEPCTL_TXFNUM_Pos) | - (desc_edpt->bmAttributes.xfer << USB_OTG_DIEPCTL_EPTYP_Pos) | - (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? USB_OTG_DIEPCTL_SD0PID_SEVNFRM : 0) | - (xfer->max_size << USB_OTG_DIEPCTL_MPSIZ_Pos); + in_ep[epnum].DIEPCTL |= (1 << DIEPCTL_USBAEP_Pos) | + (epnum << DIEPCTL_TXFNUM_Pos) | + (desc_edpt->bmAttributes.xfer << DIEPCTL_EPTYP_Pos) | + (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DIEPCTL_SD0PID_SEVNFRM : 0) | + (xfer->max_size << DIEPCTL_MPSIZ_Pos); - dev->DAINTMSK |= (1 << (USB_OTG_DAINTMSK_IEPM_Pos + epnum)); + dev->DAINTMSK |= (1 << (DAINTMSK_IEPM_Pos + epnum)); } return true; @@ -627,7 +611,7 @@ void dcd_edpt_close_all (uint8_t rhport) dwc2_epin_t * in_ep = IN_EP_BASE(rhport); // Disable non-control interrupt - dev->DAINTMSK = (1 << USB_OTG_DAINTMSK_OEPM_Pos) | (1 << USB_OTG_DAINTMSK_IEPM_Pos); + dev->DAINTMSK = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); for(uint8_t n = 1; n < EP_MAX; n++) { @@ -719,42 +703,42 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) if(dir == TUSB_DIR_IN) { // Only disable currently enabled non-control endpoint - if ( (epnum == 0) || !(in_ep[epnum].DIEPCTL & USB_OTG_DIEPCTL_EPENA) ){ - in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_SNAK | (stall ? USB_OTG_DIEPCTL_STALL : 0); + if ( (epnum == 0) || !(in_ep[epnum].DIEPCTL & DIEPCTL_EPENA) ){ + in_ep[epnum].DIEPCTL |= DIEPCTL_SNAK | (stall ? DIEPCTL_STALL : 0); } else { // Stop transmitting packets and NAK IN xfers. - in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_SNAK; - while((in_ep[epnum].DIEPINT & USB_OTG_DIEPINT_INEPNE) == 0); + in_ep[epnum].DIEPCTL |= DIEPCTL_SNAK; + while((in_ep[epnum].DIEPINT & DIEPINT_INEPNE) == 0); // Disable the endpoint. - in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_EPDIS | (stall ? USB_OTG_DIEPCTL_STALL : 0); - while((in_ep[epnum].DIEPINT & USB_OTG_DIEPINT_EPDISD_Msk) == 0); - in_ep[epnum].DIEPINT = USB_OTG_DIEPINT_EPDISD; + in_ep[epnum].DIEPCTL |= DIEPCTL_EPDIS | (stall ? DIEPCTL_STALL : 0); + while((in_ep[epnum].DIEPINT & DIEPINT_EPDISD_Msk) == 0); + in_ep[epnum].DIEPINT = DIEPINT_EPDISD; } // Flush the FIFO, and wait until we have confirmed it cleared. - usb_otg->GRSTCTL |= (epnum << USB_OTG_GRSTCTL_TXFNUM_Pos); - usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_TXFFLSH; - while((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH_Msk) != 0); + usb_otg->GRSTCTL |= (epnum << GRSTCTL_TXFNUM_Pos); + usb_otg->GRSTCTL |= GRSTCTL_TXFFLSH; + while((usb_otg->GRSTCTL & GRSTCTL_TXFFLSH_Msk) != 0); } else { // Only disable currently enabled non-control endpoint - if ( (epnum == 0) || !(out_ep[epnum].DOEPCTL & USB_OTG_DOEPCTL_EPENA) ){ - out_ep[epnum].DOEPCTL |= stall ? USB_OTG_DOEPCTL_STALL : 0; + if ( (epnum == 0) || !(out_ep[epnum].DOEPCTL & DOEPCTL_EPENA) ){ + out_ep[epnum].DOEPCTL |= stall ? DOEPCTL_STALL : 0; } else { // Asserting GONAK is required to STALL an OUT endpoint. // Simpler to use polling here, we don't use the "B"OUTNAKEFF interrupt // anyway, and it can't be cleared by user code. If this while loop never // finishes, we have bigger problems than just the stack. - dev->DCTL |= USB_OTG_DCTL_SGONAK; - while((usb_otg->GINTSTS & USB_OTG_GINTSTS_BOUTNAKEFF_Msk) == 0); + dev->DCTL |= DCTL_SGONAK; + while((usb_otg->GINTSTS & GINTSTS_BOUTNAKEFF_Msk) == 0); // Ditto here- disable the endpoint. - out_ep[epnum].DOEPCTL |= USB_OTG_DOEPCTL_EPDIS | (stall ? USB_OTG_DOEPCTL_STALL : 0); - while((out_ep[epnum].DOEPINT & USB_OTG_DOEPINT_EPDISD_Msk) == 0); - out_ep[epnum].DOEPINT = USB_OTG_DOEPINT_EPDISD; + out_ep[epnum].DOEPCTL |= DOEPCTL_EPDIS | (stall ? DOEPCTL_STALL : 0); + while((out_ep[epnum].DOEPINT & DOEPINT_EPDISD_Msk) == 0); + out_ep[epnum].DOEPINT = DOEPINT_EPDISD; // Allow other OUT endpoints to keep receiving. - dev->DCTL |= USB_OTG_DCTL_CGONAK; + dev->DCTL |= DCTL_CGONAK; } } } @@ -776,8 +760,8 @@ void dcd_edpt_close (uint8_t rhport, uint8_t ep_addr) if (dir == TUSB_DIR_IN) { - uint16_t const fifo_size = (usb_otg->DIEPTXF[epnum - 1] & USB_OTG_DIEPTXF_INEPTXFD_Msk) >> USB_OTG_DIEPTXF_INEPTXFD_Pos; - uint16_t const fifo_start = (usb_otg->DIEPTXF[epnum - 1] & USB_OTG_DIEPTXF_INEPTXSA_Msk) >> USB_OTG_DIEPTXF_INEPTXSA_Pos; + uint16_t const fifo_size = (usb_otg->DIEPTXF[epnum - 1] & DIEPTXF_INEPTXFD_Msk) >> DIEPTXF_INEPTXFD_Pos; + uint16_t const fifo_start = (usb_otg->DIEPTXF[epnum - 1] & DIEPTXF_INEPTXSA_Msk) >> DIEPTXF_INEPTXSA_Pos; // For now only the last opened endpoint can be closed without fuss. TU_ASSERT(fifo_start == EP_FIFO_SIZE/4 - _allocated_fifo_words_tx,); _allocated_fifo_words_tx -= fifo_size; @@ -805,11 +789,11 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) // Clear stall and reset data toggle if(dir == TUSB_DIR_IN) { - in_ep[epnum].DIEPCTL &= ~USB_OTG_DIEPCTL_STALL; - in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; + in_ep[epnum].DIEPCTL &= ~DIEPCTL_STALL; + in_ep[epnum].DIEPCTL |= DIEPCTL_SD0PID_SEVNFRM; } else { - out_ep[epnum].DOEPCTL &= ~USB_OTG_DOEPCTL_STALL; - out_ep[epnum].DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; + out_ep[epnum].DOEPCTL &= ~DOEPCTL_STALL; + out_ep[epnum].DOEPCTL |= DOEPCTL_SD0PID_SEVNFRM; } } @@ -882,9 +866,9 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { // Pop control word off FIFO uint32_t ctl_word = usb_otg->GRXSTSP; - uint8_t pktsts = (ctl_word & USB_OTG_GRXSTSP_PKTSTS_Msk) >> USB_OTG_GRXSTSP_PKTSTS_Pos; - uint8_t epnum = (ctl_word & USB_OTG_GRXSTSP_EPNUM_Msk) >> USB_OTG_GRXSTSP_EPNUM_Pos; - uint16_t bcnt = (ctl_word & USB_OTG_GRXSTSP_BCNT_Msk) >> USB_OTG_GRXSTSP_BCNT_Pos; + uint8_t pktsts = (ctl_word & GRXSTSP_PKTSTS_Msk) >> GRXSTSP_PKTSTS_Pos; + uint8_t epnum = (ctl_word & GRXSTSP_EPNUM_Msk) >> GRXSTSP_EPNUM_Pos; + uint16_t bcnt = (ctl_word & GRXSTSP_BCNT_Msk) >> GRXSTSP_BCNT_Pos; switch(pktsts) { case 0x01: // Global OUT NAK (Interrupt) @@ -911,7 +895,7 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { // Truncate transfer length in case of short packet if(bcnt < xfer->max_size) { - xfer->total_len -= (out_ep[epnum].DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DOEPTSIZ_XFRSIZ_Pos; + xfer->total_len -= (out_ep[epnum].DOEPTSIZ & DOEPTSIZ_XFRSIZ_Msk) >> DOEPTSIZ_XFRSIZ_Pos; if(epnum == 0) { xfer->total_len -= ep0_pending[TUSB_DIR_OUT]; ep0_pending[TUSB_DIR_OUT] = 0; @@ -924,7 +908,7 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { break; case 0x04: // Setup packet done (Interrupt) - out_ep[epnum].DOEPTSIZ |= (3 << USB_OTG_DOEPTSIZ_STUPCNT_Pos); + out_ep[epnum].DOEPTSIZ |= (3 << DOEPTSIZ_STUPCNT_Pos); break; case 0x06: // Setup packet recvd @@ -946,16 +930,16 @@ static void handle_epout_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epout_t for(uint8_t n = 0; n < EP_MAX; n++) { xfer_ctl_t * xfer = XFER_CTL_BASE(n, TUSB_DIR_OUT); - if(dev->DAINT & (1 << (USB_OTG_DAINT_OEPINT_Pos + n))) { + if(dev->DAINT & (1 << (DAINT_OEPINT_Pos + n))) { // SETUP packet Setup Phase done. - if(out_ep[n].DOEPINT & USB_OTG_DOEPINT_STUP) { - out_ep[n].DOEPINT = USB_OTG_DOEPINT_STUP; + if(out_ep[n].DOEPINT & DOEPINT_STUP) { + out_ep[n].DOEPINT = DOEPINT_STUP; dcd_event_setup_received(rhport, (uint8_t*) &_setup_packet[0], true); } // OUT XFER complete - if(out_ep[n].DOEPINT & USB_OTG_DOEPINT_XFRC) { - out_ep[n].DOEPINT = USB_OTG_DOEPINT_XFRC; + if(out_ep[n].DOEPINT & DOEPINT_XFRC) { + out_ep[n].DOEPINT = DOEPINT_XFRC; // EP0 can only handle one packet if((n == 0) && ep0_pending[TUSB_DIR_OUT]) { @@ -976,12 +960,12 @@ static void handle_epin_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epin_t * { xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_IN); - if ( dev->DAINT & (1 << (USB_OTG_DAINT_IEPINT_Pos + n)) ) + if ( dev->DAINT & (1 << (DAINT_IEPINT_Pos + n)) ) { // IN XFER complete (entire xfer). - if ( in_ep[n].DIEPINT & USB_OTG_DIEPINT_XFRC ) + if ( in_ep[n].DIEPINT & DIEPINT_XFRC ) { - in_ep[n].DIEPINT = USB_OTG_DIEPINT_XFRC; + in_ep[n].DIEPINT = DIEPINT_XFRC; // EP0 can only handle one packet if((n == 0) && ep0_pending[TUSB_DIR_IN]) { @@ -993,26 +977,26 @@ static void handle_epin_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epin_t * } // XFER FIFO empty - if ( (in_ep[n].DIEPINT & USB_OTG_DIEPINT_TXFE) && (dev->DIEPEMPMSK & (1 << n)) ) + if ( (in_ep[n].DIEPINT & DIEPINT_TXFE) && (dev->DIEPEMPMSK & (1 << n)) ) { // DIEPINT's TXFE bit is read-only, software cannot clear it. // It will only be cleared by hardware when written bytes is more than // - 64 bytes or // - Half of TX FIFO size (configured by DIEPTXF) - uint16_t remaining_packets = (in_ep[n].DIEPTSIZ & USB_OTG_DIEPTSIZ_PKTCNT_Msk) >> USB_OTG_DIEPTSIZ_PKTCNT_Pos; + uint16_t remaining_packets = (in_ep[n].DIEPTSIZ & DIEPTSIZ_PKTCNT_Msk) >> DIEPTSIZ_PKTCNT_Pos; // Process every single packet (only whole packets can be written to fifo) for(uint16_t i = 0; i < remaining_packets; i++) { - uint16_t const remaining_bytes = (in_ep[n].DIEPTSIZ & USB_OTG_DIEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DIEPTSIZ_XFRSIZ_Pos; + uint16_t const remaining_bytes = (in_ep[n].DIEPTSIZ & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos; // Packet can not be larger than ep max size uint16_t const packet_size = tu_min16(remaining_bytes, xfer->max_size); // It's only possible to write full packets into FIFO. Therefore DTXFSTS register of current // EP has to be checked if the buffer can take another WHOLE packet - if(packet_size > ((in_ep[n].DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV_Msk) << 2)) break; + if(packet_size > ((in_ep[n].DTXFSTS & DTXFSTS_INEPTFSAV_Msk) << 2)) break; // Push packet to Tx-FIFO if (xfer->ff) @@ -1030,7 +1014,7 @@ static void handle_epin_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epin_t * } // Turn off TXFE if all bytes are written. - if (((in_ep[n].DIEPTSIZ & USB_OTG_DIEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DIEPTSIZ_XFRSIZ_Pos) == 0) + if (((in_ep[n].DIEPTSIZ & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos) == 0) { dev->DIEPEMPMSK &= ~(1 << n); } @@ -1048,18 +1032,18 @@ void dcd_int_handler(uint8_t rhport) uint32_t const int_status = usb_otg->GINTSTS & usb_otg->GINTMSK; - if(int_status & USB_OTG_GINTSTS_USBRST) + if(int_status & GINTSTS_USBRST) { // USBRST is start of reset. - usb_otg->GINTSTS = USB_OTG_GINTSTS_USBRST; + usb_otg->GINTSTS = GINTSTS_USBRST; bus_reset(rhport); } - if(int_status & USB_OTG_GINTSTS_ENUMDNE) + if(int_status & GINTSTS_ENUMDNE) { // ENUMDNE is the end of reset where speed of the link is detected - usb_otg->GINTSTS = USB_OTG_GINTSTS_ENUMDNE; + usb_otg->GINTSTS = GINTSTS_ENUMDNE; tusb_speed_t const speed = get_speed(rhport); @@ -1067,27 +1051,27 @@ void dcd_int_handler(uint8_t rhport) dcd_event_bus_reset(rhport, speed, true); } - if(int_status & USB_OTG_GINTSTS_USBSUSP) + if(int_status & GINTSTS_USBSUSP) { - usb_otg->GINTSTS = USB_OTG_GINTSTS_USBSUSP; + usb_otg->GINTSTS = GINTSTS_USBSUSP; dcd_event_bus_signal(rhport, DCD_EVENT_SUSPEND, true); } - if(int_status & USB_OTG_GINTSTS_WKUINT) + if(int_status & GINTSTS_WKUINT) { - usb_otg->GINTSTS = USB_OTG_GINTSTS_WKUINT; + usb_otg->GINTSTS = GINTSTS_WKUINT; dcd_event_bus_signal(rhport, DCD_EVENT_RESUME, true); } - // TODO check USB_OTG_GINTSTS_DISCINT for disconnect detection - // if(int_status & USB_OTG_GINTSTS_DISCINT) + // TODO check GINTSTS_DISCINT for disconnect detection + // if(int_status & GINTSTS_DISCINT) - if(int_status & USB_OTG_GINTSTS_OTGINT) + if(int_status & GINTSTS_OTGINT) { // OTG INT bit is read-only uint32_t const otg_int = usb_otg->GOTGINT; - if (otg_int & USB_OTG_GOTGINT_SEDET) + if (otg_int & GOTGINT_SEDET) { dcd_event_bus_signal(rhport, DCD_EVENT_UNPLUGGED, true); } @@ -1095,29 +1079,29 @@ void dcd_int_handler(uint8_t rhport) usb_otg->GOTGINT = otg_int; } - if(int_status & USB_OTG_GINTSTS_SOF) + if(int_status & GINTSTS_SOF) { - usb_otg->GINTSTS = USB_OTG_GINTSTS_SOF; + usb_otg->GINTSTS = GINTSTS_SOF; // Disable SOF interrupt since currently only used for remote wakeup detection - usb_otg->GINTMSK &= ~USB_OTG_GINTMSK_SOFM; + usb_otg->GINTMSK &= ~GINTMSK_SOFM; dcd_event_bus_signal(rhport, DCD_EVENT_SOF, true); } // RxFIFO non-empty interrupt handling. - if(int_status & USB_OTG_GINTSTS_RXFLVL) + if(int_status & GINTSTS_RXFLVL) { // RXFLVL bit is read-only // Mask out RXFLVL while reading data from FIFO - usb_otg->GINTMSK &= ~USB_OTG_GINTMSK_RXFLVLM; + usb_otg->GINTMSK &= ~GINTMSK_RXFLVLM; // Loop until all available packets were handled do { handle_rxflvl_ints(rhport, out_ep); - } while(usb_otg->GINTSTS & USB_OTG_GINTSTS_RXFLVL); + } while(usb_otg->GINTSTS & GINTSTS_RXFLVL); // Manage RX FIFO size if (_out_ep_closed) @@ -1128,25 +1112,25 @@ void dcd_int_handler(uint8_t rhport) _out_ep_closed = false; } - usb_otg->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; + usb_otg->GINTMSK |= GINTMSK_RXFLVLM; } // OUT endpoint interrupt handling. - if(int_status & USB_OTG_GINTSTS_OEPINT) + if(int_status & GINTSTS_OEPINT) { // OEPINT is read-only handle_epout_ints(rhport, dev, out_ep); } // IN endpoint interrupt handling. - if(int_status & USB_OTG_GINTSTS_IEPINT) + if(int_status & GINTSTS_IEPINT) { // IEPINT bit read-only handle_epin_ints(rhport, dev, in_ep); } // // Check for Incomplete isochronous IN transfer - // if(int_status & USB_OTG_GINTSTS_IISOIXFR) { + // if(int_status & GINTSTS_IISOIXFR) { // printf(" IISOIXFR!\r\n"); //// TU_LOG2(" IISOIXFR!\r\n"); // } diff --git a/src/portable/synopsys/dwc2/dwc2_gd32.h b/src/portable/synopsys/dwc2/dwc2_gd32.h index 5abbd225f..3ace4d484 100644 --- a/src/portable/synopsys/dwc2/dwc2_gd32.h +++ b/src/portable/synopsys/dwc2/dwc2_gd32.h @@ -32,9 +32,10 @@ #define __NOP() __asm volatile ("nop") // These numbers are the same for the whole GD32VF103 family. -#define OTG_FS_IRQn 86 -#define EP_MAX_FS 4 -#define EP_FIFO_SIZE_FS 1280 +#define RHPORT_IRQn 86 +#define EP_MAX 4 +#define EP_FIFO_SIZE 1280 +#define DWC2_REG_BASE 0x50000000UL // The GD32VF103 is a RISC-V MCU, which implements the ECLIC Core-Local // Interrupt Controller by Nuclei. It is nearly API compatible to the diff --git a/src/portable/synopsys/dwc2/dwc2_stm32.h b/src/portable/synopsys/dwc2/dwc2_stm32.h index efed6d14a..3a5e1a9ac 100644 --- a/src/portable/synopsys/dwc2/dwc2_stm32.h +++ b/src/portable/synopsys/dwc2/dwc2_stm32.h @@ -69,4 +69,19 @@ #error "Unsupported MCUs" #endif +// On STM32 we associate Port0 to OTG_FS, and Port1 to OTG_HS +#if TUD_OPT_RHPORT == 0 + #define EP_MAX EP_MAX_FS + #define EP_FIFO_SIZE EP_FIFO_SIZE_FS + #define DWC2_REG_BASE USB_OTG_FS_PERIPH_BASE + #define RHPORT_IRQn OTG_FS_IRQn + +#else + #define EP_MAX EP_MAX_HS + #define EP_FIFO_SIZE EP_FIFO_SIZE_HS + #define DWC2_REG_BASE USB_OTG_HS_PERIPH_BASE + #define RHPORT_IRQn OTG_HS_IRQn + +#endif + #endif /* DWC2_STM32_H_ */ diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 8f48c71eb..5f3b4a420 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -39,14 +39,14 @@ typedef struct { -__IO uint32_t USB_HS_PHYC_PLL; /*!< This register is used to control the PLL of the HS PHY. 000h */ +__IO uint32_t HS_PHYC_PLL; /*!< This register is used to control the PLL of the HS PHY. 000h */ __IO uint32_t Reserved04; /*!< Reserved 004h */ __IO uint32_t Reserved08; /*!< Reserved 008h */ -__IO uint32_t USB_HS_PHYC_TUNE; /*!< This register is used to control the tuning interface of the High Speed PHY. 00Ch */ +__IO uint32_t HS_PHYC_TUNE; /*!< This register is used to control the tuning interface of the High Speed PHY. 00Ch */ __IO uint32_t Reserved10; /*!< Reserved 010h */ __IO uint32_t Reserved14; /*!< Reserved 014h */ -__IO uint32_t USB_HS_PHYC_LDO; /*!< This register is used to control the regulator (LDO). 018h */ -} USB_HS_PHYC_GlobalTypeDef; +__IO uint32_t HS_PHYC_LDO; /*!< This register is used to control the regulator (LDO). 018h */ +} HS_PHYC_GlobalTypeDef; #endif // Core @@ -156,7 +156,10 @@ typedef struct } dwc2_epout_t; -/*!< USB registers base address */ +//--------------------------------------------------------------------+ +// Register Base Address +//--------------------------------------------------------------------+ + #define DWC2_GLOBAL_BASE 0x00000000UL #define DWC2_DEVICE_BASE 0x00000800UL #define DWC2_IN_ENDPOINT_BASE 0x00000900UL @@ -170,1299 +173,1438 @@ typedef struct #define DWC2_FIFO_BASE 0x00001000UL #define DWC2_FIFO_SIZE 0x00001000UL -#if 0 -/******************************************************************************/ -/* */ -/* USB_OTG */ -/* */ -/******************************************************************************/ -/******************** Bit definition for USB_OTG_GOTGCTL register ***********/ -#define USB_OTG_GOTGCTL_SRQSCS_Pos (0U) -#define USB_OTG_GOTGCTL_SRQSCS_Msk (0x1UL << USB_OTG_GOTGCTL_SRQSCS_Pos) /*!< 0x00000001 */ -#define USB_OTG_GOTGCTL_SRQSCS USB_OTG_GOTGCTL_SRQSCS_Msk /*!< Session request success */ -#define USB_OTG_GOTGCTL_SRQ_Pos (1U) -#define USB_OTG_GOTGCTL_SRQ_Msk (0x1UL << USB_OTG_GOTGCTL_SRQ_Pos) /*!< 0x00000002 */ -#define USB_OTG_GOTGCTL_SRQ USB_OTG_GOTGCTL_SRQ_Msk /*!< Session request */ -#define USB_OTG_GOTGCTL_HNGSCS_Pos (8U) -#define USB_OTG_GOTGCTL_HNGSCS_Msk (0x1UL << USB_OTG_GOTGCTL_HNGSCS_Pos) /*!< 0x00000100 */ -#define USB_OTG_GOTGCTL_HNGSCS USB_OTG_GOTGCTL_HNGSCS_Msk /*!< Host set HNP enable */ -#define USB_OTG_GOTGCTL_HNPRQ_Pos (9U) -#define USB_OTG_GOTGCTL_HNPRQ_Msk (0x1UL << USB_OTG_GOTGCTL_HNPRQ_Pos) /*!< 0x00000200 */ -#define USB_OTG_GOTGCTL_HNPRQ USB_OTG_GOTGCTL_HNPRQ_Msk /*!< HNP request */ -#define USB_OTG_GOTGCTL_HSHNPEN_Pos (10U) -#define USB_OTG_GOTGCTL_HSHNPEN_Msk (0x1UL << USB_OTG_GOTGCTL_HSHNPEN_Pos) /*!< 0x00000400 */ -#define USB_OTG_GOTGCTL_HSHNPEN USB_OTG_GOTGCTL_HSHNPEN_Msk /*!< Host set HNP enable */ -#define USB_OTG_GOTGCTL_DHNPEN_Pos (11U) -#define USB_OTG_GOTGCTL_DHNPEN_Msk (0x1UL << USB_OTG_GOTGCTL_DHNPEN_Pos) /*!< 0x00000800 */ -#define USB_OTG_GOTGCTL_DHNPEN USB_OTG_GOTGCTL_DHNPEN_Msk /*!< Device HNP enabled */ -#define USB_OTG_GOTGCTL_CIDSTS_Pos (16U) -#define USB_OTG_GOTGCTL_CIDSTS_Msk (0x1UL << USB_OTG_GOTGCTL_CIDSTS_Pos) /*!< 0x00010000 */ -#define USB_OTG_GOTGCTL_CIDSTS USB_OTG_GOTGCTL_CIDSTS_Msk /*!< Connector ID status */ -#define USB_OTG_GOTGCTL_DBCT_Pos (17U) -#define USB_OTG_GOTGCTL_DBCT_Msk (0x1UL << USB_OTG_GOTGCTL_DBCT_Pos) /*!< 0x00020000 */ -#define USB_OTG_GOTGCTL_DBCT USB_OTG_GOTGCTL_DBCT_Msk /*!< Long/short debounce time */ -#define USB_OTG_GOTGCTL_ASVLD_Pos (18U) -#define USB_OTG_GOTGCTL_ASVLD_Msk (0x1UL << USB_OTG_GOTGCTL_ASVLD_Pos) /*!< 0x00040000 */ -#define USB_OTG_GOTGCTL_ASVLD USB_OTG_GOTGCTL_ASVLD_Msk /*!< A-session valid */ -#define USB_OTG_GOTGCTL_BSVLD_Pos (19U) -#define USB_OTG_GOTGCTL_BSVLD_Msk (0x1UL << USB_OTG_GOTGCTL_BSVLD_Pos) /*!< 0x00080000 */ -#define USB_OTG_GOTGCTL_BSVLD USB_OTG_GOTGCTL_BSVLD_Msk /*!< B-session valid */ +//--------------------------------------------------------------------+ +// Register Bit Definitions +//--------------------------------------------------------------------+ -/******************** Bit definition for USB_OTG_HCFG register ********************/ +/******************** Bit definition for GOTGCTL register ********************/ +#define GOTGCTL_SRQSCS_Pos (0U) +#define GOTGCTL_SRQSCS_Msk (0x1UL << GOTGCTL_SRQSCS_Pos) /*!< 0x00000001 */ +#define GOTGCTL_SRQSCS GOTGCTL_SRQSCS_Msk /*!< Session request success */ +#define GOTGCTL_SRQ_Pos (1U) +#define GOTGCTL_SRQ_Msk (0x1UL << GOTGCTL_SRQ_Pos) /*!< 0x00000002 */ +#define GOTGCTL_SRQ GOTGCTL_SRQ_Msk /*!< Session request */ +#define GOTGCTL_VBVALOEN_Pos (2U) +#define GOTGCTL_VBVALOEN_Msk (0x1UL << GOTGCTL_VBVALOEN_Pos) /*!< 0x00000004 */ +#define GOTGCTL_VBVALOEN GOTGCTL_VBVALOEN_Msk /*!< VBUS valid override enable */ +#define GOTGCTL_VBVALOVAL_Pos (3U) +#define GOTGCTL_VBVALOVAL_Msk (0x1UL << GOTGCTL_VBVALOVAL_Pos) /*!< 0x00000008 */ +#define GOTGCTL_VBVALOVAL GOTGCTL_VBVALOVAL_Msk /*!< VBUS valid override value */ +#define GOTGCTL_AVALOEN_Pos (4U) +#define GOTGCTL_AVALOEN_Msk (0x1UL << GOTGCTL_AVALOEN_Pos) /*!< 0x00000010 */ +#define GOTGCTL_AVALOEN GOTGCTL_AVALOEN_Msk /*!< A-peripheral session valid override enable */ +#define GOTGCTL_AVALOVAL_Pos (5U) +#define GOTGCTL_AVALOVAL_Msk (0x1UL << GOTGCTL_AVALOVAL_Pos) /*!< 0x00000020 */ +#define GOTGCTL_AVALOVAL GOTGCTL_AVALOVAL_Msk /*!< A-peripheral session valid override value */ +#define GOTGCTL_BVALOEN_Pos (6U) +#define GOTGCTL_BVALOEN_Msk (0x1UL << GOTGCTL_BVALOEN_Pos) /*!< 0x00000040 */ +#define GOTGCTL_BVALOEN GOTGCTL_BVALOEN_Msk /*!< B-peripheral session valid override enable */ +#define GOTGCTL_BVALOVAL_Pos (7U) +#define GOTGCTL_BVALOVAL_Msk (0x1UL << GOTGCTL_BVALOVAL_Pos) /*!< 0x00000080 */ +#define GOTGCTL_BVALOVAL GOTGCTL_BVALOVAL_Msk /*!< B-peripheral session valid override value */ +#define GOTGCTL_HNGSCS_Pos (8U) +#define GOTGCTL_HNGSCS_Msk (0x1UL << GOTGCTL_HNGSCS_Pos) /*!< 0x00000100 */ +#define GOTGCTL_HNGSCS GOTGCTL_HNGSCS_Msk /*!< Host set HNP enable */ +#define GOTGCTL_HNPRQ_Pos (9U) +#define GOTGCTL_HNPRQ_Msk (0x1UL << GOTGCTL_HNPRQ_Pos) /*!< 0x00000200 */ +#define GOTGCTL_HNPRQ GOTGCTL_HNPRQ_Msk /*!< HNP request */ +#define GOTGCTL_HSHNPEN_Pos (10U) +#define GOTGCTL_HSHNPEN_Msk (0x1UL << GOTGCTL_HSHNPEN_Pos) /*!< 0x00000400 */ +#define GOTGCTL_HSHNPEN GOTGCTL_HSHNPEN_Msk /*!< Host set HNP enable */ +#define GOTGCTL_DHNPEN_Pos (11U) +#define GOTGCTL_DHNPEN_Msk (0x1UL << GOTGCTL_DHNPEN_Pos) /*!< 0x00000800 */ +#define GOTGCTL_DHNPEN GOTGCTL_DHNPEN_Msk /*!< Device HNP enabled */ +#define GOTGCTL_EHEN_Pos (12U) +#define GOTGCTL_EHEN_Msk (0x1UL << GOTGCTL_EHEN_Pos) /*!< 0x00001000 */ +#define GOTGCTL_EHEN GOTGCTL_EHEN_Msk /*!< Embedded host enable */ +#define GOTGCTL_CIDSTS_Pos (16U) +#define GOTGCTL_CIDSTS_Msk (0x1UL << GOTGCTL_CIDSTS_Pos) /*!< 0x00010000 */ +#define GOTGCTL_CIDSTS GOTGCTL_CIDSTS_Msk /*!< Connector ID status */ +#define GOTGCTL_DBCT_Pos (17U) +#define GOTGCTL_DBCT_Msk (0x1UL << GOTGCTL_DBCT_Pos) /*!< 0x00020000 */ +#define GOTGCTL_DBCT GOTGCTL_DBCT_Msk /*!< Long/short debounce time */ +#define GOTGCTL_ASVLD_Pos (18U) +#define GOTGCTL_ASVLD_Msk (0x1UL << GOTGCTL_ASVLD_Pos) /*!< 0x00040000 */ +#define GOTGCTL_ASVLD GOTGCTL_ASVLD_Msk /*!< A-session valid */ +#define GOTGCTL_BSESVLD_Pos (19U) +#define GOTGCTL_BSESVLD_Msk (0x1UL << GOTGCTL_BSESVLD_Pos) /*!< 0x00080000 */ +#define GOTGCTL_BSESVLD GOTGCTL_BSESVLD_Msk /*!< B-session valid */ +#define GOTGCTL_OTGVER_Pos (20U) +#define GOTGCTL_OTGVER_Msk (0x1UL << GOTGCTL_OTGVER_Pos) /*!< 0x00100000 */ +#define GOTGCTL_OTGVER GOTGCTL_OTGVER_Msk /*!< OTG version */ -#define USB_OTG_HCFG_FSLSPCS_Pos (0U) -#define USB_OTG_HCFG_FSLSPCS_Msk (0x3UL << USB_OTG_HCFG_FSLSPCS_Pos) /*!< 0x00000003 */ -#define USB_OTG_HCFG_FSLSPCS USB_OTG_HCFG_FSLSPCS_Msk /*!< FS/LS PHY clock select */ -#define USB_OTG_HCFG_FSLSPCS_0 (0x1UL << USB_OTG_HCFG_FSLSPCS_Pos) /*!< 0x00000001 */ -#define USB_OTG_HCFG_FSLSPCS_1 (0x2UL << USB_OTG_HCFG_FSLSPCS_Pos) /*!< 0x00000002 */ -#define USB_OTG_HCFG_FSLSS_Pos (2U) -#define USB_OTG_HCFG_FSLSS_Msk (0x1UL << USB_OTG_HCFG_FSLSS_Pos) /*!< 0x00000004 */ -#define USB_OTG_HCFG_FSLSS USB_OTG_HCFG_FSLSS_Msk /*!< FS- and LS-only support */ +/******************** Bit definition for HCFG register ********************/ +#define HCFG_FSLSPCS_Pos (0U) +#define HCFG_FSLSPCS_Msk (0x3UL << HCFG_FSLSPCS_Pos) /*!< 0x00000003 */ +#define HCFG_FSLSPCS HCFG_FSLSPCS_Msk /*!< FS/LS PHY clock select */ +#define HCFG_FSLSPCS_0 (0x1UL << HCFG_FSLSPCS_Pos) /*!< 0x00000001 */ +#define HCFG_FSLSPCS_1 (0x2UL << HCFG_FSLSPCS_Pos) /*!< 0x00000002 */ +#define HCFG_FSLSS_Pos (2U) +#define HCFG_FSLSS_Msk (0x1UL << HCFG_FSLSS_Pos) /*!< 0x00000004 */ +#define HCFG_FSLSS HCFG_FSLSS_Msk /*!< FS- and LS-only support */ -/******************** Bit definition for USB_OTG_DCFG register ********************/ +/******************** Bit definition for DCFG register ********************/ +#define DCFG_DSPD_Pos (0U) +#define DCFG_DSPD_Msk (0x3UL << DCFG_DSPD_Pos) /*!< 0x00000003 */ +#define DCFG_DSPD DCFG_DSPD_Msk /*!< Device speed */ +#define DCFG_DSPD_0 (0x1UL << DCFG_DSPD_Pos) /*!< 0x00000001 */ +#define DCFG_DSPD_1 (0x2UL << DCFG_DSPD_Pos) /*!< 0x00000002 */ +#define DCFG_NZLSOHSK_Pos (2U) +#define DCFG_NZLSOHSK_Msk (0x1UL << DCFG_NZLSOHSK_Pos) /*!< 0x00000004 */ +#define DCFG_NZLSOHSK DCFG_NZLSOHSK_Msk /*!< Nonzero-length status OUT handshake */ -#define USB_OTG_DCFG_DSPD_Pos (0U) -#define USB_OTG_DCFG_DSPD_Msk (0x3UL << USB_OTG_DCFG_DSPD_Pos) /*!< 0x00000003 */ -#define USB_OTG_DCFG_DSPD USB_OTG_DCFG_DSPD_Msk /*!< Device speed */ -#define USB_OTG_DCFG_DSPD_0 (0x1UL << USB_OTG_DCFG_DSPD_Pos) /*!< 0x00000001 */ -#define USB_OTG_DCFG_DSPD_1 (0x2UL << USB_OTG_DCFG_DSPD_Pos) /*!< 0x00000002 */ -#define USB_OTG_DCFG_NZLSOHSK_Pos (2U) -#define USB_OTG_DCFG_NZLSOHSK_Msk (0x1UL << USB_OTG_DCFG_NZLSOHSK_Pos) /*!< 0x00000004 */ -#define USB_OTG_DCFG_NZLSOHSK USB_OTG_DCFG_NZLSOHSK_Msk /*!< Nonzero-length status OUT handshake */ +#define DCFG_DAD_Pos (4U) +#define DCFG_DAD_Msk (0x7FUL << DCFG_DAD_Pos) /*!< 0x000007F0 */ +#define DCFG_DAD DCFG_DAD_Msk /*!< Device address */ +#define DCFG_DAD_0 (0x01UL << DCFG_DAD_Pos) /*!< 0x00000010 */ +#define DCFG_DAD_1 (0x02UL << DCFG_DAD_Pos) /*!< 0x00000020 */ +#define DCFG_DAD_2 (0x04UL << DCFG_DAD_Pos) /*!< 0x00000040 */ +#define DCFG_DAD_3 (0x08UL << DCFG_DAD_Pos) /*!< 0x00000080 */ +#define DCFG_DAD_4 (0x10UL << DCFG_DAD_Pos) /*!< 0x00000100 */ +#define DCFG_DAD_5 (0x20UL << DCFG_DAD_Pos) /*!< 0x00000200 */ +#define DCFG_DAD_6 (0x40UL << DCFG_DAD_Pos) /*!< 0x00000400 */ -#define USB_OTG_DCFG_DAD_Pos (4U) -#define USB_OTG_DCFG_DAD_Msk (0x7FUL << USB_OTG_DCFG_DAD_Pos) /*!< 0x000007F0 */ -#define USB_OTG_DCFG_DAD USB_OTG_DCFG_DAD_Msk /*!< Device address */ -#define USB_OTG_DCFG_DAD_0 (0x01UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000010 */ -#define USB_OTG_DCFG_DAD_1 (0x02UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000020 */ -#define USB_OTG_DCFG_DAD_2 (0x04UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000040 */ -#define USB_OTG_DCFG_DAD_3 (0x08UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000080 */ -#define USB_OTG_DCFG_DAD_4 (0x10UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000100 */ -#define USB_OTG_DCFG_DAD_5 (0x20UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000200 */ -#define USB_OTG_DCFG_DAD_6 (0x40UL << USB_OTG_DCFG_DAD_Pos) /*!< 0x00000400 */ +#define DCFG_PFIVL_Pos (11U) +#define DCFG_PFIVL_Msk (0x3UL << DCFG_PFIVL_Pos) /*!< 0x00001800 */ +#define DCFG_PFIVL DCFG_PFIVL_Msk /*!< Periodic (micro)frame interval */ +#define DCFG_PFIVL_0 (0x1UL << DCFG_PFIVL_Pos) /*!< 0x00000800 */ +#define DCFG_PFIVL_1 (0x2UL << DCFG_PFIVL_Pos) /*!< 0x00001000 */ -#define USB_OTG_DCFG_PFIVL_Pos (11U) -#define USB_OTG_DCFG_PFIVL_Msk (0x3UL << USB_OTG_DCFG_PFIVL_Pos) /*!< 0x00001800 */ -#define USB_OTG_DCFG_PFIVL USB_OTG_DCFG_PFIVL_Msk /*!< Periodic (micro)frame interval */ -#define USB_OTG_DCFG_PFIVL_0 (0x1UL << USB_OTG_DCFG_PFIVL_Pos) /*!< 0x00000800 */ -#define USB_OTG_DCFG_PFIVL_1 (0x2UL << USB_OTG_DCFG_PFIVL_Pos) /*!< 0x00001000 */ +#define DCFG_PERSCHIVL_Pos (24U) +#define DCFG_PERSCHIVL_Msk (0x3UL << DCFG_PERSCHIVL_Pos) /*!< 0x03000000 */ +#define DCFG_PERSCHIVL DCFG_PERSCHIVL_Msk /*!< Periodic scheduling interval */ +#define DCFG_PERSCHIVL_0 (0x1UL << DCFG_PERSCHIVL_Pos) /*!< 0x01000000 */ +#define DCFG_PERSCHIVL_1 (0x2UL << DCFG_PERSCHIVL_Pos) /*!< 0x02000000 */ -#define USB_OTG_DCFG_PERSCHIVL_Pos (24U) -#define USB_OTG_DCFG_PERSCHIVL_Msk (0x3UL << USB_OTG_DCFG_PERSCHIVL_Pos) /*!< 0x03000000 */ -#define USB_OTG_DCFG_PERSCHIVL USB_OTG_DCFG_PERSCHIVL_Msk /*!< Periodic scheduling interval */ -#define USB_OTG_DCFG_PERSCHIVL_0 (0x1UL << USB_OTG_DCFG_PERSCHIVL_Pos) /*!< 0x01000000 */ -#define USB_OTG_DCFG_PERSCHIVL_1 (0x2UL << USB_OTG_DCFG_PERSCHIVL_Pos) /*!< 0x02000000 */ +/******************** Bit definition for PCGCR register ********************/ +#define PCGCR_STPPCLK_Pos (0U) +#define PCGCR_STPPCLK_Msk (0x1UL << PCGCR_STPPCLK_Pos) /*!< 0x00000001 */ +#define PCGCR_STPPCLK PCGCR_STPPCLK_Msk /*!< Stop PHY clock */ +#define PCGCR_GATEHCLK_Pos (1U) +#define PCGCR_GATEHCLK_Msk (0x1UL << PCGCR_GATEHCLK_Pos) /*!< 0x00000002 */ +#define PCGCR_GATEHCLK PCGCR_GATEHCLK_Msk /*!< Gate HCLK */ +#define PCGCR_PHYSUSP_Pos (4U) +#define PCGCR_PHYSUSP_Msk (0x1UL << PCGCR_PHYSUSP_Pos) /*!< 0x00000010 */ +#define PCGCR_PHYSUSP PCGCR_PHYSUSP_Msk /*!< PHY suspended */ -/******************** Bit definition for USB_OTG_PCGCR register ********************/ -#define USB_OTG_PCGCR_STPPCLK_Pos (0U) -#define USB_OTG_PCGCR_STPPCLK_Msk (0x1UL << USB_OTG_PCGCR_STPPCLK_Pos) /*!< 0x00000001 */ -#define USB_OTG_PCGCR_STPPCLK USB_OTG_PCGCR_STPPCLK_Msk /*!< Stop PHY clock */ -#define USB_OTG_PCGCR_GATEHCLK_Pos (1U) -#define USB_OTG_PCGCR_GATEHCLK_Msk (0x1UL << USB_OTG_PCGCR_GATEHCLK_Pos) /*!< 0x00000002 */ -#define USB_OTG_PCGCR_GATEHCLK USB_OTG_PCGCR_GATEHCLK_Msk /*!< Gate HCLK */ -#define USB_OTG_PCGCR_PHYSUSP_Pos (4U) -#define USB_OTG_PCGCR_PHYSUSP_Msk (0x1UL << USB_OTG_PCGCR_PHYSUSP_Pos) /*!< 0x00000010 */ -#define USB_OTG_PCGCR_PHYSUSP USB_OTG_PCGCR_PHYSUSP_Msk /*!< PHY suspended */ +/******************** Bit definition for GOTGINT register ********************/ +#define GOTGINT_SEDET_Pos (2U) +#define GOTGINT_SEDET_Msk (0x1UL << GOTGINT_SEDET_Pos) /*!< 0x00000004 */ +#define GOTGINT_SEDET GOTGINT_SEDET_Msk /*!< Session end detected */ +#define GOTGINT_SRSSCHG_Pos (8U) +#define GOTGINT_SRSSCHG_Msk (0x1UL << GOTGINT_SRSSCHG_Pos) /*!< 0x00000100 */ +#define GOTGINT_SRSSCHG GOTGINT_SRSSCHG_Msk /*!< Session request success status change */ +#define GOTGINT_HNSSCHG_Pos (9U) +#define GOTGINT_HNSSCHG_Msk (0x1UL << GOTGINT_HNSSCHG_Pos) /*!< 0x00000200 */ +#define GOTGINT_HNSSCHG GOTGINT_HNSSCHG_Msk /*!< Host negotiation success status change */ +#define GOTGINT_HNGDET_Pos (17U) +#define GOTGINT_HNGDET_Msk (0x1UL << GOTGINT_HNGDET_Pos) /*!< 0x00020000 */ +#define GOTGINT_HNGDET GOTGINT_HNGDET_Msk /*!< Host negotiation detected */ +#define GOTGINT_ADTOCHG_Pos (18U) +#define GOTGINT_ADTOCHG_Msk (0x1UL << GOTGINT_ADTOCHG_Pos) /*!< 0x00040000 */ +#define GOTGINT_ADTOCHG GOTGINT_ADTOCHG_Msk /*!< A-device timeout change */ +#define GOTGINT_DBCDNE_Pos (19U) +#define GOTGINT_DBCDNE_Msk (0x1UL << GOTGINT_DBCDNE_Pos) /*!< 0x00080000 */ +#define GOTGINT_DBCDNE GOTGINT_DBCDNE_Msk /*!< Debounce done */ +#define GOTGINT_IDCHNG_Pos (20U) +#define GOTGINT_IDCHNG_Msk (0x1UL << GOTGINT_IDCHNG_Pos) /*!< 0x00100000 */ +#define GOTGINT_IDCHNG GOTGINT_IDCHNG_Msk /*!< Change in ID pin input value */ -/******************** Bit definition for USB_OTG_GOTGINT register ********************/ -#define USB_OTG_GOTGINT_SEDET_Pos (2U) -#define USB_OTG_GOTGINT_SEDET_Msk (0x1UL << USB_OTG_GOTGINT_SEDET_Pos) /*!< 0x00000004 */ -#define USB_OTG_GOTGINT_SEDET USB_OTG_GOTGINT_SEDET_Msk /*!< Session end detected */ -#define USB_OTG_GOTGINT_SRSSCHG_Pos (8U) -#define USB_OTG_GOTGINT_SRSSCHG_Msk (0x1UL << USB_OTG_GOTGINT_SRSSCHG_Pos) /*!< 0x00000100 */ -#define USB_OTG_GOTGINT_SRSSCHG USB_OTG_GOTGINT_SRSSCHG_Msk /*!< Session request success status change */ -#define USB_OTG_GOTGINT_HNSSCHG_Pos (9U) -#define USB_OTG_GOTGINT_HNSSCHG_Msk (0x1UL << USB_OTG_GOTGINT_HNSSCHG_Pos) /*!< 0x00000200 */ -#define USB_OTG_GOTGINT_HNSSCHG USB_OTG_GOTGINT_HNSSCHG_Msk /*!< Host negotiation success status change */ -#define USB_OTG_GOTGINT_HNGDET_Pos (17U) -#define USB_OTG_GOTGINT_HNGDET_Msk (0x1UL << USB_OTG_GOTGINT_HNGDET_Pos) /*!< 0x00020000 */ -#define USB_OTG_GOTGINT_HNGDET USB_OTG_GOTGINT_HNGDET_Msk /*!< Host negotiation detected */ -#define USB_OTG_GOTGINT_ADTOCHG_Pos (18U) -#define USB_OTG_GOTGINT_ADTOCHG_Msk (0x1UL << USB_OTG_GOTGINT_ADTOCHG_Pos) /*!< 0x00040000 */ -#define USB_OTG_GOTGINT_ADTOCHG USB_OTG_GOTGINT_ADTOCHG_Msk /*!< A-device timeout change */ -#define USB_OTG_GOTGINT_DBCDNE_Pos (19U) -#define USB_OTG_GOTGINT_DBCDNE_Msk (0x1UL << USB_OTG_GOTGINT_DBCDNE_Pos) /*!< 0x00080000 */ -#define USB_OTG_GOTGINT_DBCDNE USB_OTG_GOTGINT_DBCDNE_Msk /*!< Debounce done */ +/******************** Bit definition for DCTL register ********************/ +#define DCTL_RWUSIG_Pos (0U) +#define DCTL_RWUSIG_Msk (0x1UL << DCTL_RWUSIG_Pos) /*!< 0x00000001 */ +#define DCTL_RWUSIG DCTL_RWUSIG_Msk /*!< Remote wakeup signaling */ +#define DCTL_SDIS_Pos (1U) +#define DCTL_SDIS_Msk (0x1UL << DCTL_SDIS_Pos) /*!< 0x00000002 */ +#define DCTL_SDIS DCTL_SDIS_Msk /*!< Soft disconnect */ +#define DCTL_GINSTS_Pos (2U) +#define DCTL_GINSTS_Msk (0x1UL << DCTL_GINSTS_Pos) /*!< 0x00000004 */ +#define DCTL_GINSTS DCTL_GINSTS_Msk /*!< Global IN NAK status */ +#define DCTL_GONSTS_Pos (3U) +#define DCTL_GONSTS_Msk (0x1UL << DCTL_GONSTS_Pos) /*!< 0x00000008 */ +#define DCTL_GONSTS DCTL_GONSTS_Msk /*!< Global OUT NAK status */ -/******************** Bit definition for USB_OTG_DCTL register ********************/ -#define USB_OTG_DCTL_RWUSIG_Pos (0U) -#define USB_OTG_DCTL_RWUSIG_Msk (0x1UL << USB_OTG_DCTL_RWUSIG_Pos) /*!< 0x00000001 */ -#define USB_OTG_DCTL_RWUSIG USB_OTG_DCTL_RWUSIG_Msk /*!< Remote wakeup signaling */ -#define USB_OTG_DCTL_SDIS_Pos (1U) -#define USB_OTG_DCTL_SDIS_Msk (0x1UL << USB_OTG_DCTL_SDIS_Pos) /*!< 0x00000002 */ -#define USB_OTG_DCTL_SDIS USB_OTG_DCTL_SDIS_Msk /*!< Soft disconnect */ -#define USB_OTG_DCTL_GINSTS_Pos (2U) -#define USB_OTG_DCTL_GINSTS_Msk (0x1UL << USB_OTG_DCTL_GINSTS_Pos) /*!< 0x00000004 */ -#define USB_OTG_DCTL_GINSTS USB_OTG_DCTL_GINSTS_Msk /*!< Global IN NAK status */ -#define USB_OTG_DCTL_GONSTS_Pos (3U) -#define USB_OTG_DCTL_GONSTS_Msk (0x1UL << USB_OTG_DCTL_GONSTS_Pos) /*!< 0x00000008 */ -#define USB_OTG_DCTL_GONSTS USB_OTG_DCTL_GONSTS_Msk /*!< Global OUT NAK status */ +#define DCTL_TCTL_Pos (4U) +#define DCTL_TCTL_Msk (0x7UL << DCTL_TCTL_Pos) /*!< 0x00000070 */ +#define DCTL_TCTL DCTL_TCTL_Msk /*!< Test control */ +#define DCTL_TCTL_0 (0x1UL << DCTL_TCTL_Pos) /*!< 0x00000010 */ +#define DCTL_TCTL_1 (0x2UL << DCTL_TCTL_Pos) /*!< 0x00000020 */ +#define DCTL_TCTL_2 (0x4UL << DCTL_TCTL_Pos) /*!< 0x00000040 */ +#define DCTL_SGINAK_Pos (7U) +#define DCTL_SGINAK_Msk (0x1UL << DCTL_SGINAK_Pos) /*!< 0x00000080 */ +#define DCTL_SGINAK DCTL_SGINAK_Msk /*!< Set global IN NAK */ +#define DCTL_CGINAK_Pos (8U) +#define DCTL_CGINAK_Msk (0x1UL << DCTL_CGINAK_Pos) /*!< 0x00000100 */ +#define DCTL_CGINAK DCTL_CGINAK_Msk /*!< Clear global IN NAK */ +#define DCTL_SGONAK_Pos (9U) +#define DCTL_SGONAK_Msk (0x1UL << DCTL_SGONAK_Pos) /*!< 0x00000200 */ +#define DCTL_SGONAK DCTL_SGONAK_Msk /*!< Set global OUT NAK */ +#define DCTL_CGONAK_Pos (10U) +#define DCTL_CGONAK_Msk (0x1UL << DCTL_CGONAK_Pos) /*!< 0x00000400 */ +#define DCTL_CGONAK DCTL_CGONAK_Msk /*!< Clear global OUT NAK */ +#define DCTL_POPRGDNE_Pos (11U) +#define DCTL_POPRGDNE_Msk (0x1UL << DCTL_POPRGDNE_Pos) /*!< 0x00000800 */ +#define DCTL_POPRGDNE DCTL_POPRGDNE_Msk /*!< Power-on programming done */ -#define USB_OTG_DCTL_TCTL_Pos (4U) -#define USB_OTG_DCTL_TCTL_Msk (0x7UL << USB_OTG_DCTL_TCTL_Pos) /*!< 0x00000070 */ -#define USB_OTG_DCTL_TCTL USB_OTG_DCTL_TCTL_Msk /*!< Test control */ -#define USB_OTG_DCTL_TCTL_0 (0x1UL << USB_OTG_DCTL_TCTL_Pos) /*!< 0x00000010 */ -#define USB_OTG_DCTL_TCTL_1 (0x2UL << USB_OTG_DCTL_TCTL_Pos) /*!< 0x00000020 */ -#define USB_OTG_DCTL_TCTL_2 (0x4UL << USB_OTG_DCTL_TCTL_Pos) /*!< 0x00000040 */ -#define USB_OTG_DCTL_SGINAK_Pos (7U) -#define USB_OTG_DCTL_SGINAK_Msk (0x1UL << USB_OTG_DCTL_SGINAK_Pos) /*!< 0x00000080 */ -#define USB_OTG_DCTL_SGINAK USB_OTG_DCTL_SGINAK_Msk /*!< Set global IN NAK */ -#define USB_OTG_DCTL_CGINAK_Pos (8U) -#define USB_OTG_DCTL_CGINAK_Msk (0x1UL << USB_OTG_DCTL_CGINAK_Pos) /*!< 0x00000100 */ -#define USB_OTG_DCTL_CGINAK USB_OTG_DCTL_CGINAK_Msk /*!< Clear global IN NAK */ -#define USB_OTG_DCTL_SGONAK_Pos (9U) -#define USB_OTG_DCTL_SGONAK_Msk (0x1UL << USB_OTG_DCTL_SGONAK_Pos) /*!< 0x00000200 */ -#define USB_OTG_DCTL_SGONAK USB_OTG_DCTL_SGONAK_Msk /*!< Set global OUT NAK */ -#define USB_OTG_DCTL_CGONAK_Pos (10U) -#define USB_OTG_DCTL_CGONAK_Msk (0x1UL << USB_OTG_DCTL_CGONAK_Pos) /*!< 0x00000400 */ -#define USB_OTG_DCTL_CGONAK USB_OTG_DCTL_CGONAK_Msk /*!< Clear global OUT NAK */ -#define USB_OTG_DCTL_POPRGDNE_Pos (11U) -#define USB_OTG_DCTL_POPRGDNE_Msk (0x1UL << USB_OTG_DCTL_POPRGDNE_Pos) /*!< 0x00000800 */ -#define USB_OTG_DCTL_POPRGDNE USB_OTG_DCTL_POPRGDNE_Msk /*!< Power-on programming done */ +/******************** Bit definition for HFIR register ********************/ +#define HFIR_FRIVL_Pos (0U) +#define HFIR_FRIVL_Msk (0xFFFFUL << HFIR_FRIVL_Pos) /*!< 0x0000FFFF */ +#define HFIR_FRIVL HFIR_FRIVL_Msk /*!< Frame interval */ -/******************** Bit definition for USB_OTG_HFIR register ********************/ -#define USB_OTG_HFIR_FRIVL_Pos (0U) -#define USB_OTG_HFIR_FRIVL_Msk (0xFFFFUL << USB_OTG_HFIR_FRIVL_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_HFIR_FRIVL USB_OTG_HFIR_FRIVL_Msk /*!< Frame interval */ +/******************** Bit definition for HFNUM register ********************/ +#define HFNUM_FRNUM_Pos (0U) +#define HFNUM_FRNUM_Msk (0xFFFFUL << HFNUM_FRNUM_Pos) /*!< 0x0000FFFF */ +#define HFNUM_FRNUM HFNUM_FRNUM_Msk /*!< Frame number */ +#define HFNUM_FTREM_Pos (16U) +#define HFNUM_FTREM_Msk (0xFFFFUL << HFNUM_FTREM_Pos) /*!< 0xFFFF0000 */ +#define HFNUM_FTREM HFNUM_FTREM_Msk /*!< Frame time remaining */ -/******************** Bit definition for USB_OTG_HFNUM register ********************/ -#define USB_OTG_HFNUM_FRNUM_Pos (0U) -#define USB_OTG_HFNUM_FRNUM_Msk (0xFFFFUL << USB_OTG_HFNUM_FRNUM_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_HFNUM_FRNUM USB_OTG_HFNUM_FRNUM_Msk /*!< Frame number */ -#define USB_OTG_HFNUM_FTREM_Pos (16U) -#define USB_OTG_HFNUM_FTREM_Msk (0xFFFFUL << USB_OTG_HFNUM_FTREM_Pos) /*!< 0xFFFF0000 */ -#define USB_OTG_HFNUM_FTREM USB_OTG_HFNUM_FTREM_Msk /*!< Frame time remaining */ +/******************** Bit definition for DSTS register ********************/ +#define DSTS_SUSPSTS_Pos (0U) +#define DSTS_SUSPSTS_Msk (0x1UL << DSTS_SUSPSTS_Pos) /*!< 0x00000001 */ +#define DSTS_SUSPSTS DSTS_SUSPSTS_Msk /*!< Suspend status */ -/******************** Bit definition for USB_OTG_DSTS register ********************/ -#define USB_OTG_DSTS_SUSPSTS_Pos (0U) -#define USB_OTG_DSTS_SUSPSTS_Msk (0x1UL << USB_OTG_DSTS_SUSPSTS_Pos) /*!< 0x00000001 */ -#define USB_OTG_DSTS_SUSPSTS USB_OTG_DSTS_SUSPSTS_Msk /*!< Suspend status */ +#define DSTS_ENUMSPD_Pos (1U) +#define DSTS_ENUMSPD_Msk (0x3UL << DSTS_ENUMSPD_Pos) /*!< 0x00000006 */ +#define DSTS_ENUMSPD DSTS_ENUMSPD_Msk /*!< Enumerated speed */ +#define DSTS_ENUMSPD_0 (0x1UL << DSTS_ENUMSPD_Pos) /*!< 0x00000002 */ +#define DSTS_ENUMSPD_1 (0x2UL << DSTS_ENUMSPD_Pos) /*!< 0x00000004 */ +#define DSTS_EERR_Pos (3U) +#define DSTS_EERR_Msk (0x1UL << DSTS_EERR_Pos) /*!< 0x00000008 */ +#define DSTS_EERR DSTS_EERR_Msk /*!< Erratic error */ +#define DSTS_FNSOF_Pos (8U) +#define DSTS_FNSOF_Msk (0x3FFFUL << DSTS_FNSOF_Pos) /*!< 0x003FFF00 */ +#define DSTS_FNSOF DSTS_FNSOF_Msk /*!< Frame number of the received SOF */ -#define USB_OTG_DSTS_ENUMSPD_Pos (1U) -#define USB_OTG_DSTS_ENUMSPD_Msk (0x3UL << USB_OTG_DSTS_ENUMSPD_Pos) /*!< 0x00000006 */ -#define USB_OTG_DSTS_ENUMSPD USB_OTG_DSTS_ENUMSPD_Msk /*!< Enumerated speed */ -#define USB_OTG_DSTS_ENUMSPD_0 (0x1UL << USB_OTG_DSTS_ENUMSPD_Pos) /*!< 0x00000002 */ -#define USB_OTG_DSTS_ENUMSPD_1 (0x2UL << USB_OTG_DSTS_ENUMSPD_Pos) /*!< 0x00000004 */ -#define USB_OTG_DSTS_EERR_Pos (3U) -#define USB_OTG_DSTS_EERR_Msk (0x1UL << USB_OTG_DSTS_EERR_Pos) /*!< 0x00000008 */ -#define USB_OTG_DSTS_EERR USB_OTG_DSTS_EERR_Msk /*!< Erratic error */ -#define USB_OTG_DSTS_FNSOF_Pos (8U) -#define USB_OTG_DSTS_FNSOF_Msk (0x3FFFUL << USB_OTG_DSTS_FNSOF_Pos) /*!< 0x003FFF00 */ -#define USB_OTG_DSTS_FNSOF USB_OTG_DSTS_FNSOF_Msk /*!< Frame number of the received SOF */ +/******************** Bit definition for GAHBCFG register ********************/ +#define GAHBCFG_GINT_Pos (0U) +#define GAHBCFG_GINT_Msk (0x1UL << GAHBCFG_GINT_Pos) /*!< 0x00000001 */ +#define GAHBCFG_GINT GAHBCFG_GINT_Msk /*!< Global interrupt mask */ +#define GAHBCFG_HBSTLEN_Pos (1U) +#define GAHBCFG_HBSTLEN_Msk (0xFUL << GAHBCFG_HBSTLEN_Pos) /*!< 0x0000001E */ +#define GAHBCFG_HBSTLEN GAHBCFG_HBSTLEN_Msk /*!< Burst length/type */ +#define GAHBCFG_HBSTLEN_0 (0x0UL << GAHBCFG_HBSTLEN_Pos) /*!< Single */ +#define GAHBCFG_HBSTLEN_1 (0x1UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR */ +#define GAHBCFG_HBSTLEN_2 (0x3UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR4 */ +#define GAHBCFG_HBSTLEN_3 (0x5UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR8 */ +#define GAHBCFG_HBSTLEN_4 (0x7UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR16 */ +#define GAHBCFG_DMAEN_Pos (5U) +#define GAHBCFG_DMAEN_Msk (0x1UL << GAHBCFG_DMAEN_Pos) /*!< 0x00000020 */ +#define GAHBCFG_DMAEN GAHBCFG_DMAEN_Msk /*!< DMA enable */ +#define GAHBCFG_TXFELVL_Pos (7U) +#define GAHBCFG_TXFELVL_Msk (0x1UL << GAHBCFG_TXFELVL_Pos) /*!< 0x00000080 */ +#define GAHBCFG_TXFELVL GAHBCFG_TXFELVL_Msk /*!< TxFIFO empty level */ +#define GAHBCFG_PTXFELVL_Pos (8U) +#define GAHBCFG_PTXFELVL_Msk (0x1UL << GAHBCFG_PTXFELVL_Pos) /*!< 0x00000100 */ +#define GAHBCFG_PTXFELVL GAHBCFG_PTXFELVL_Msk /*!< Periodic TxFIFO empty level */ -/******************** Bit definition for USB_OTG_GAHBCFG register ********************/ -#define USB_OTG_GAHBCFG_GINT_Pos (0U) -#define USB_OTG_GAHBCFG_GINT_Msk (0x1UL << USB_OTG_GAHBCFG_GINT_Pos) /*!< 0x00000001 */ -#define USB_OTG_GAHBCFG_GINT USB_OTG_GAHBCFG_GINT_Msk /*!< Global interrupt mask */ -#define USB_OTG_GAHBCFG_HBSTLEN_Pos (1U) -#define USB_OTG_GAHBCFG_HBSTLEN_Msk (0xFUL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< 0x0000001E */ -#define USB_OTG_GAHBCFG_HBSTLEN USB_OTG_GAHBCFG_HBSTLEN_Msk /*!< Burst length/type */ -#define USB_OTG_GAHBCFG_HBSTLEN_0 (0x0UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< Single */ -#define USB_OTG_GAHBCFG_HBSTLEN_1 (0x1UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< INCR */ -#define USB_OTG_GAHBCFG_HBSTLEN_2 (0x3UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< INCR4 */ -#define USB_OTG_GAHBCFG_HBSTLEN_3 (0x5UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< INCR8 */ -#define USB_OTG_GAHBCFG_HBSTLEN_4 (0x7UL << USB_OTG_GAHBCFG_HBSTLEN_Pos) /*!< INCR16 */ -#define USB_OTG_GAHBCFG_DMAEN_Pos (5U) -#define USB_OTG_GAHBCFG_DMAEN_Msk (0x1UL << USB_OTG_GAHBCFG_DMAEN_Pos) /*!< 0x00000020 */ -#define USB_OTG_GAHBCFG_DMAEN USB_OTG_GAHBCFG_DMAEN_Msk /*!< DMA enable */ -#define USB_OTG_GAHBCFG_TXFELVL_Pos (7U) -#define USB_OTG_GAHBCFG_TXFELVL_Msk (0x1UL << USB_OTG_GAHBCFG_TXFELVL_Pos) /*!< 0x00000080 */ -#define USB_OTG_GAHBCFG_TXFELVL USB_OTG_GAHBCFG_TXFELVL_Msk /*!< TxFIFO empty level */ -#define USB_OTG_GAHBCFG_PTXFELVL_Pos (8U) -#define USB_OTG_GAHBCFG_PTXFELVL_Msk (0x1UL << USB_OTG_GAHBCFG_PTXFELVL_Pos) /*!< 0x00000100 */ -#define USB_OTG_GAHBCFG_PTXFELVL USB_OTG_GAHBCFG_PTXFELVL_Msk /*!< Periodic TxFIFO empty level */ +/******************** Bit definition for GUSBCFG register ********************/ +#define GUSBCFG_TOCAL_Pos (0U) +#define GUSBCFG_TOCAL_Msk (0x7UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000007 */ +#define GUSBCFG_TOCAL GUSBCFG_TOCAL_Msk /*!< FS timeout calibration */ +#define GUSBCFG_TOCAL_0 (0x1UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000001 */ +#define GUSBCFG_TOCAL_1 (0x2UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000002 */ +#define GUSBCFG_TOCAL_2 (0x4UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000004 */ +#define GUSBCFG_PHYIF_Pos (3U) +#define GUSBCFG_PHYIF_Msk (0x1UL << GUSBCFG_PHYIF_Pos) /*!< 0x00000008 */ +#define GUSBCFG_PHYIF GUSBCFG_PHYIF_Msk /*!< PHY Interface (PHYIf) */ +#define GUSBCFG_ULPI_UTMI_SEL_Pos (4U) +#define GUSBCFG_ULPI_UTMI_SEL_Msk (0x1UL << GUSBCFG_ULPI_UTMI_SEL_Pos) /*!< 0x00000010 */ +#define GUSBCFG_ULPI_UTMI_SEL GUSBCFG_ULPI_UTMI_SEL_Msk /*!< ULPI or UTMI+ Select (ULPI_UTMI_Sel) */ +#define GUSBCFG_PHYSEL_Pos (6U) +#define GUSBCFG_PHYSEL_Msk (0x1UL << GUSBCFG_PHYSEL_Pos) /*!< 0x00000040 */ +#define GUSBCFG_PHYSEL GUSBCFG_PHYSEL_Msk /*!< USB 2.0 high-speed ULPI PHY or USB 1.1 full-speed serial transceiver select */ +#define GUSBCFG_SRPCAP_Pos (8U) +#define GUSBCFG_SRPCAP_Msk (0x1UL << GUSBCFG_SRPCAP_Pos) /*!< 0x00000100 */ +#define GUSBCFG_SRPCAP GUSBCFG_SRPCAP_Msk /*!< SRP-capable */ +#define GUSBCFG_HNPCAP_Pos (9U) +#define GUSBCFG_HNPCAP_Msk (0x1UL << GUSBCFG_HNPCAP_Pos) /*!< 0x00000200 */ +#define GUSBCFG_HNPCAP GUSBCFG_HNPCAP_Msk /*!< HNP-capable */ +#define GUSBCFG_TRDT_Pos (10U) +#define GUSBCFG_TRDT_Msk (0xFUL << GUSBCFG_TRDT_Pos) /*!< 0x00003C00 */ +#define GUSBCFG_TRDT GUSBCFG_TRDT_Msk /*!< USB turnaround time */ +#define GUSBCFG_TRDT_0 (0x1UL << GUSBCFG_TRDT_Pos) /*!< 0x00000400 */ +#define GUSBCFG_TRDT_1 (0x2UL << GUSBCFG_TRDT_Pos) /*!< 0x00000800 */ +#define GUSBCFG_TRDT_2 (0x4UL << GUSBCFG_TRDT_Pos) /*!< 0x00001000 */ +#define GUSBCFG_TRDT_3 (0x8UL << GUSBCFG_TRDT_Pos) /*!< 0x00002000 */ +#define GUSBCFG_PHYLPCS_Pos (15U) +#define GUSBCFG_PHYLPCS_Msk (0x1UL << GUSBCFG_PHYLPCS_Pos) /*!< 0x00008000 */ +#define GUSBCFG_PHYLPCS GUSBCFG_PHYLPCS_Msk /*!< PHY Low-power clock select */ +#define GUSBCFG_ULPIFSLS_Pos (17U) +#define GUSBCFG_ULPIFSLS_Msk (0x1UL << GUSBCFG_ULPIFSLS_Pos) /*!< 0x00020000 */ +#define GUSBCFG_ULPIFSLS GUSBCFG_ULPIFSLS_Msk /*!< ULPI FS/LS select */ +#define GUSBCFG_ULPIAR_Pos (18U) +#define GUSBCFG_ULPIAR_Msk (0x1UL << GUSBCFG_ULPIAR_Pos) /*!< 0x00040000 */ +#define GUSBCFG_ULPIAR GUSBCFG_ULPIAR_Msk /*!< ULPI Auto-resume */ +#define GUSBCFG_ULPICSM_Pos (19U) +#define GUSBCFG_ULPICSM_Msk (0x1UL << GUSBCFG_ULPICSM_Pos) /*!< 0x00080000 */ +#define GUSBCFG_ULPICSM GUSBCFG_ULPICSM_Msk /*!< ULPI Clock SuspendM */ +#define GUSBCFG_ULPIEVBUSD_Pos (20U) +#define GUSBCFG_ULPIEVBUSD_Msk (0x1UL << GUSBCFG_ULPIEVBUSD_Pos) /*!< 0x00100000 */ +#define GUSBCFG_ULPIEVBUSD GUSBCFG_ULPIEVBUSD_Msk /*!< ULPI External VBUS Drive */ +#define GUSBCFG_ULPIEVBUSI_Pos (21U) +#define GUSBCFG_ULPIEVBUSI_Msk (0x1UL << GUSBCFG_ULPIEVBUSI_Pos) /*!< 0x00200000 */ +#define GUSBCFG_ULPIEVBUSI GUSBCFG_ULPIEVBUSI_Msk /*!< ULPI external VBUS indicator */ +#define GUSBCFG_TSDPS_Pos (22U) +#define GUSBCFG_TSDPS_Msk (0x1UL << GUSBCFG_TSDPS_Pos) /*!< 0x00400000 */ +#define GUSBCFG_TSDPS GUSBCFG_TSDPS_Msk /*!< TermSel DLine pulsing selection */ +#define GUSBCFG_PCCI_Pos (23U) +#define GUSBCFG_PCCI_Msk (0x1UL << GUSBCFG_PCCI_Pos) /*!< 0x00800000 */ +#define GUSBCFG_PCCI GUSBCFG_PCCI_Msk /*!< Indicator complement */ +#define GUSBCFG_PTCI_Pos (24U) +#define GUSBCFG_PTCI_Msk (0x1UL << GUSBCFG_PTCI_Pos) /*!< 0x01000000 */ +#define GUSBCFG_PTCI GUSBCFG_PTCI_Msk /*!< Indicator pass through */ +#define GUSBCFG_ULPIIPD_Pos (25U) +#define GUSBCFG_ULPIIPD_Msk (0x1UL << GUSBCFG_ULPIIPD_Pos) /*!< 0x02000000 */ +#define GUSBCFG_ULPIIPD GUSBCFG_ULPIIPD_Msk /*!< ULPI interface protect disable */ +#define GUSBCFG_FHMOD_Pos (29U) +#define GUSBCFG_FHMOD_Msk (0x1UL << GUSBCFG_FHMOD_Pos) /*!< 0x20000000 */ +#define GUSBCFG_FHMOD GUSBCFG_FHMOD_Msk /*!< Forced host mode */ +#define GUSBCFG_FDMOD_Pos (30U) +#define GUSBCFG_FDMOD_Msk (0x1UL << GUSBCFG_FDMOD_Pos) /*!< 0x40000000 */ +#define GUSBCFG_FDMOD GUSBCFG_FDMOD_Msk /*!< Forced peripheral mode */ +#define GUSBCFG_CTXPKT_Pos (31U) +#define GUSBCFG_CTXPKT_Msk (0x1UL << GUSBCFG_CTXPKT_Pos) /*!< 0x80000000 */ +#define GUSBCFG_CTXPKT GUSBCFG_CTXPKT_Msk /*!< Corrupt Tx packet */ -/******************** Bit definition for USB_OTG_GUSBCFG register ********************/ +/******************** Bit definition for GRSTCTL register ********************/ +#define GRSTCTL_CSRST_Pos (0U) +#define GRSTCTL_CSRST_Msk (0x1UL << GRSTCTL_CSRST_Pos) /*!< 0x00000001 */ +#define GRSTCTL_CSRST GRSTCTL_CSRST_Msk /*!< Core soft reset */ +#define GRSTCTL_HSRST_Pos (1U) +#define GRSTCTL_HSRST_Msk (0x1UL << GRSTCTL_HSRST_Pos) /*!< 0x00000002 */ +#define GRSTCTL_HSRST GRSTCTL_HSRST_Msk /*!< HCLK soft reset */ +#define GRSTCTL_FCRST_Pos (2U) +#define GRSTCTL_FCRST_Msk (0x1UL << GRSTCTL_FCRST_Pos) /*!< 0x00000004 */ +#define GRSTCTL_FCRST GRSTCTL_FCRST_Msk /*!< Host frame counter reset */ +#define GRSTCTL_RXFFLSH_Pos (4U) +#define GRSTCTL_RXFFLSH_Msk (0x1UL << GRSTCTL_RXFFLSH_Pos) /*!< 0x00000010 */ +#define GRSTCTL_RXFFLSH GRSTCTL_RXFFLSH_Msk /*!< RxFIFO flush */ +#define GRSTCTL_TXFFLSH_Pos (5U) +#define GRSTCTL_TXFFLSH_Msk (0x1UL << GRSTCTL_TXFFLSH_Pos) /*!< 0x00000020 */ +#define GRSTCTL_TXFFLSH GRSTCTL_TXFFLSH_Msk /*!< TxFIFO flush */ +#define GRSTCTL_TXFNUM_Pos (6U) +#define GRSTCTL_TXFNUM_Msk (0x1FUL << GRSTCTL_TXFNUM_Pos) /*!< 0x000007C0 */ +#define GRSTCTL_TXFNUM GRSTCTL_TXFNUM_Msk /*!< TxFIFO number */ +#define GRSTCTL_TXFNUM_0 (0x01UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000040 */ +#define GRSTCTL_TXFNUM_1 (0x02UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000080 */ +#define GRSTCTL_TXFNUM_2 (0x04UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000100 */ +#define GRSTCTL_TXFNUM_3 (0x08UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000200 */ +#define GRSTCTL_TXFNUM_4 (0x10UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000400 */ +#define GRSTCTL_DMAREQ_Pos (30U) +#define GRSTCTL_DMAREQ_Msk (0x1UL << GRSTCTL_DMAREQ_Pos) /*!< 0x40000000 */ +#define GRSTCTL_DMAREQ GRSTCTL_DMAREQ_Msk /*!< DMA request signal */ +#define GRSTCTL_AHBIDL_Pos (31U) +#define GRSTCTL_AHBIDL_Msk (0x1UL << GRSTCTL_AHBIDL_Pos) /*!< 0x80000000 */ +#define GRSTCTL_AHBIDL GRSTCTL_AHBIDL_Msk /*!< AHB master idle */ -#define USB_OTG_GUSBCFG_TOCAL_Pos (0U) -#define USB_OTG_GUSBCFG_TOCAL_Msk (0x7UL << USB_OTG_GUSBCFG_TOCAL_Pos) /*!< 0x00000007 */ -#define USB_OTG_GUSBCFG_TOCAL USB_OTG_GUSBCFG_TOCAL_Msk /*!< FS timeout calibration */ -#define USB_OTG_GUSBCFG_TOCAL_0 (0x1UL << USB_OTG_GUSBCFG_TOCAL_Pos) /*!< 0x00000001 */ -#define USB_OTG_GUSBCFG_TOCAL_1 (0x2UL << USB_OTG_GUSBCFG_TOCAL_Pos) /*!< 0x00000002 */ -#define USB_OTG_GUSBCFG_TOCAL_2 (0x4UL << USB_OTG_GUSBCFG_TOCAL_Pos) /*!< 0x00000004 */ -#define USB_OTG_GUSBCFG_PHYSEL_Pos (6U) -#define USB_OTG_GUSBCFG_PHYSEL_Msk (0x1UL << USB_OTG_GUSBCFG_PHYSEL_Pos) /*!< 0x00000040 */ -#define USB_OTG_GUSBCFG_PHYSEL USB_OTG_GUSBCFG_PHYSEL_Msk /*!< USB 2.0 high-speed ULPI PHY or USB 1.1 full-speed serial transceiver select */ -#define USB_OTG_GUSBCFG_SRPCAP_Pos (8U) -#define USB_OTG_GUSBCFG_SRPCAP_Msk (0x1UL << USB_OTG_GUSBCFG_SRPCAP_Pos) /*!< 0x00000100 */ -#define USB_OTG_GUSBCFG_SRPCAP USB_OTG_GUSBCFG_SRPCAP_Msk /*!< SRP-capable */ -#define USB_OTG_GUSBCFG_HNPCAP_Pos (9U) -#define USB_OTG_GUSBCFG_HNPCAP_Msk (0x1UL << USB_OTG_GUSBCFG_HNPCAP_Pos) /*!< 0x00000200 */ -#define USB_OTG_GUSBCFG_HNPCAP USB_OTG_GUSBCFG_HNPCAP_Msk /*!< HNP-capable */ -#define USB_OTG_GUSBCFG_TRDT_Pos (10U) -#define USB_OTG_GUSBCFG_TRDT_Msk (0xFUL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00003C00 */ -#define USB_OTG_GUSBCFG_TRDT USB_OTG_GUSBCFG_TRDT_Msk /*!< USB turnaround time */ -#define USB_OTG_GUSBCFG_TRDT_0 (0x1UL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00000400 */ -#define USB_OTG_GUSBCFG_TRDT_1 (0x2UL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00000800 */ -#define USB_OTG_GUSBCFG_TRDT_2 (0x4UL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00001000 */ -#define USB_OTG_GUSBCFG_TRDT_3 (0x8UL << USB_OTG_GUSBCFG_TRDT_Pos) /*!< 0x00002000 */ -#define USB_OTG_GUSBCFG_PHYLPCS_Pos (15U) -#define USB_OTG_GUSBCFG_PHYLPCS_Msk (0x1UL << USB_OTG_GUSBCFG_PHYLPCS_Pos) /*!< 0x00008000 */ -#define USB_OTG_GUSBCFG_PHYLPCS USB_OTG_GUSBCFG_PHYLPCS_Msk /*!< PHY Low-power clock select */ -#define USB_OTG_GUSBCFG_ULPIFSLS_Pos (17U) -#define USB_OTG_GUSBCFG_ULPIFSLS_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIFSLS_Pos) /*!< 0x00020000 */ -#define USB_OTG_GUSBCFG_ULPIFSLS USB_OTG_GUSBCFG_ULPIFSLS_Msk /*!< ULPI FS/LS select */ -#define USB_OTG_GUSBCFG_ULPIAR_Pos (18U) -#define USB_OTG_GUSBCFG_ULPIAR_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIAR_Pos) /*!< 0x00040000 */ -#define USB_OTG_GUSBCFG_ULPIAR USB_OTG_GUSBCFG_ULPIAR_Msk /*!< ULPI Auto-resume */ -#define USB_OTG_GUSBCFG_ULPICSM_Pos (19U) -#define USB_OTG_GUSBCFG_ULPICSM_Msk (0x1UL << USB_OTG_GUSBCFG_ULPICSM_Pos) /*!< 0x00080000 */ -#define USB_OTG_GUSBCFG_ULPICSM USB_OTG_GUSBCFG_ULPICSM_Msk /*!< ULPI Clock SuspendM */ -#define USB_OTG_GUSBCFG_ULPIEVBUSD_Pos (20U) -#define USB_OTG_GUSBCFG_ULPIEVBUSD_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIEVBUSD_Pos) /*!< 0x00100000 */ -#define USB_OTG_GUSBCFG_ULPIEVBUSD USB_OTG_GUSBCFG_ULPIEVBUSD_Msk /*!< ULPI External VBUS Drive */ -#define USB_OTG_GUSBCFG_ULPIEVBUSI_Pos (21U) -#define USB_OTG_GUSBCFG_ULPIEVBUSI_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIEVBUSI_Pos) /*!< 0x00200000 */ -#define USB_OTG_GUSBCFG_ULPIEVBUSI USB_OTG_GUSBCFG_ULPIEVBUSI_Msk /*!< ULPI external VBUS indicator */ -#define USB_OTG_GUSBCFG_TSDPS_Pos (22U) -#define USB_OTG_GUSBCFG_TSDPS_Msk (0x1UL << USB_OTG_GUSBCFG_TSDPS_Pos) /*!< 0x00400000 */ -#define USB_OTG_GUSBCFG_TSDPS USB_OTG_GUSBCFG_TSDPS_Msk /*!< TermSel DLine pulsing selection */ -#define USB_OTG_GUSBCFG_PCCI_Pos (23U) -#define USB_OTG_GUSBCFG_PCCI_Msk (0x1UL << USB_OTG_GUSBCFG_PCCI_Pos) /*!< 0x00800000 */ -#define USB_OTG_GUSBCFG_PCCI USB_OTG_GUSBCFG_PCCI_Msk /*!< Indicator complement */ -#define USB_OTG_GUSBCFG_PTCI_Pos (24U) -#define USB_OTG_GUSBCFG_PTCI_Msk (0x1UL << USB_OTG_GUSBCFG_PTCI_Pos) /*!< 0x01000000 */ -#define USB_OTG_GUSBCFG_PTCI USB_OTG_GUSBCFG_PTCI_Msk /*!< Indicator pass through */ -#define USB_OTG_GUSBCFG_ULPIIPD_Pos (25U) -#define USB_OTG_GUSBCFG_ULPIIPD_Msk (0x1UL << USB_OTG_GUSBCFG_ULPIIPD_Pos) /*!< 0x02000000 */ -#define USB_OTG_GUSBCFG_ULPIIPD USB_OTG_GUSBCFG_ULPIIPD_Msk /*!< ULPI interface protect disable */ -#define USB_OTG_GUSBCFG_FHMOD_Pos (29U) -#define USB_OTG_GUSBCFG_FHMOD_Msk (0x1UL << USB_OTG_GUSBCFG_FHMOD_Pos) /*!< 0x20000000 */ -#define USB_OTG_GUSBCFG_FHMOD USB_OTG_GUSBCFG_FHMOD_Msk /*!< Forced host mode */ -#define USB_OTG_GUSBCFG_FDMOD_Pos (30U) -#define USB_OTG_GUSBCFG_FDMOD_Msk (0x1UL << USB_OTG_GUSBCFG_FDMOD_Pos) /*!< 0x40000000 */ -#define USB_OTG_GUSBCFG_FDMOD USB_OTG_GUSBCFG_FDMOD_Msk /*!< Forced peripheral mode */ -#define USB_OTG_GUSBCFG_CTXPKT_Pos (31U) -#define USB_OTG_GUSBCFG_CTXPKT_Msk (0x1UL << USB_OTG_GUSBCFG_CTXPKT_Pos) /*!< 0x80000000 */ -#define USB_OTG_GUSBCFG_CTXPKT USB_OTG_GUSBCFG_CTXPKT_Msk /*!< Corrupt Tx packet */ +/******************** Bit definition for DIEPMSK register ********************/ +#define DIEPMSK_XFRCM_Pos (0U) +#define DIEPMSK_XFRCM_Msk (0x1UL << DIEPMSK_XFRCM_Pos) /*!< 0x00000001 */ +#define DIEPMSK_XFRCM DIEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define DIEPMSK_EPDM_Pos (1U) +#define DIEPMSK_EPDM_Msk (0x1UL << DIEPMSK_EPDM_Pos) /*!< 0x00000002 */ +#define DIEPMSK_EPDM DIEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define DIEPMSK_TOM_Pos (3U) +#define DIEPMSK_TOM_Msk (0x1UL << DIEPMSK_TOM_Pos) /*!< 0x00000008 */ +#define DIEPMSK_TOM DIEPMSK_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ +#define DIEPMSK_ITTXFEMSK_Pos (4U) +#define DIEPMSK_ITTXFEMSK_Msk (0x1UL << DIEPMSK_ITTXFEMSK_Pos) /*!< 0x00000010 */ +#define DIEPMSK_ITTXFEMSK DIEPMSK_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define DIEPMSK_INEPNMM_Pos (5U) +#define DIEPMSK_INEPNMM_Msk (0x1UL << DIEPMSK_INEPNMM_Pos) /*!< 0x00000020 */ +#define DIEPMSK_INEPNMM DIEPMSK_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define DIEPMSK_INEPNEM_Pos (6U) +#define DIEPMSK_INEPNEM_Msk (0x1UL << DIEPMSK_INEPNEM_Pos) /*!< 0x00000040 */ +#define DIEPMSK_INEPNEM DIEPMSK_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define DIEPMSK_TXFURM_Pos (8U) +#define DIEPMSK_TXFURM_Msk (0x1UL << DIEPMSK_TXFURM_Pos) /*!< 0x00000100 */ +#define DIEPMSK_TXFURM DIEPMSK_TXFURM_Msk /*!< FIFO underrun mask */ +#define DIEPMSK_BIM_Pos (9U) +#define DIEPMSK_BIM_Msk (0x1UL << DIEPMSK_BIM_Pos) /*!< 0x00000200 */ +#define DIEPMSK_BIM DIEPMSK_BIM_Msk /*!< BNA interrupt mask */ -/******************** Bit definition for USB_OTG_GRSTCTL register ********************/ -#define USB_OTG_GRSTCTL_CSRST_Pos (0U) -#define USB_OTG_GRSTCTL_CSRST_Msk (0x1UL << USB_OTG_GRSTCTL_CSRST_Pos) /*!< 0x00000001 */ -#define USB_OTG_GRSTCTL_CSRST USB_OTG_GRSTCTL_CSRST_Msk /*!< Core soft reset */ -#define USB_OTG_GRSTCTL_HSRST_Pos (1U) -#define USB_OTG_GRSTCTL_HSRST_Msk (0x1UL << USB_OTG_GRSTCTL_HSRST_Pos) /*!< 0x00000002 */ -#define USB_OTG_GRSTCTL_HSRST USB_OTG_GRSTCTL_HSRST_Msk /*!< HCLK soft reset */ -#define USB_OTG_GRSTCTL_FCRST_Pos (2U) -#define USB_OTG_GRSTCTL_FCRST_Msk (0x1UL << USB_OTG_GRSTCTL_FCRST_Pos) /*!< 0x00000004 */ -#define USB_OTG_GRSTCTL_FCRST USB_OTG_GRSTCTL_FCRST_Msk /*!< Host frame counter reset */ -#define USB_OTG_GRSTCTL_RXFFLSH_Pos (4U) -#define USB_OTG_GRSTCTL_RXFFLSH_Msk (0x1UL << USB_OTG_GRSTCTL_RXFFLSH_Pos) /*!< 0x00000010 */ -#define USB_OTG_GRSTCTL_RXFFLSH USB_OTG_GRSTCTL_RXFFLSH_Msk /*!< RxFIFO flush */ -#define USB_OTG_GRSTCTL_TXFFLSH_Pos (5U) -#define USB_OTG_GRSTCTL_TXFFLSH_Msk (0x1UL << USB_OTG_GRSTCTL_TXFFLSH_Pos) /*!< 0x00000020 */ -#define USB_OTG_GRSTCTL_TXFFLSH USB_OTG_GRSTCTL_TXFFLSH_Msk /*!< TxFIFO flush */ +/******************** Bit definition for HPTXSTS register ********************/ +#define HPTXSTS_PTXFSAVL_Pos (0U) +#define HPTXSTS_PTXFSAVL_Msk (0xFFFFUL << HPTXSTS_PTXFSAVL_Pos) /*!< 0x0000FFFF */ +#define HPTXSTS_PTXFSAVL HPTXSTS_PTXFSAVL_Msk /*!< Periodic transmit data FIFO space available */ +#define HPTXSTS_PTXQSAV_Pos (16U) +#define HPTXSTS_PTXQSAV_Msk (0xFFUL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00FF0000 */ +#define HPTXSTS_PTXQSAV HPTXSTS_PTXQSAV_Msk /*!< Periodic transmit request queue space available */ +#define HPTXSTS_PTXQSAV_0 (0x01UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00010000 */ +#define HPTXSTS_PTXQSAV_1 (0x02UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00020000 */ +#define HPTXSTS_PTXQSAV_2 (0x04UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00040000 */ +#define HPTXSTS_PTXQSAV_3 (0x08UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00080000 */ +#define HPTXSTS_PTXQSAV_4 (0x10UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00100000 */ +#define HPTXSTS_PTXQSAV_5 (0x20UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00200000 */ +#define HPTXSTS_PTXQSAV_6 (0x40UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00400000 */ +#define HPTXSTS_PTXQSAV_7 (0x80UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00800000 */ +#define HPTXSTS_PTXQTOP_Pos (24U) +#define HPTXSTS_PTXQTOP_Msk (0xFFUL << HPTXSTS_PTXQTOP_Pos) /*!< 0xFF000000 */ +#define HPTXSTS_PTXQTOP HPTXSTS_PTXQTOP_Msk /*!< Top of the periodic transmit request queue */ +#define HPTXSTS_PTXQTOP_0 (0x01UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x01000000 */ +#define HPTXSTS_PTXQTOP_1 (0x02UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x02000000 */ +#define HPTXSTS_PTXQTOP_2 (0x04UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x04000000 */ +#define HPTXSTS_PTXQTOP_3 (0x08UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x08000000 */ +#define HPTXSTS_PTXQTOP_4 (0x10UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x10000000 */ +#define HPTXSTS_PTXQTOP_5 (0x20UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x20000000 */ +#define HPTXSTS_PTXQTOP_6 (0x40UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x40000000 */ +#define HPTXSTS_PTXQTOP_7 (0x80UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x80000000 */ -#define USB_OTG_GRSTCTL_TXFNUM_Pos (6U) -#define USB_OTG_GRSTCTL_TXFNUM_Msk (0x1FUL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x000007C0 */ -#define USB_OTG_GRSTCTL_TXFNUM USB_OTG_GRSTCTL_TXFNUM_Msk /*!< TxFIFO number */ -#define USB_OTG_GRSTCTL_TXFNUM_0 (0x01UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000040 */ -#define USB_OTG_GRSTCTL_TXFNUM_1 (0x02UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000080 */ -#define USB_OTG_GRSTCTL_TXFNUM_2 (0x04UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000100 */ -#define USB_OTG_GRSTCTL_TXFNUM_3 (0x08UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000200 */ -#define USB_OTG_GRSTCTL_TXFNUM_4 (0x10UL << USB_OTG_GRSTCTL_TXFNUM_Pos) /*!< 0x00000400 */ -#define USB_OTG_GRSTCTL_DMAREQ_Pos (30U) -#define USB_OTG_GRSTCTL_DMAREQ_Msk (0x1UL << USB_OTG_GRSTCTL_DMAREQ_Pos) /*!< 0x40000000 */ -#define USB_OTG_GRSTCTL_DMAREQ USB_OTG_GRSTCTL_DMAREQ_Msk /*!< DMA request signal */ -#define USB_OTG_GRSTCTL_AHBIDL_Pos (31U) -#define USB_OTG_GRSTCTL_AHBIDL_Msk (0x1UL << USB_OTG_GRSTCTL_AHBIDL_Pos) /*!< 0x80000000 */ -#define USB_OTG_GRSTCTL_AHBIDL USB_OTG_GRSTCTL_AHBIDL_Msk /*!< AHB master idle */ +/******************** Bit definition for HAINT register ********************/ +#define HAINT_HAINT_Pos (0U) +#define HAINT_HAINT_Msk (0xFFFFUL << HAINT_HAINT_Pos) /*!< 0x0000FFFF */ +#define HAINT_HAINT HAINT_HAINT_Msk /*!< Channel interrupts */ -/******************** Bit definition for USB_OTG_DIEPMSK register ********************/ -#define USB_OTG_DIEPMSK_XFRCM_Pos (0U) -#define USB_OTG_DIEPMSK_XFRCM_Msk (0x1UL << USB_OTG_DIEPMSK_XFRCM_Pos) /*!< 0x00000001 */ -#define USB_OTG_DIEPMSK_XFRCM USB_OTG_DIEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ -#define USB_OTG_DIEPMSK_EPDM_Pos (1U) -#define USB_OTG_DIEPMSK_EPDM_Msk (0x1UL << USB_OTG_DIEPMSK_EPDM_Pos) /*!< 0x00000002 */ -#define USB_OTG_DIEPMSK_EPDM USB_OTG_DIEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ -#define USB_OTG_DIEPMSK_TOM_Pos (3U) -#define USB_OTG_DIEPMSK_TOM_Msk (0x1UL << USB_OTG_DIEPMSK_TOM_Pos) /*!< 0x00000008 */ -#define USB_OTG_DIEPMSK_TOM USB_OTG_DIEPMSK_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ -#define USB_OTG_DIEPMSK_ITTXFEMSK_Pos (4U) -#define USB_OTG_DIEPMSK_ITTXFEMSK_Msk (0x1UL << USB_OTG_DIEPMSK_ITTXFEMSK_Pos) /*!< 0x00000010 */ -#define USB_OTG_DIEPMSK_ITTXFEMSK USB_OTG_DIEPMSK_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ -#define USB_OTG_DIEPMSK_INEPNMM_Pos (5U) -#define USB_OTG_DIEPMSK_INEPNMM_Msk (0x1UL << USB_OTG_DIEPMSK_INEPNMM_Pos) /*!< 0x00000020 */ -#define USB_OTG_DIEPMSK_INEPNMM USB_OTG_DIEPMSK_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ -#define USB_OTG_DIEPMSK_INEPNEM_Pos (6U) -#define USB_OTG_DIEPMSK_INEPNEM_Msk (0x1UL << USB_OTG_DIEPMSK_INEPNEM_Pos) /*!< 0x00000040 */ -#define USB_OTG_DIEPMSK_INEPNEM USB_OTG_DIEPMSK_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ -#define USB_OTG_DIEPMSK_TXFURM_Pos (8U) -#define USB_OTG_DIEPMSK_TXFURM_Msk (0x1UL << USB_OTG_DIEPMSK_TXFURM_Pos) /*!< 0x00000100 */ -#define USB_OTG_DIEPMSK_TXFURM USB_OTG_DIEPMSK_TXFURM_Msk /*!< FIFO underrun mask */ -#define USB_OTG_DIEPMSK_BIM_Pos (9U) -#define USB_OTG_DIEPMSK_BIM_Msk (0x1UL << USB_OTG_DIEPMSK_BIM_Pos) /*!< 0x00000200 */ -#define USB_OTG_DIEPMSK_BIM USB_OTG_DIEPMSK_BIM_Msk /*!< BNA interrupt mask */ +/******************** Bit definition for DOEPMSK register ********************/ +#define DOEPMSK_XFRCM_Pos (0U) +#define DOEPMSK_XFRCM_Msk (0x1UL << DOEPMSK_XFRCM_Pos) /*!< 0x00000001 */ +#define DOEPMSK_XFRCM DOEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define DOEPMSK_EPDM_Pos (1U) +#define DOEPMSK_EPDM_Msk (0x1UL << DOEPMSK_EPDM_Pos) /*!< 0x00000002 */ +#define DOEPMSK_EPDM DOEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define DOEPMSK_AHBERRM_Pos (2U) +#define DOEPMSK_AHBERRM_Msk (0x1UL << DOEPMSK_AHBERRM_Pos) /*!< 0x00000004 */ +#define DOEPMSK_AHBERRM DOEPMSK_AHBERRM_Msk /*!< OUT transaction AHB Error interrupt mask */ +#define DOEPMSK_STUPM_Pos (3U) +#define DOEPMSK_STUPM_Msk (0x1UL << DOEPMSK_STUPM_Pos) /*!< 0x00000008 */ +#define DOEPMSK_STUPM DOEPMSK_STUPM_Msk /*!< SETUP phase done mask */ +#define DOEPMSK_OTEPDM_Pos (4U) +#define DOEPMSK_OTEPDM_Msk (0x1UL << DOEPMSK_OTEPDM_Pos) /*!< 0x00000010 */ +#define DOEPMSK_OTEPDM DOEPMSK_OTEPDM_Msk /*!< OUT token received when endpoint disabled mask */ +#define DOEPMSK_OTEPSPRM_Pos (5U) +#define DOEPMSK_OTEPSPRM_Msk (0x1UL << DOEPMSK_OTEPSPRM_Pos) /*!< 0x00000020 */ +#define DOEPMSK_OTEPSPRM DOEPMSK_OTEPSPRM_Msk /*!< Status Phase Received mask */ +#define DOEPMSK_B2BSTUP_Pos (6U) +#define DOEPMSK_B2BSTUP_Msk (0x1UL << DOEPMSK_B2BSTUP_Pos) /*!< 0x00000040 */ +#define DOEPMSK_B2BSTUP DOEPMSK_B2BSTUP_Msk /*!< Back-to-back SETUP packets received mask */ +#define DOEPMSK_OPEM_Pos (8U) +#define DOEPMSK_OPEM_Msk (0x1UL << DOEPMSK_OPEM_Pos) /*!< 0x00000100 */ +#define DOEPMSK_OPEM DOEPMSK_OPEM_Msk /*!< OUT packet error mask */ +#define DOEPMSK_BOIM_Pos (9U) +#define DOEPMSK_BOIM_Msk (0x1UL << DOEPMSK_BOIM_Pos) /*!< 0x00000200 */ +#define DOEPMSK_BOIM DOEPMSK_BOIM_Msk /*!< BNA interrupt mask */ +#define DOEPMSK_BERRM_Pos (12U) +#define DOEPMSK_BERRM_Msk (0x1UL << DOEPMSK_BERRM_Pos) /*!< 0x00001000 */ +#define DOEPMSK_BERRM DOEPMSK_BERRM_Msk /*!< Babble error interrupt mask */ +#define DOEPMSK_NAKM_Pos (13U) +#define DOEPMSK_NAKM_Msk (0x1UL << DOEPMSK_NAKM_Pos) /*!< 0x00002000 */ +#define DOEPMSK_NAKM DOEPMSK_NAKM_Msk /*!< OUT Packet NAK interrupt mask */ +#define DOEPMSK_NYETM_Pos (14U) +#define DOEPMSK_NYETM_Msk (0x1UL << DOEPMSK_NYETM_Pos) /*!< 0x00004000 */ +#define DOEPMSK_NYETM DOEPMSK_NYETM_Msk /*!< NYET interrupt mask */ -/******************** Bit definition for USB_OTG_HPTXSTS register ********************/ -#define USB_OTG_HPTXSTS_PTXFSAVL_Pos (0U) -#define USB_OTG_HPTXSTS_PTXFSAVL_Msk (0xFFFFUL << USB_OTG_HPTXSTS_PTXFSAVL_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_HPTXSTS_PTXFSAVL USB_OTG_HPTXSTS_PTXFSAVL_Msk /*!< Periodic transmit data FIFO space available */ -#define USB_OTG_HPTXSTS_PTXQSAV_Pos (16U) -#define USB_OTG_HPTXSTS_PTXQSAV_Msk (0xFFUL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00FF0000 */ -#define USB_OTG_HPTXSTS_PTXQSAV USB_OTG_HPTXSTS_PTXQSAV_Msk /*!< Periodic transmit request queue space available */ -#define USB_OTG_HPTXSTS_PTXQSAV_0 (0x01UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00010000 */ -#define USB_OTG_HPTXSTS_PTXQSAV_1 (0x02UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00020000 */ -#define USB_OTG_HPTXSTS_PTXQSAV_2 (0x04UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00040000 */ -#define USB_OTG_HPTXSTS_PTXQSAV_3 (0x08UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00080000 */ -#define USB_OTG_HPTXSTS_PTXQSAV_4 (0x10UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00100000 */ -#define USB_OTG_HPTXSTS_PTXQSAV_5 (0x20UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00200000 */ -#define USB_OTG_HPTXSTS_PTXQSAV_6 (0x40UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00400000 */ -#define USB_OTG_HPTXSTS_PTXQSAV_7 (0x80UL << USB_OTG_HPTXSTS_PTXQSAV_Pos) /*!< 0x00800000 */ +/******************** Bit definition for GINTSTS register ********************/ +#define GINTSTS_CMOD_Pos (0U) +#define GINTSTS_CMOD_Msk (0x1UL << GINTSTS_CMOD_Pos) /*!< 0x00000001 */ +#define GINTSTS_CMOD GINTSTS_CMOD_Msk /*!< Current mode of operation */ +#define GINTSTS_MMIS_Pos (1U) +#define GINTSTS_MMIS_Msk (0x1UL << GINTSTS_MMIS_Pos) /*!< 0x00000002 */ +#define GINTSTS_MMIS GINTSTS_MMIS_Msk /*!< Mode mismatch interrupt */ +#define GINTSTS_OTGINT_Pos (2U) +#define GINTSTS_OTGINT_Msk (0x1UL << GINTSTS_OTGINT_Pos) /*!< 0x00000004 */ +#define GINTSTS_OTGINT GINTSTS_OTGINT_Msk /*!< OTG interrupt */ +#define GINTSTS_SOF_Pos (3U) +#define GINTSTS_SOF_Msk (0x1UL << GINTSTS_SOF_Pos) /*!< 0x00000008 */ +#define GINTSTS_SOF GINTSTS_SOF_Msk /*!< Start of frame */ +#define GINTSTS_RXFLVL_Pos (4U) +#define GINTSTS_RXFLVL_Msk (0x1UL << GINTSTS_RXFLVL_Pos) /*!< 0x00000010 */ +#define GINTSTS_RXFLVL GINTSTS_RXFLVL_Msk /*!< RxFIFO nonempty */ +#define GINTSTS_NPTXFE_Pos (5U) +#define GINTSTS_NPTXFE_Msk (0x1UL << GINTSTS_NPTXFE_Pos) /*!< 0x00000020 */ +#define GINTSTS_NPTXFE GINTSTS_NPTXFE_Msk /*!< Nonperiodic TxFIFO empty */ +#define GINTSTS_GINAKEFF_Pos (6U) +#define GINTSTS_GINAKEFF_Msk (0x1UL << GINTSTS_GINAKEFF_Pos) /*!< 0x00000040 */ +#define GINTSTS_GINAKEFF GINTSTS_GINAKEFF_Msk /*!< Global IN nonperiodic NAK effective */ +#define GINTSTS_BOUTNAKEFF_Pos (7U) +#define GINTSTS_BOUTNAKEFF_Msk (0x1UL << GINTSTS_BOUTNAKEFF_Pos) /*!< 0x00000080 */ +#define GINTSTS_BOUTNAKEFF GINTSTS_BOUTNAKEFF_Msk /*!< Global OUT NAK effective */ +#define GINTSTS_ESUSP_Pos (10U) +#define GINTSTS_ESUSP_Msk (0x1UL << GINTSTS_ESUSP_Pos) /*!< 0x00000400 */ +#define GINTSTS_ESUSP GINTSTS_ESUSP_Msk /*!< Early suspend */ +#define GINTSTS_USBSUSP_Pos (11U) +#define GINTSTS_USBSUSP_Msk (0x1UL << GINTSTS_USBSUSP_Pos) /*!< 0x00000800 */ +#define GINTSTS_USBSUSP GINTSTS_USBSUSP_Msk /*!< USB suspend */ +#define GINTSTS_USBRST_Pos (12U) +#define GINTSTS_USBRST_Msk (0x1UL << GINTSTS_USBRST_Pos) /*!< 0x00001000 */ +#define GINTSTS_USBRST GINTSTS_USBRST_Msk /*!< USB reset */ +#define GINTSTS_ENUMDNE_Pos (13U) +#define GINTSTS_ENUMDNE_Msk (0x1UL << GINTSTS_ENUMDNE_Pos) /*!< 0x00002000 */ +#define GINTSTS_ENUMDNE GINTSTS_ENUMDNE_Msk /*!< Enumeration done */ +#define GINTSTS_ISOODRP_Pos (14U) +#define GINTSTS_ISOODRP_Msk (0x1UL << GINTSTS_ISOODRP_Pos) /*!< 0x00004000 */ +#define GINTSTS_ISOODRP GINTSTS_ISOODRP_Msk /*!< Isochronous OUT packet dropped interrupt */ +#define GINTSTS_EOPF_Pos (15U) +#define GINTSTS_EOPF_Msk (0x1UL << GINTSTS_EOPF_Pos) /*!< 0x00008000 */ +#define GINTSTS_EOPF GINTSTS_EOPF_Msk /*!< End of periodic frame interrupt */ +#define GINTSTS_IEPINT_Pos (18U) +#define GINTSTS_IEPINT_Msk (0x1UL << GINTSTS_IEPINT_Pos) /*!< 0x00040000 */ +#define GINTSTS_IEPINT GINTSTS_IEPINT_Msk /*!< IN endpoint interrupt */ +#define GINTSTS_OEPINT_Pos (19U) +#define GINTSTS_OEPINT_Msk (0x1UL << GINTSTS_OEPINT_Pos) /*!< 0x00080000 */ +#define GINTSTS_OEPINT GINTSTS_OEPINT_Msk /*!< OUT endpoint interrupt */ +#define GINTSTS_IISOIXFR_Pos (20U) +#define GINTSTS_IISOIXFR_Msk (0x1UL << GINTSTS_IISOIXFR_Pos) /*!< 0x00100000 */ +#define GINTSTS_IISOIXFR GINTSTS_IISOIXFR_Msk /*!< Incomplete isochronous IN transfer */ +#define GINTSTS_PXFR_INCOMPISOOUT_Pos (21U) +#define GINTSTS_PXFR_INCOMPISOOUT_Msk (0x1UL << GINTSTS_PXFR_INCOMPISOOUT_Pos) /*!< 0x00200000 */ +#define GINTSTS_PXFR_INCOMPISOOUT GINTSTS_PXFR_INCOMPISOOUT_Msk /*!< Incomplete periodic transfer */ +#define GINTSTS_DATAFSUSP_Pos (22U) +#define GINTSTS_DATAFSUSP_Msk (0x1UL << GINTSTS_DATAFSUSP_Pos) /*!< 0x00400000 */ +#define GINTSTS_DATAFSUSP GINTSTS_DATAFSUSP_Msk /*!< Data fetch suspended */ +#define GINTSTS_RSTDET_Pos (23U) +#define GINTSTS_RSTDET_Msk (0x1UL << GINTSTS_RSTDET_Pos) /*!< 0x00800000 */ +#define GINTSTS_RSTDET GINTSTS_RSTDET_Msk /*!< Reset detected interrupt */ +#define GINTSTS_HPRTINT_Pos (24U) +#define GINTSTS_HPRTINT_Msk (0x1UL << GINTSTS_HPRTINT_Pos) /*!< 0x01000000 */ +#define GINTSTS_HPRTINT GINTSTS_HPRTINT_Msk /*!< Host port interrupt */ +#define GINTSTS_HCINT_Pos (25U) +#define GINTSTS_HCINT_Msk (0x1UL << GINTSTS_HCINT_Pos) /*!< 0x02000000 */ +#define GINTSTS_HCINT GINTSTS_HCINT_Msk /*!< Host channels interrupt */ +#define GINTSTS_PTXFE_Pos (26U) +#define GINTSTS_PTXFE_Msk (0x1UL << GINTSTS_PTXFE_Pos) /*!< 0x04000000 */ +#define GINTSTS_PTXFE GINTSTS_PTXFE_Msk /*!< Periodic TxFIFO empty */ +#define GINTSTS_LPMINT_Pos (27U) +#define GINTSTS_LPMINT_Msk (0x1UL << GINTSTS_LPMINT_Pos) /*!< 0x08000000 */ +#define GINTSTS_LPMINT GINTSTS_LPMINT_Msk /*!< LPM interrupt */ +#define GINTSTS_CIDSCHG_Pos (28U) +#define GINTSTS_CIDSCHG_Msk (0x1UL << GINTSTS_CIDSCHG_Pos) /*!< 0x10000000 */ +#define GINTSTS_CIDSCHG GINTSTS_CIDSCHG_Msk /*!< Connector ID status change */ +#define GINTSTS_DISCINT_Pos (29U) +#define GINTSTS_DISCINT_Msk (0x1UL << GINTSTS_DISCINT_Pos) /*!< 0x20000000 */ +#define GINTSTS_DISCINT GINTSTS_DISCINT_Msk /*!< Disconnect detected interrupt */ +#define GINTSTS_SRQINT_Pos (30U) +#define GINTSTS_SRQINT_Msk (0x1UL << GINTSTS_SRQINT_Pos) /*!< 0x40000000 */ +#define GINTSTS_SRQINT GINTSTS_SRQINT_Msk /*!< Session request/new session detected interrupt */ +#define GINTSTS_WKUINT_Pos (31U) +#define GINTSTS_WKUINT_Msk (0x1UL << GINTSTS_WKUINT_Pos) /*!< 0x80000000 */ +#define GINTSTS_WKUINT GINTSTS_WKUINT_Msk /*!< Resume/remote wakeup detected interrupt */ -#define USB_OTG_HPTXSTS_PTXQTOP_Pos (24U) -#define USB_OTG_HPTXSTS_PTXQTOP_Msk (0xFFUL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0xFF000000 */ -#define USB_OTG_HPTXSTS_PTXQTOP USB_OTG_HPTXSTS_PTXQTOP_Msk /*!< Top of the periodic transmit request queue */ -#define USB_OTG_HPTXSTS_PTXQTOP_0 (0x01UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x01000000 */ -#define USB_OTG_HPTXSTS_PTXQTOP_1 (0x02UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x02000000 */ -#define USB_OTG_HPTXSTS_PTXQTOP_2 (0x04UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x04000000 */ -#define USB_OTG_HPTXSTS_PTXQTOP_3 (0x08UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x08000000 */ -#define USB_OTG_HPTXSTS_PTXQTOP_4 (0x10UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x10000000 */ -#define USB_OTG_HPTXSTS_PTXQTOP_5 (0x20UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x20000000 */ -#define USB_OTG_HPTXSTS_PTXQTOP_6 (0x40UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x40000000 */ -#define USB_OTG_HPTXSTS_PTXQTOP_7 (0x80UL << USB_OTG_HPTXSTS_PTXQTOP_Pos) /*!< 0x80000000 */ +/******************** Bit definition for GINTMSK register ********************/ +#define GINTMSK_MMISM_Pos (1U) +#define GINTMSK_MMISM_Msk (0x1UL << GINTMSK_MMISM_Pos) /*!< 0x00000002 */ +#define GINTMSK_MMISM GINTMSK_MMISM_Msk /*!< Mode mismatch interrupt mask */ +#define GINTMSK_OTGINT_Pos (2U) +#define GINTMSK_OTGINT_Msk (0x1UL << GINTMSK_OTGINT_Pos) /*!< 0x00000004 */ +#define GINTMSK_OTGINT GINTMSK_OTGINT_Msk /*!< OTG interrupt mask */ +#define GINTMSK_SOFM_Pos (3U) +#define GINTMSK_SOFM_Msk (0x1UL << GINTMSK_SOFM_Pos) /*!< 0x00000008 */ +#define GINTMSK_SOFM GINTMSK_SOFM_Msk /*!< Start of frame mask */ +#define GINTMSK_RXFLVLM_Pos (4U) +#define GINTMSK_RXFLVLM_Msk (0x1UL << GINTMSK_RXFLVLM_Pos) /*!< 0x00000010 */ +#define GINTMSK_RXFLVLM GINTMSK_RXFLVLM_Msk /*!< Receive FIFO nonempty mask */ +#define GINTMSK_NPTXFEM_Pos (5U) +#define GINTMSK_NPTXFEM_Msk (0x1UL << GINTMSK_NPTXFEM_Pos) /*!< 0x00000020 */ +#define GINTMSK_NPTXFEM GINTMSK_NPTXFEM_Msk /*!< Nonperiodic TxFIFO empty mask */ +#define GINTMSK_GINAKEFFM_Pos (6U) +#define GINTMSK_GINAKEFFM_Msk (0x1UL << GINTMSK_GINAKEFFM_Pos) /*!< 0x00000040 */ +#define GINTMSK_GINAKEFFM GINTMSK_GINAKEFFM_Msk /*!< Global nonperiodic IN NAK effective mask */ +#define GINTMSK_GONAKEFFM_Pos (7U) +#define GINTMSK_GONAKEFFM_Msk (0x1UL << GINTMSK_GONAKEFFM_Pos) /*!< 0x00000080 */ +#define GINTMSK_GONAKEFFM GINTMSK_GONAKEFFM_Msk /*!< Global OUT NAK effective mask */ +#define GINTMSK_ESUSPM_Pos (10U) +#define GINTMSK_ESUSPM_Msk (0x1UL << GINTMSK_ESUSPM_Pos) /*!< 0x00000400 */ +#define GINTMSK_ESUSPM GINTMSK_ESUSPM_Msk /*!< Early suspend mask */ +#define GINTMSK_USBSUSPM_Pos (11U) +#define GINTMSK_USBSUSPM_Msk (0x1UL << GINTMSK_USBSUSPM_Pos) /*!< 0x00000800 */ +#define GINTMSK_USBSUSPM GINTMSK_USBSUSPM_Msk /*!< USB suspend mask */ +#define GINTMSK_USBRST_Pos (12U) +#define GINTMSK_USBRST_Msk (0x1UL << GINTMSK_USBRST_Pos) /*!< 0x00001000 */ +#define GINTMSK_USBRST GINTMSK_USBRST_Msk /*!< USB reset mask */ +#define GINTMSK_ENUMDNEM_Pos (13U) +#define GINTMSK_ENUMDNEM_Msk (0x1UL << GINTMSK_ENUMDNEM_Pos) /*!< 0x00002000 */ +#define GINTMSK_ENUMDNEM GINTMSK_ENUMDNEM_Msk /*!< Enumeration done mask */ +#define GINTMSK_ISOODRPM_Pos (14U) +#define GINTMSK_ISOODRPM_Msk (0x1UL << GINTMSK_ISOODRPM_Pos) /*!< 0x00004000 */ +#define GINTMSK_ISOODRPM GINTMSK_ISOODRPM_Msk /*!< Isochronous OUT packet dropped interrupt mask */ +#define GINTMSK_EOPFM_Pos (15U) +#define GINTMSK_EOPFM_Msk (0x1UL << GINTMSK_EOPFM_Pos) /*!< 0x00008000 */ +#define GINTMSK_EOPFM GINTMSK_EOPFM_Msk /*!< End of periodic frame interrupt mask */ +#define GINTMSK_EPMISM_Pos (17U) +#define GINTMSK_EPMISM_Msk (0x1UL << GINTMSK_EPMISM_Pos) /*!< 0x00020000 */ +#define GINTMSK_EPMISM GINTMSK_EPMISM_Msk /*!< Endpoint mismatch interrupt mask */ +#define GINTMSK_IEPINT_Pos (18U) +#define GINTMSK_IEPINT_Msk (0x1UL << GINTMSK_IEPINT_Pos) /*!< 0x00040000 */ +#define GINTMSK_IEPINT GINTMSK_IEPINT_Msk /*!< IN endpoints interrupt mask */ +#define GINTMSK_OEPINT_Pos (19U) +#define GINTMSK_OEPINT_Msk (0x1UL << GINTMSK_OEPINT_Pos) /*!< 0x00080000 */ +#define GINTMSK_OEPINT GINTMSK_OEPINT_Msk /*!< OUT endpoints interrupt mask */ +#define GINTMSK_IISOIXFRM_Pos (20U) +#define GINTMSK_IISOIXFRM_Msk (0x1UL << GINTMSK_IISOIXFRM_Pos) /*!< 0x00100000 */ +#define GINTMSK_IISOIXFRM GINTMSK_IISOIXFRM_Msk /*!< Incomplete isochronous IN transfer mask */ +#define GINTMSK_PXFRM_IISOOXFRM_Pos (21U) +#define GINTMSK_PXFRM_IISOOXFRM_Msk (0x1UL << GINTMSK_PXFRM_IISOOXFRM_Pos) /*!< 0x00200000 */ +#define GINTMSK_PXFRM_IISOOXFRM GINTMSK_PXFRM_IISOOXFRM_Msk /*!< Incomplete periodic transfer mask */ +#define GINTMSK_FSUSPM_Pos (22U) +#define GINTMSK_FSUSPM_Msk (0x1UL << GINTMSK_FSUSPM_Pos) /*!< 0x00400000 */ +#define GINTMSK_FSUSPM GINTMSK_FSUSPM_Msk /*!< Data fetch suspended mask */ +#define GINTMSK_RSTDEM_Pos (23U) +#define GINTMSK_RSTDEM_Msk (0x1UL << GINTMSK_RSTDEM_Pos) /*!< 0x00800000 */ +#define GINTMSK_RSTDEM GINTMSK_RSTDEM_Msk /*!< Reset detected interrupt mask */ +#define GINTMSK_PRTIM_Pos (24U) +#define GINTMSK_PRTIM_Msk (0x1UL << GINTMSK_PRTIM_Pos) /*!< 0x01000000 */ +#define GINTMSK_PRTIM GINTMSK_PRTIM_Msk /*!< Host port interrupt mask */ +#define GINTMSK_HCIM_Pos (25U) +#define GINTMSK_HCIM_Msk (0x1UL << GINTMSK_HCIM_Pos) /*!< 0x02000000 */ +#define GINTMSK_HCIM GINTMSK_HCIM_Msk /*!< Host channels interrupt mask */ +#define GINTMSK_PTXFEM_Pos (26U) +#define GINTMSK_PTXFEM_Msk (0x1UL << GINTMSK_PTXFEM_Pos) /*!< 0x04000000 */ +#define GINTMSK_PTXFEM GINTMSK_PTXFEM_Msk /*!< Periodic TxFIFO empty mask */ +#define GINTMSK_LPMINTM_Pos (27U) +#define GINTMSK_LPMINTM_Msk (0x1UL << GINTMSK_LPMINTM_Pos) /*!< 0x08000000 */ +#define GINTMSK_LPMINTM GINTMSK_LPMINTM_Msk /*!< LPM interrupt Mask */ +#define GINTMSK_CIDSCHGM_Pos (28U) +#define GINTMSK_CIDSCHGM_Msk (0x1UL << GINTMSK_CIDSCHGM_Pos) /*!< 0x10000000 */ +#define GINTMSK_CIDSCHGM GINTMSK_CIDSCHGM_Msk /*!< Connector ID status change mask */ +#define GINTMSK_DISCINT_Pos (29U) +#define GINTMSK_DISCINT_Msk (0x1UL << GINTMSK_DISCINT_Pos) /*!< 0x20000000 */ +#define GINTMSK_DISCINT GINTMSK_DISCINT_Msk /*!< Disconnect detected interrupt mask */ +#define GINTMSK_SRQIM_Pos (30U) +#define GINTMSK_SRQIM_Msk (0x1UL << GINTMSK_SRQIM_Pos) /*!< 0x40000000 */ +#define GINTMSK_SRQIM GINTMSK_SRQIM_Msk /*!< Session request/new session detected interrupt mask */ +#define GINTMSK_WUIM_Pos (31U) +#define GINTMSK_WUIM_Msk (0x1UL << GINTMSK_WUIM_Pos) /*!< 0x80000000 */ +#define GINTMSK_WUIM GINTMSK_WUIM_Msk /*!< Resume/remote wakeup detected interrupt mask */ -/******************** Bit definition for USB_OTG_HAINT register ********************/ -#define USB_OTG_HAINT_HAINT_Pos (0U) -#define USB_OTG_HAINT_HAINT_Msk (0xFFFFUL << USB_OTG_HAINT_HAINT_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_HAINT_HAINT USB_OTG_HAINT_HAINT_Msk /*!< Channel interrupts */ +/******************** Bit definition for DAINT register ********************/ +#define DAINT_IEPINT_Pos (0U) +#define DAINT_IEPINT_Msk (0xFFFFUL << DAINT_IEPINT_Pos) /*!< 0x0000FFFF */ +#define DAINT_IEPINT DAINT_IEPINT_Msk /*!< IN endpoint interrupt bits */ +#define DAINT_OEPINT_Pos (16U) +#define DAINT_OEPINT_Msk (0xFFFFUL << DAINT_OEPINT_Pos) /*!< 0xFFFF0000 */ +#define DAINT_OEPINT DAINT_OEPINT_Msk /*!< OUT endpoint interrupt bits */ -/******************** Bit definition for USB_OTG_DOEPMSK register ********************/ -#define USB_OTG_DOEPMSK_XFRCM_Pos (0U) -#define USB_OTG_DOEPMSK_XFRCM_Msk (0x1UL << USB_OTG_DOEPMSK_XFRCM_Pos) /*!< 0x00000001 */ -#define USB_OTG_DOEPMSK_XFRCM USB_OTG_DOEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ -#define USB_OTG_DOEPMSK_EPDM_Pos (1U) -#define USB_OTG_DOEPMSK_EPDM_Msk (0x1UL << USB_OTG_DOEPMSK_EPDM_Pos) /*!< 0x00000002 */ -#define USB_OTG_DOEPMSK_EPDM USB_OTG_DOEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ -#define USB_OTG_DOEPMSK_AHBERRM_Pos (2U) -#define USB_OTG_DOEPMSK_AHBERRM_Msk (0x1UL << USB_OTG_DOEPMSK_AHBERRM_Pos) /*!< 0x00000004 */ -#define USB_OTG_DOEPMSK_AHBERRM USB_OTG_DOEPMSK_AHBERRM_Msk /*!< OUT transaction AHB Error interrupt mask */ -#define USB_OTG_DOEPMSK_STUPM_Pos (3U) -#define USB_OTG_DOEPMSK_STUPM_Msk (0x1UL << USB_OTG_DOEPMSK_STUPM_Pos) /*!< 0x00000008 */ -#define USB_OTG_DOEPMSK_STUPM USB_OTG_DOEPMSK_STUPM_Msk /*!< SETUP phase done mask */ -#define USB_OTG_DOEPMSK_OTEPDM_Pos (4U) -#define USB_OTG_DOEPMSK_OTEPDM_Msk (0x1UL << USB_OTG_DOEPMSK_OTEPDM_Pos) /*!< 0x00000010 */ -#define USB_OTG_DOEPMSK_OTEPDM USB_OTG_DOEPMSK_OTEPDM_Msk /*!< OUT token received when endpoint disabled mask */ -#define USB_OTG_DOEPMSK_OTEPSPRM_Pos (5U) -#define USB_OTG_DOEPMSK_OTEPSPRM_Msk (0x1UL << USB_OTG_DOEPMSK_OTEPSPRM_Pos) /*!< 0x00000020 */ -#define USB_OTG_DOEPMSK_OTEPSPRM USB_OTG_DOEPMSK_OTEPSPRM_Msk /*!< Status Phase Received mask */ -#define USB_OTG_DOEPMSK_B2BSTUP_Pos (6U) -#define USB_OTG_DOEPMSK_B2BSTUP_Msk (0x1UL << USB_OTG_DOEPMSK_B2BSTUP_Pos) /*!< 0x00000040 */ -#define USB_OTG_DOEPMSK_B2BSTUP USB_OTG_DOEPMSK_B2BSTUP_Msk /*!< Back-to-back SETUP packets received mask */ -#define USB_OTG_DOEPMSK_OPEM_Pos (8U) -#define USB_OTG_DOEPMSK_OPEM_Msk (0x1UL << USB_OTG_DOEPMSK_OPEM_Pos) /*!< 0x00000100 */ -#define USB_OTG_DOEPMSK_OPEM USB_OTG_DOEPMSK_OPEM_Msk /*!< OUT packet error mask */ -#define USB_OTG_DOEPMSK_BOIM_Pos (9U) -#define USB_OTG_DOEPMSK_BOIM_Msk (0x1UL << USB_OTG_DOEPMSK_BOIM_Pos) /*!< 0x00000200 */ -#define USB_OTG_DOEPMSK_BOIM USB_OTG_DOEPMSK_BOIM_Msk /*!< BNA interrupt mask */ -#define USB_OTG_DOEPMSK_BERRM_Pos (12U) -#define USB_OTG_DOEPMSK_BERRM_Msk (0x1UL << USB_OTG_DOEPMSK_BERRM_Pos) /*!< 0x00001000 */ -#define USB_OTG_DOEPMSK_BERRM USB_OTG_DOEPMSK_BERRM_Msk /*!< Babble error interrupt mask */ -#define USB_OTG_DOEPMSK_NAKM_Pos (13U) -#define USB_OTG_DOEPMSK_NAKM_Msk (0x1UL << USB_OTG_DOEPMSK_NAKM_Pos) /*!< 0x00002000 */ -#define USB_OTG_DOEPMSK_NAKM USB_OTG_DOEPMSK_NAKM_Msk /*!< OUT Packet NAK interrupt mask */ -#define USB_OTG_DOEPMSK_NYETM_Pos (14U) -#define USB_OTG_DOEPMSK_NYETM_Msk (0x1UL << USB_OTG_DOEPMSK_NYETM_Pos) /*!< 0x00004000 */ -#define USB_OTG_DOEPMSK_NYETM USB_OTG_DOEPMSK_NYETM_Msk /*!< NYET interrupt mask */ -/******************** Bit definition for USB_OTG_GINTSTS register ********************/ -#define USB_OTG_GINTSTS_CMOD_Pos (0U) -#define USB_OTG_GINTSTS_CMOD_Msk (0x1UL << USB_OTG_GINTSTS_CMOD_Pos) /*!< 0x00000001 */ -#define USB_OTG_GINTSTS_CMOD USB_OTG_GINTSTS_CMOD_Msk /*!< Current mode of operation */ -#define USB_OTG_GINTSTS_MMIS_Pos (1U) -#define USB_OTG_GINTSTS_MMIS_Msk (0x1UL << USB_OTG_GINTSTS_MMIS_Pos) /*!< 0x00000002 */ -#define USB_OTG_GINTSTS_MMIS USB_OTG_GINTSTS_MMIS_Msk /*!< Mode mismatch interrupt */ -#define USB_OTG_GINTSTS_OTGINT_Pos (2U) -#define USB_OTG_GINTSTS_OTGINT_Msk (0x1UL << USB_OTG_GINTSTS_OTGINT_Pos) /*!< 0x00000004 */ -#define USB_OTG_GINTSTS_OTGINT USB_OTG_GINTSTS_OTGINT_Msk /*!< OTG interrupt */ -#define USB_OTG_GINTSTS_SOF_Pos (3U) -#define USB_OTG_GINTSTS_SOF_Msk (0x1UL << USB_OTG_GINTSTS_SOF_Pos) /*!< 0x00000008 */ -#define USB_OTG_GINTSTS_SOF USB_OTG_GINTSTS_SOF_Msk /*!< Start of frame */ -#define USB_OTG_GINTSTS_RXFLVL_Pos (4U) -#define USB_OTG_GINTSTS_RXFLVL_Msk (0x1UL << USB_OTG_GINTSTS_RXFLVL_Pos) /*!< 0x00000010 */ -#define USB_OTG_GINTSTS_RXFLVL USB_OTG_GINTSTS_RXFLVL_Msk /*!< RxFIFO nonempty */ -#define USB_OTG_GINTSTS_NPTXFE_Pos (5U) -#define USB_OTG_GINTSTS_NPTXFE_Msk (0x1UL << USB_OTG_GINTSTS_NPTXFE_Pos) /*!< 0x00000020 */ -#define USB_OTG_GINTSTS_NPTXFE USB_OTG_GINTSTS_NPTXFE_Msk /*!< Nonperiodic TxFIFO empty */ -#define USB_OTG_GINTSTS_GINAKEFF_Pos (6U) -#define USB_OTG_GINTSTS_GINAKEFF_Msk (0x1UL << USB_OTG_GINTSTS_GINAKEFF_Pos) /*!< 0x00000040 */ -#define USB_OTG_GINTSTS_GINAKEFF USB_OTG_GINTSTS_GINAKEFF_Msk /*!< Global IN nonperiodic NAK effective */ -#define USB_OTG_GINTSTS_BOUTNAKEFF_Pos (7U) -#define USB_OTG_GINTSTS_BOUTNAKEFF_Msk (0x1UL << USB_OTG_GINTSTS_BOUTNAKEFF_Pos) /*!< 0x00000080 */ -#define USB_OTG_GINTSTS_BOUTNAKEFF USB_OTG_GINTSTS_BOUTNAKEFF_Msk /*!< Global OUT NAK effective */ -#define USB_OTG_GINTSTS_ESUSP_Pos (10U) -#define USB_OTG_GINTSTS_ESUSP_Msk (0x1UL << USB_OTG_GINTSTS_ESUSP_Pos) /*!< 0x00000400 */ -#define USB_OTG_GINTSTS_ESUSP USB_OTG_GINTSTS_ESUSP_Msk /*!< Early suspend */ -#define USB_OTG_GINTSTS_USBSUSP_Pos (11U) -#define USB_OTG_GINTSTS_USBSUSP_Msk (0x1UL << USB_OTG_GINTSTS_USBSUSP_Pos) /*!< 0x00000800 */ -#define USB_OTG_GINTSTS_USBSUSP USB_OTG_GINTSTS_USBSUSP_Msk /*!< USB suspend */ -#define USB_OTG_GINTSTS_USBRST_Pos (12U) -#define USB_OTG_GINTSTS_USBRST_Msk (0x1UL << USB_OTG_GINTSTS_USBRST_Pos) /*!< 0x00001000 */ -#define USB_OTG_GINTSTS_USBRST USB_OTG_GINTSTS_USBRST_Msk /*!< USB reset */ -#define USB_OTG_GINTSTS_ENUMDNE_Pos (13U) -#define USB_OTG_GINTSTS_ENUMDNE_Msk (0x1UL << USB_OTG_GINTSTS_ENUMDNE_Pos) /*!< 0x00002000 */ -#define USB_OTG_GINTSTS_ENUMDNE USB_OTG_GINTSTS_ENUMDNE_Msk /*!< Enumeration done */ -#define USB_OTG_GINTSTS_ISOODRP_Pos (14U) -#define USB_OTG_GINTSTS_ISOODRP_Msk (0x1UL << USB_OTG_GINTSTS_ISOODRP_Pos) /*!< 0x00004000 */ -#define USB_OTG_GINTSTS_ISOODRP USB_OTG_GINTSTS_ISOODRP_Msk /*!< Isochronous OUT packet dropped interrupt */ -#define USB_OTG_GINTSTS_EOPF_Pos (15U) -#define USB_OTG_GINTSTS_EOPF_Msk (0x1UL << USB_OTG_GINTSTS_EOPF_Pos) /*!< 0x00008000 */ -#define USB_OTG_GINTSTS_EOPF USB_OTG_GINTSTS_EOPF_Msk /*!< End of periodic frame interrupt */ -#define USB_OTG_GINTSTS_IEPINT_Pos (18U) -#define USB_OTG_GINTSTS_IEPINT_Msk (0x1UL << USB_OTG_GINTSTS_IEPINT_Pos) /*!< 0x00040000 */ -#define USB_OTG_GINTSTS_IEPINT USB_OTG_GINTSTS_IEPINT_Msk /*!< IN endpoint interrupt */ -#define USB_OTG_GINTSTS_OEPINT_Pos (19U) -#define USB_OTG_GINTSTS_OEPINT_Msk (0x1UL << USB_OTG_GINTSTS_OEPINT_Pos) /*!< 0x00080000 */ -#define USB_OTG_GINTSTS_OEPINT USB_OTG_GINTSTS_OEPINT_Msk /*!< OUT endpoint interrupt */ -#define USB_OTG_GINTSTS_IISOIXFR_Pos (20U) -#define USB_OTG_GINTSTS_IISOIXFR_Msk (0x1UL << USB_OTG_GINTSTS_IISOIXFR_Pos) /*!< 0x00100000 */ -#define USB_OTG_GINTSTS_IISOIXFR USB_OTG_GINTSTS_IISOIXFR_Msk /*!< Incomplete isochronous IN transfer */ -#define USB_OTG_GINTSTS_PXFR_INCOMPISOOUT_Pos (21U) -#define USB_OTG_GINTSTS_PXFR_INCOMPISOOUT_Msk (0x1UL << USB_OTG_GINTSTS_PXFR_INCOMPISOOUT_Pos) /*!< 0x00200000 */ -#define USB_OTG_GINTSTS_PXFR_INCOMPISOOUT USB_OTG_GINTSTS_PXFR_INCOMPISOOUT_Msk /*!< Incomplete periodic transfer */ -#define USB_OTG_GINTSTS_DATAFSUSP_Pos (22U) -#define USB_OTG_GINTSTS_DATAFSUSP_Msk (0x1UL << USB_OTG_GINTSTS_DATAFSUSP_Pos) /*!< 0x00400000 */ -#define USB_OTG_GINTSTS_DATAFSUSP USB_OTG_GINTSTS_DATAFSUSP_Msk /*!< Data fetch suspended */ -#define USB_OTG_GINTSTS_HPRTINT_Pos (24U) -#define USB_OTG_GINTSTS_HPRTINT_Msk (0x1UL << USB_OTG_GINTSTS_HPRTINT_Pos) /*!< 0x01000000 */ -#define USB_OTG_GINTSTS_HPRTINT USB_OTG_GINTSTS_HPRTINT_Msk /*!< Host port interrupt */ -#define USB_OTG_GINTSTS_HCINT_Pos (25U) -#define USB_OTG_GINTSTS_HCINT_Msk (0x1UL << USB_OTG_GINTSTS_HCINT_Pos) /*!< 0x02000000 */ -#define USB_OTG_GINTSTS_HCINT USB_OTG_GINTSTS_HCINT_Msk /*!< Host channels interrupt */ -#define USB_OTG_GINTSTS_PTXFE_Pos (26U) -#define USB_OTG_GINTSTS_PTXFE_Msk (0x1UL << USB_OTG_GINTSTS_PTXFE_Pos) /*!< 0x04000000 */ -#define USB_OTG_GINTSTS_PTXFE USB_OTG_GINTSTS_PTXFE_Msk /*!< Periodic TxFIFO empty */ -#define USB_OTG_GINTSTS_CIDSCHG_Pos (28U) -#define USB_OTG_GINTSTS_CIDSCHG_Msk (0x1UL << USB_OTG_GINTSTS_CIDSCHG_Pos) /*!< 0x10000000 */ -#define USB_OTG_GINTSTS_CIDSCHG USB_OTG_GINTSTS_CIDSCHG_Msk /*!< Connector ID status change */ -#define USB_OTG_GINTSTS_DISCINT_Pos (29U) -#define USB_OTG_GINTSTS_DISCINT_Msk (0x1UL << USB_OTG_GINTSTS_DISCINT_Pos) /*!< 0x20000000 */ -#define USB_OTG_GINTSTS_DISCINT USB_OTG_GINTSTS_DISCINT_Msk /*!< Disconnect detected interrupt */ -#define USB_OTG_GINTSTS_SRQINT_Pos (30U) -#define USB_OTG_GINTSTS_SRQINT_Msk (0x1UL << USB_OTG_GINTSTS_SRQINT_Pos) /*!< 0x40000000 */ -#define USB_OTG_GINTSTS_SRQINT USB_OTG_GINTSTS_SRQINT_Msk /*!< Session request/new session detected interrupt */ -#define USB_OTG_GINTSTS_WKUINT_Pos (31U) -#define USB_OTG_GINTSTS_WKUINT_Msk (0x1UL << USB_OTG_GINTSTS_WKUINT_Pos) /*!< 0x80000000 */ -#define USB_OTG_GINTSTS_WKUINT USB_OTG_GINTSTS_WKUINT_Msk /*!< Resume/remote wakeup detected interrupt */ +/******************** Bit definition for HAINTMSK register ********************/ +#define HAINTMSK_HAINTM_Pos (0U) +#define HAINTMSK_HAINTM_Msk (0xFFFFUL << HAINTMSK_HAINTM_Pos) /*!< 0x0000FFFF */ +#define HAINTMSK_HAINTM HAINTMSK_HAINTM_Msk /*!< Channel interrupt mask */ -/******************** Bit definition for USB_OTG_GINTMSK register ********************/ -#define USB_OTG_GINTMSK_MMISM_Pos (1U) -#define USB_OTG_GINTMSK_MMISM_Msk (0x1UL << USB_OTG_GINTMSK_MMISM_Pos) /*!< 0x00000002 */ -#define USB_OTG_GINTMSK_MMISM USB_OTG_GINTMSK_MMISM_Msk /*!< Mode mismatch interrupt mask */ -#define USB_OTG_GINTMSK_OTGINT_Pos (2U) -#define USB_OTG_GINTMSK_OTGINT_Msk (0x1UL << USB_OTG_GINTMSK_OTGINT_Pos) /*!< 0x00000004 */ -#define USB_OTG_GINTMSK_OTGINT USB_OTG_GINTMSK_OTGINT_Msk /*!< OTG interrupt mask */ -#define USB_OTG_GINTMSK_SOFM_Pos (3U) -#define USB_OTG_GINTMSK_SOFM_Msk (0x1UL << USB_OTG_GINTMSK_SOFM_Pos) /*!< 0x00000008 */ -#define USB_OTG_GINTMSK_SOFM USB_OTG_GINTMSK_SOFM_Msk /*!< Start of frame mask */ -#define USB_OTG_GINTMSK_RXFLVLM_Pos (4U) -#define USB_OTG_GINTMSK_RXFLVLM_Msk (0x1UL << USB_OTG_GINTMSK_RXFLVLM_Pos) /*!< 0x00000010 */ -#define USB_OTG_GINTMSK_RXFLVLM USB_OTG_GINTMSK_RXFLVLM_Msk /*!< Receive FIFO nonempty mask */ -#define USB_OTG_GINTMSK_NPTXFEM_Pos (5U) -#define USB_OTG_GINTMSK_NPTXFEM_Msk (0x1UL << USB_OTG_GINTMSK_NPTXFEM_Pos) /*!< 0x00000020 */ -#define USB_OTG_GINTMSK_NPTXFEM USB_OTG_GINTMSK_NPTXFEM_Msk /*!< Nonperiodic TxFIFO empty mask */ -#define USB_OTG_GINTMSK_GINAKEFFM_Pos (6U) -#define USB_OTG_GINTMSK_GINAKEFFM_Msk (0x1UL << USB_OTG_GINTMSK_GINAKEFFM_Pos) /*!< 0x00000040 */ -#define USB_OTG_GINTMSK_GINAKEFFM USB_OTG_GINTMSK_GINAKEFFM_Msk /*!< Global nonperiodic IN NAK effective mask */ -#define USB_OTG_GINTMSK_GONAKEFFM_Pos (7U) -#define USB_OTG_GINTMSK_GONAKEFFM_Msk (0x1UL << USB_OTG_GINTMSK_GONAKEFFM_Pos) /*!< 0x00000080 */ -#define USB_OTG_GINTMSK_GONAKEFFM USB_OTG_GINTMSK_GONAKEFFM_Msk /*!< Global OUT NAK effective mask */ -#define USB_OTG_GINTMSK_ESUSPM_Pos (10U) -#define USB_OTG_GINTMSK_ESUSPM_Msk (0x1UL << USB_OTG_GINTMSK_ESUSPM_Pos) /*!< 0x00000400 */ -#define USB_OTG_GINTMSK_ESUSPM USB_OTG_GINTMSK_ESUSPM_Msk /*!< Early suspend mask */ -#define USB_OTG_GINTMSK_USBSUSPM_Pos (11U) -#define USB_OTG_GINTMSK_USBSUSPM_Msk (0x1UL << USB_OTG_GINTMSK_USBSUSPM_Pos) /*!< 0x00000800 */ -#define USB_OTG_GINTMSK_USBSUSPM USB_OTG_GINTMSK_USBSUSPM_Msk /*!< USB suspend mask */ -#define USB_OTG_GINTMSK_USBRST_Pos (12U) -#define USB_OTG_GINTMSK_USBRST_Msk (0x1UL << USB_OTG_GINTMSK_USBRST_Pos) /*!< 0x00001000 */ -#define USB_OTG_GINTMSK_USBRST USB_OTG_GINTMSK_USBRST_Msk /*!< USB reset mask */ -#define USB_OTG_GINTMSK_ENUMDNEM_Pos (13U) -#define USB_OTG_GINTMSK_ENUMDNEM_Msk (0x1UL << USB_OTG_GINTMSK_ENUMDNEM_Pos) /*!< 0x00002000 */ -#define USB_OTG_GINTMSK_ENUMDNEM USB_OTG_GINTMSK_ENUMDNEM_Msk /*!< Enumeration done mask */ -#define USB_OTG_GINTMSK_ISOODRPM_Pos (14U) -#define USB_OTG_GINTMSK_ISOODRPM_Msk (0x1UL << USB_OTG_GINTMSK_ISOODRPM_Pos) /*!< 0x00004000 */ -#define USB_OTG_GINTMSK_ISOODRPM USB_OTG_GINTMSK_ISOODRPM_Msk /*!< Isochronous OUT packet dropped interrupt mask */ -#define USB_OTG_GINTMSK_EOPFM_Pos (15U) -#define USB_OTG_GINTMSK_EOPFM_Msk (0x1UL << USB_OTG_GINTMSK_EOPFM_Pos) /*!< 0x00008000 */ -#define USB_OTG_GINTMSK_EOPFM USB_OTG_GINTMSK_EOPFM_Msk /*!< End of periodic frame interrupt mask */ -#define USB_OTG_GINTMSK_EPMISM_Pos (17U) -#define USB_OTG_GINTMSK_EPMISM_Msk (0x1UL << USB_OTG_GINTMSK_EPMISM_Pos) /*!< 0x00020000 */ -#define USB_OTG_GINTMSK_EPMISM USB_OTG_GINTMSK_EPMISM_Msk /*!< Endpoint mismatch interrupt mask */ -#define USB_OTG_GINTMSK_IEPINT_Pos (18U) -#define USB_OTG_GINTMSK_IEPINT_Msk (0x1UL << USB_OTG_GINTMSK_IEPINT_Pos) /*!< 0x00040000 */ -#define USB_OTG_GINTMSK_IEPINT USB_OTG_GINTMSK_IEPINT_Msk /*!< IN endpoints interrupt mask */ -#define USB_OTG_GINTMSK_OEPINT_Pos (19U) -#define USB_OTG_GINTMSK_OEPINT_Msk (0x1UL << USB_OTG_GINTMSK_OEPINT_Pos) /*!< 0x00080000 */ -#define USB_OTG_GINTMSK_OEPINT USB_OTG_GINTMSK_OEPINT_Msk /*!< OUT endpoints interrupt mask */ -#define USB_OTG_GINTMSK_IISOIXFRM_Pos (20U) -#define USB_OTG_GINTMSK_IISOIXFRM_Msk (0x1UL << USB_OTG_GINTMSK_IISOIXFRM_Pos) /*!< 0x00100000 */ -#define USB_OTG_GINTMSK_IISOIXFRM USB_OTG_GINTMSK_IISOIXFRM_Msk /*!< Incomplete isochronous IN transfer mask */ -#define USB_OTG_GINTMSK_PXFRM_IISOOXFRM_Pos (21U) -#define USB_OTG_GINTMSK_PXFRM_IISOOXFRM_Msk (0x1UL << USB_OTG_GINTMSK_PXFRM_IISOOXFRM_Pos) /*!< 0x00200000 */ -#define USB_OTG_GINTMSK_PXFRM_IISOOXFRM USB_OTG_GINTMSK_PXFRM_IISOOXFRM_Msk /*!< Incomplete periodic transfer mask */ -#define USB_OTG_GINTMSK_FSUSPM_Pos (22U) -#define USB_OTG_GINTMSK_FSUSPM_Msk (0x1UL << USB_OTG_GINTMSK_FSUSPM_Pos) /*!< 0x00400000 */ -#define USB_OTG_GINTMSK_FSUSPM USB_OTG_GINTMSK_FSUSPM_Msk /*!< Data fetch suspended mask */ -#define USB_OTG_GINTMSK_PRTIM_Pos (24U) -#define USB_OTG_GINTMSK_PRTIM_Msk (0x1UL << USB_OTG_GINTMSK_PRTIM_Pos) /*!< 0x01000000 */ -#define USB_OTG_GINTMSK_PRTIM USB_OTG_GINTMSK_PRTIM_Msk /*!< Host port interrupt mask */ -#define USB_OTG_GINTMSK_HCIM_Pos (25U) -#define USB_OTG_GINTMSK_HCIM_Msk (0x1UL << USB_OTG_GINTMSK_HCIM_Pos) /*!< 0x02000000 */ -#define USB_OTG_GINTMSK_HCIM USB_OTG_GINTMSK_HCIM_Msk /*!< Host channels interrupt mask */ -#define USB_OTG_GINTMSK_PTXFEM_Pos (26U) -#define USB_OTG_GINTMSK_PTXFEM_Msk (0x1UL << USB_OTG_GINTMSK_PTXFEM_Pos) /*!< 0x04000000 */ -#define USB_OTG_GINTMSK_PTXFEM USB_OTG_GINTMSK_PTXFEM_Msk /*!< Periodic TxFIFO empty mask */ -#define USB_OTG_GINTMSK_CIDSCHGM_Pos (28U) -#define USB_OTG_GINTMSK_CIDSCHGM_Msk (0x1UL << USB_OTG_GINTMSK_CIDSCHGM_Pos) /*!< 0x10000000 */ -#define USB_OTG_GINTMSK_CIDSCHGM USB_OTG_GINTMSK_CIDSCHGM_Msk /*!< Connector ID status change mask */ -#define USB_OTG_GINTMSK_DISCINT_Pos (29U) -#define USB_OTG_GINTMSK_DISCINT_Msk (0x1UL << USB_OTG_GINTMSK_DISCINT_Pos) /*!< 0x20000000 */ -#define USB_OTG_GINTMSK_DISCINT USB_OTG_GINTMSK_DISCINT_Msk /*!< Disconnect detected interrupt mask */ -#define USB_OTG_GINTMSK_SRQIM_Pos (30U) -#define USB_OTG_GINTMSK_SRQIM_Msk (0x1UL << USB_OTG_GINTMSK_SRQIM_Pos) /*!< 0x40000000 */ -#define USB_OTG_GINTMSK_SRQIM USB_OTG_GINTMSK_SRQIM_Msk /*!< Session request/new session detected interrupt mask */ -#define USB_OTG_GINTMSK_WUIM_Pos (31U) -#define USB_OTG_GINTMSK_WUIM_Msk (0x1UL << USB_OTG_GINTMSK_WUIM_Pos) /*!< 0x80000000 */ -#define USB_OTG_GINTMSK_WUIM USB_OTG_GINTMSK_WUIM_Msk /*!< Resume/remote wakeup detected interrupt mask */ +/******************** Bit definition for GRXSTSP register ********************/ +#define GRXSTSP_EPNUM_Pos (0U) +#define GRXSTSP_EPNUM_Msk (0xFUL << GRXSTSP_EPNUM_Pos) /*!< 0x0000000F */ +#define GRXSTSP_EPNUM GRXSTSP_EPNUM_Msk /*!< IN EP interrupt mask bits */ +#define GRXSTSP_BCNT_Pos (4U) +#define GRXSTSP_BCNT_Msk (0x7FFUL << GRXSTSP_BCNT_Pos) /*!< 0x00007FF0 */ +#define GRXSTSP_BCNT GRXSTSP_BCNT_Msk /*!< OUT EP interrupt mask bits */ +#define GRXSTSP_DPID_Pos (15U) +#define GRXSTSP_DPID_Msk (0x3UL << GRXSTSP_DPID_Pos) /*!< 0x00018000 */ +#define GRXSTSP_DPID GRXSTSP_DPID_Msk /*!< OUT EP interrupt mask bits */ +#define GRXSTSP_PKTSTS_Pos (17U) +#define GRXSTSP_PKTSTS_Msk (0xFUL << GRXSTSP_PKTSTS_Pos) /*!< 0x001E0000 */ +#define GRXSTSP_PKTSTS GRXSTSP_PKTSTS_Msk /*!< OUT EP interrupt mask bits */ -/******************** Bit definition for USB_OTG_DAINT register ********************/ -#define USB_OTG_DAINT_IEPINT_Pos (0U) -#define USB_OTG_DAINT_IEPINT_Msk (0xFFFFUL << USB_OTG_DAINT_IEPINT_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_DAINT_IEPINT USB_OTG_DAINT_IEPINT_Msk /*!< IN endpoint interrupt bits */ -#define USB_OTG_DAINT_OEPINT_Pos (16U) -#define USB_OTG_DAINT_OEPINT_Msk (0xFFFFUL << USB_OTG_DAINT_OEPINT_Pos) /*!< 0xFFFF0000 */ -#define USB_OTG_DAINT_OEPINT USB_OTG_DAINT_OEPINT_Msk /*!< OUT endpoint interrupt bits */ - -/******************** Bit definition for USB_OTG_HAINTMSK register ********************/ -#define USB_OTG_HAINTMSK_HAINTM_Pos (0U) -#define USB_OTG_HAINTMSK_HAINTM_Msk (0xFFFFUL << USB_OTG_HAINTMSK_HAINTM_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_HAINTMSK_HAINTM USB_OTG_HAINTMSK_HAINTM_Msk /*!< Channel interrupt mask */ - -/******************** Bit definition for USB_OTG_GRXSTSP register ********************/ -#define USB_OTG_GRXSTSP_EPNUM_Pos (0U) -#define USB_OTG_GRXSTSP_EPNUM_Msk (0xFUL << USB_OTG_GRXSTSP_EPNUM_Pos) /*!< 0x0000000F */ -#define USB_OTG_GRXSTSP_EPNUM USB_OTG_GRXSTSP_EPNUM_Msk /*!< IN EP interrupt mask bits */ -#define USB_OTG_GRXSTSP_BCNT_Pos (4U) -#define USB_OTG_GRXSTSP_BCNT_Msk (0x7FFUL << USB_OTG_GRXSTSP_BCNT_Pos) /*!< 0x00007FF0 */ -#define USB_OTG_GRXSTSP_BCNT USB_OTG_GRXSTSP_BCNT_Msk /*!< OUT EP interrupt mask bits */ -#define USB_OTG_GRXSTSP_DPID_Pos (15U) -#define USB_OTG_GRXSTSP_DPID_Msk (0x3UL << USB_OTG_GRXSTSP_DPID_Pos) /*!< 0x00018000 */ -#define USB_OTG_GRXSTSP_DPID USB_OTG_GRXSTSP_DPID_Msk /*!< OUT EP interrupt mask bits */ -#define USB_OTG_GRXSTSP_PKTSTS_Pos (17U) -#define USB_OTG_GRXSTSP_PKTSTS_Msk (0xFUL << USB_OTG_GRXSTSP_PKTSTS_Pos) /*!< 0x001E0000 */ -#define USB_OTG_GRXSTSP_PKTSTS USB_OTG_GRXSTSP_PKTSTS_Msk /*!< OUT EP interrupt mask bits */ - -/******************** Bit definition for USB_OTG_DAINTMSK register ********************/ -#define USB_OTG_DAINTMSK_IEPM_Pos (0U) -#define USB_OTG_DAINTMSK_IEPM_Msk (0xFFFFUL << USB_OTG_DAINTMSK_IEPM_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_DAINTMSK_IEPM USB_OTG_DAINTMSK_IEPM_Msk /*!< IN EP interrupt mask bits */ -#define USB_OTG_DAINTMSK_OEPM_Pos (16U) -#define USB_OTG_DAINTMSK_OEPM_Msk (0xFFFFUL << USB_OTG_DAINTMSK_OEPM_Pos) /*!< 0xFFFF0000 */ -#define USB_OTG_DAINTMSK_OEPM USB_OTG_DAINTMSK_OEPM_Msk /*!< OUT EP interrupt mask bits */ - -/******************** Bit definition for USB_OTG_GRXFSIZ register ********************/ -#define USB_OTG_GRXFSIZ_RXFD_Pos (0U) -#define USB_OTG_GRXFSIZ_RXFD_Msk (0xFFFFUL << USB_OTG_GRXFSIZ_RXFD_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_GRXFSIZ_RXFD USB_OTG_GRXFSIZ_RXFD_Msk /*!< RxFIFO depth */ - -/******************** Bit definition for USB_OTG_DVBUSDIS register ********************/ -#define USB_OTG_DVBUSDIS_VBUSDT_Pos (0U) -#define USB_OTG_DVBUSDIS_VBUSDT_Msk (0xFFFFUL << USB_OTG_DVBUSDIS_VBUSDT_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_DVBUSDIS_VBUSDT USB_OTG_DVBUSDIS_VBUSDT_Msk /*!< Device VBUS discharge time */ +/******************** Bit definition for DAINTMSK register ********************/ +#define DAINTMSK_IEPM_Pos (0U) +#define DAINTMSK_IEPM_Msk (0xFFFFUL << DAINTMSK_IEPM_Pos) /*!< 0x0000FFFF */ +#define DAINTMSK_IEPM DAINTMSK_IEPM_Msk /*!< IN EP interrupt mask bits */ +#define DAINTMSK_OEPM_Pos (16U) +#define DAINTMSK_OEPM_Msk (0xFFFFUL << DAINTMSK_OEPM_Pos) /*!< 0xFFFF0000 */ +#define DAINTMSK_OEPM DAINTMSK_OEPM_Msk /*!< OUT EP interrupt mask bits */ /******************** Bit definition for OTG register ********************/ -#define USB_OTG_NPTXFSA_Pos (0U) -#define USB_OTG_NPTXFSA_Msk (0xFFFFUL << USB_OTG_NPTXFSA_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_NPTXFSA USB_OTG_NPTXFSA_Msk /*!< Nonperiodic transmit RAM start address */ -#define USB_OTG_NPTXFD_Pos (16U) -#define USB_OTG_NPTXFD_Msk (0xFFFFUL << USB_OTG_NPTXFD_Pos) /*!< 0xFFFF0000 */ -#define USB_OTG_NPTXFD USB_OTG_NPTXFD_Msk /*!< Nonperiodic TxFIFO depth */ -#define USB_OTG_TX0FSA_Pos (0U) -#define USB_OTG_TX0FSA_Msk (0xFFFFUL << USB_OTG_TX0FSA_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_TX0FSA USB_OTG_TX0FSA_Msk /*!< Endpoint 0 transmit RAM start address */ -#define USB_OTG_TX0FD_Pos (16U) -#define USB_OTG_TX0FD_Msk (0xFFFFUL << USB_OTG_TX0FD_Pos) /*!< 0xFFFF0000 */ -#define USB_OTG_TX0FD USB_OTG_TX0FD_Msk /*!< Endpoint 0 TxFIFO depth */ -/******************** Bit definition for USB_OTG_DVBUSPULSE register ********************/ -#define USB_OTG_DVBUSPULSE_DVBUSP_Pos (0U) -#define USB_OTG_DVBUSPULSE_DVBUSP_Msk (0xFFFUL << USB_OTG_DVBUSPULSE_DVBUSP_Pos) /*!< 0x00000FFF */ -#define USB_OTG_DVBUSPULSE_DVBUSP USB_OTG_DVBUSPULSE_DVBUSP_Msk /*!< Device VBUS pulsing time */ +#define CHNUM_Pos (0U) +#define CHNUM_Msk (0xFUL << CHNUM_Pos) /*!< 0x0000000F */ +#define CHNUM CHNUM_Msk /*!< Channel number */ +#define CHNUM_0 (0x1UL << CHNUM_Pos) /*!< 0x00000001 */ +#define CHNUM_1 (0x2UL << CHNUM_Pos) /*!< 0x00000002 */ +#define CHNUM_2 (0x4UL << CHNUM_Pos) /*!< 0x00000004 */ +#define CHNUM_3 (0x8UL << CHNUM_Pos) /*!< 0x00000008 */ +#define BCNT_Pos (4U) +#define BCNT_Msk (0x7FFUL << BCNT_Pos) /*!< 0x00007FF0 */ +#define BCNT BCNT_Msk /*!< Byte count */ -/******************** Bit definition for USB_OTG_GNPTXSTS register ********************/ -#define USB_OTG_GNPTXSTS_NPTXFSAV_Pos (0U) -#define USB_OTG_GNPTXSTS_NPTXFSAV_Msk (0xFFFFUL << USB_OTG_GNPTXSTS_NPTXFSAV_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_GNPTXSTS_NPTXFSAV USB_OTG_GNPTXSTS_NPTXFSAV_Msk /*!< Nonperiodic TxFIFO space available */ +#define DPID_Pos (15U) +#define DPID_Msk (0x3UL << DPID_Pos) /*!< 0x00018000 */ +#define DPID DPID_Msk /*!< Data PID */ +#define DPID_0 (0x1UL << DPID_Pos) /*!< 0x00008000 */ +#define DPID_1 (0x2UL << DPID_Pos) /*!< 0x00010000 */ -#define USB_OTG_GNPTXSTS_NPTQXSAV_Pos (16U) -#define USB_OTG_GNPTXSTS_NPTQXSAV_Msk (0xFFUL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00FF0000 */ -#define USB_OTG_GNPTXSTS_NPTQXSAV USB_OTG_GNPTXSTS_NPTQXSAV_Msk /*!< Nonperiodic transmit request queue space available */ -#define USB_OTG_GNPTXSTS_NPTQXSAV_0 (0x01UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00010000 */ -#define USB_OTG_GNPTXSTS_NPTQXSAV_1 (0x02UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00020000 */ -#define USB_OTG_GNPTXSTS_NPTQXSAV_2 (0x04UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00040000 */ -#define USB_OTG_GNPTXSTS_NPTQXSAV_3 (0x08UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00080000 */ -#define USB_OTG_GNPTXSTS_NPTQXSAV_4 (0x10UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00100000 */ -#define USB_OTG_GNPTXSTS_NPTQXSAV_5 (0x20UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00200000 */ -#define USB_OTG_GNPTXSTS_NPTQXSAV_6 (0x40UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00400000 */ -#define USB_OTG_GNPTXSTS_NPTQXSAV_7 (0x80UL << USB_OTG_GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00800000 */ +#define PKTSTS_Pos (17U) +#define PKTSTS_Msk (0xFUL << PKTSTS_Pos) /*!< 0x001E0000 */ +#define PKTSTS PKTSTS_Msk /*!< Packet status */ +#define PKTSTS_0 (0x1UL << PKTSTS_Pos) /*!< 0x00020000 */ +#define PKTSTS_1 (0x2UL << PKTSTS_Pos) /*!< 0x00040000 */ +#define PKTSTS_2 (0x4UL << PKTSTS_Pos) /*!< 0x00080000 */ +#define PKTSTS_3 (0x8UL << PKTSTS_Pos) /*!< 0x00100000 */ -#define USB_OTG_GNPTXSTS_NPTXQTOP_Pos (24U) -#define USB_OTG_GNPTXSTS_NPTXQTOP_Msk (0x7FUL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x7F000000 */ -#define USB_OTG_GNPTXSTS_NPTXQTOP USB_OTG_GNPTXSTS_NPTXQTOP_Msk /*!< Top of the nonperiodic transmit request queue */ -#define USB_OTG_GNPTXSTS_NPTXQTOP_0 (0x01UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x01000000 */ -#define USB_OTG_GNPTXSTS_NPTXQTOP_1 (0x02UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x02000000 */ -#define USB_OTG_GNPTXSTS_NPTXQTOP_2 (0x04UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x04000000 */ -#define USB_OTG_GNPTXSTS_NPTXQTOP_3 (0x08UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x08000000 */ -#define USB_OTG_GNPTXSTS_NPTXQTOP_4 (0x10UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x10000000 */ -#define USB_OTG_GNPTXSTS_NPTXQTOP_5 (0x20UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x20000000 */ -#define USB_OTG_GNPTXSTS_NPTXQTOP_6 (0x40UL << USB_OTG_GNPTXSTS_NPTXQTOP_Pos) /*!< 0x40000000 */ +#define EPNUM_Pos (0U) +#define EPNUM_Msk (0xFUL << EPNUM_Pos) /*!< 0x0000000F */ +#define EPNUM EPNUM_Msk /*!< Endpoint number */ +#define EPNUM_0 (0x1UL << EPNUM_Pos) /*!< 0x00000001 */ +#define EPNUM_1 (0x2UL << EPNUM_Pos) /*!< 0x00000002 */ +#define EPNUM_2 (0x4UL << EPNUM_Pos) /*!< 0x00000004 */ +#define EPNUM_3 (0x8UL << EPNUM_Pos) /*!< 0x00000008 */ -/******************** Bit definition for USB_OTG_DTHRCTL register ********************/ -#define USB_OTG_DTHRCTL_NONISOTHREN_Pos (0U) -#define USB_OTG_DTHRCTL_NONISOTHREN_Msk (0x1UL << USB_OTG_DTHRCTL_NONISOTHREN_Pos) /*!< 0x00000001 */ -#define USB_OTG_DTHRCTL_NONISOTHREN USB_OTG_DTHRCTL_NONISOTHREN_Msk /*!< Nonisochronous IN endpoints threshold enable */ -#define USB_OTG_DTHRCTL_ISOTHREN_Pos (1U) -#define USB_OTG_DTHRCTL_ISOTHREN_Msk (0x1UL << USB_OTG_DTHRCTL_ISOTHREN_Pos) /*!< 0x00000002 */ -#define USB_OTG_DTHRCTL_ISOTHREN USB_OTG_DTHRCTL_ISOTHREN_Msk /*!< ISO IN endpoint threshold enable */ +#define FRMNUM_Pos (21U) +#define FRMNUM_Msk (0xFUL << FRMNUM_Pos) /*!< 0x01E00000 */ +#define FRMNUM FRMNUM_Msk /*!< Frame number */ +#define FRMNUM_0 (0x1UL << FRMNUM_Pos) /*!< 0x00200000 */ +#define FRMNUM_1 (0x2UL << FRMNUM_Pos) /*!< 0x00400000 */ +#define FRMNUM_2 (0x4UL << FRMNUM_Pos) /*!< 0x00800000 */ +#define FRMNUM_3 (0x8UL << FRMNUM_Pos) /*!< 0x01000000 */ -#define USB_OTG_DTHRCTL_TXTHRLEN_Pos (2U) -#define USB_OTG_DTHRCTL_TXTHRLEN_Msk (0x1FFUL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x000007FC */ -#define USB_OTG_DTHRCTL_TXTHRLEN USB_OTG_DTHRCTL_TXTHRLEN_Msk /*!< Transmit threshold length */ -#define USB_OTG_DTHRCTL_TXTHRLEN_0 (0x001UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000004 */ -#define USB_OTG_DTHRCTL_TXTHRLEN_1 (0x002UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000008 */ -#define USB_OTG_DTHRCTL_TXTHRLEN_2 (0x004UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000010 */ -#define USB_OTG_DTHRCTL_TXTHRLEN_3 (0x008UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000020 */ -#define USB_OTG_DTHRCTL_TXTHRLEN_4 (0x010UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000040 */ -#define USB_OTG_DTHRCTL_TXTHRLEN_5 (0x020UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000080 */ -#define USB_OTG_DTHRCTL_TXTHRLEN_6 (0x040UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000100 */ -#define USB_OTG_DTHRCTL_TXTHRLEN_7 (0x080UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000200 */ -#define USB_OTG_DTHRCTL_TXTHRLEN_8 (0x100UL << USB_OTG_DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000400 */ -#define USB_OTG_DTHRCTL_RXTHREN_Pos (16U) -#define USB_OTG_DTHRCTL_RXTHREN_Msk (0x1UL << USB_OTG_DTHRCTL_RXTHREN_Pos) /*!< 0x00010000 */ -#define USB_OTG_DTHRCTL_RXTHREN USB_OTG_DTHRCTL_RXTHREN_Msk /*!< Receive threshold enable */ +/******************** Bit definition for GRXFSIZ register ********************/ +#define GRXFSIZ_RXFD_Pos (0U) +#define GRXFSIZ_RXFD_Msk (0xFFFFUL << GRXFSIZ_RXFD_Pos) /*!< 0x0000FFFF */ +#define GRXFSIZ_RXFD GRXFSIZ_RXFD_Msk /*!< RxFIFO depth */ -#define USB_OTG_DTHRCTL_RXTHRLEN_Pos (17U) -#define USB_OTG_DTHRCTL_RXTHRLEN_Msk (0x1FFUL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x03FE0000 */ -#define USB_OTG_DTHRCTL_RXTHRLEN USB_OTG_DTHRCTL_RXTHRLEN_Msk /*!< Receive threshold length */ -#define USB_OTG_DTHRCTL_RXTHRLEN_0 (0x001UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00020000 */ -#define USB_OTG_DTHRCTL_RXTHRLEN_1 (0x002UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00040000 */ -#define USB_OTG_DTHRCTL_RXTHRLEN_2 (0x004UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00080000 */ -#define USB_OTG_DTHRCTL_RXTHRLEN_3 (0x008UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00100000 */ -#define USB_OTG_DTHRCTL_RXTHRLEN_4 (0x010UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00200000 */ -#define USB_OTG_DTHRCTL_RXTHRLEN_5 (0x020UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00400000 */ -#define USB_OTG_DTHRCTL_RXTHRLEN_6 (0x040UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x00800000 */ -#define USB_OTG_DTHRCTL_RXTHRLEN_7 (0x080UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x01000000 */ -#define USB_OTG_DTHRCTL_RXTHRLEN_8 (0x100UL << USB_OTG_DTHRCTL_RXTHRLEN_Pos) /*!< 0x02000000 */ -#define USB_OTG_DTHRCTL_ARPEN_Pos (27U) -#define USB_OTG_DTHRCTL_ARPEN_Msk (0x1UL << USB_OTG_DTHRCTL_ARPEN_Pos) /*!< 0x08000000 */ -#define USB_OTG_DTHRCTL_ARPEN USB_OTG_DTHRCTL_ARPEN_Msk /*!< Arbiter parking enable */ +/******************** Bit definition for DVBUSDIS register ********************/ +#define DVBUSDIS_VBUSDT_Pos (0U) +#define DVBUSDIS_VBUSDT_Msk (0xFFFFUL << DVBUSDIS_VBUSDT_Pos) /*!< 0x0000FFFF */ +#define DVBUSDIS_VBUSDT DVBUSDIS_VBUSDT_Msk /*!< Device VBUS discharge time */ -/******************** Bit definition for USB_OTG_DIEPEMPMSK register ********************/ -#define USB_OTG_DIEPEMPMSK_INEPTXFEM_Pos (0U) -#define USB_OTG_DIEPEMPMSK_INEPTXFEM_Msk (0xFFFFUL << USB_OTG_DIEPEMPMSK_INEPTXFEM_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_DIEPEMPMSK_INEPTXFEM USB_OTG_DIEPEMPMSK_INEPTXFEM_Msk /*!< IN EP Tx FIFO empty interrupt mask bits */ +/******************** Bit definition for OTG register ********************/ +#define NPTXFSA_Pos (0U) +#define NPTXFSA_Msk (0xFFFFUL << NPTXFSA_Pos) /*!< 0x0000FFFF */ +#define NPTXFSA NPTXFSA_Msk /*!< Nonperiodic transmit RAM start address */ +#define NPTXFD_Pos (16U) +#define NPTXFD_Msk (0xFFFFUL << NPTXFD_Pos) /*!< 0xFFFF0000 */ +#define NPTXFD NPTXFD_Msk /*!< Nonperiodic TxFIFO depth */ +#define TX0FSA_Pos (0U) +#define TX0FSA_Msk (0xFFFFUL << TX0FSA_Pos) /*!< 0x0000FFFF */ +#define TX0FSA TX0FSA_Msk /*!< Endpoint 0 transmit RAM start address */ +#define TX0FD_Pos (16U) +#define TX0FD_Msk (0xFFFFUL << TX0FD_Pos) /*!< 0xFFFF0000 */ +#define TX0FD TX0FD_Msk /*!< Endpoint 0 TxFIFO depth */ -/******************** Bit definition for USB_OTG_DEACHINT register ********************/ -#define USB_OTG_DEACHINT_IEP1INT_Pos (1U) -#define USB_OTG_DEACHINT_IEP1INT_Msk (0x1UL << USB_OTG_DEACHINT_IEP1INT_Pos) /*!< 0x00000002 */ -#define USB_OTG_DEACHINT_IEP1INT USB_OTG_DEACHINT_IEP1INT_Msk /*!< IN endpoint 1interrupt bit */ -#define USB_OTG_DEACHINT_OEP1INT_Pos (17U) -#define USB_OTG_DEACHINT_OEP1INT_Msk (0x1UL << USB_OTG_DEACHINT_OEP1INT_Pos) /*!< 0x00020000 */ -#define USB_OTG_DEACHINT_OEP1INT USB_OTG_DEACHINT_OEP1INT_Msk /*!< OUT endpoint 1 interrupt bit */ +/******************** Bit definition for DVBUSPULSE register ********************/ +#define DVBUSPULSE_DVBUSP_Pos (0U) +#define DVBUSPULSE_DVBUSP_Msk (0xFFFUL << DVBUSPULSE_DVBUSP_Pos) /*!< 0x00000FFF */ +#define DVBUSPULSE_DVBUSP DVBUSPULSE_DVBUSP_Msk /*!< Device VBUS pulsing time */ -/******************** Bit definition for USB_OTG_GCCFG register ********************/ -#define USB_OTG_GCCFG_PWRDWN_Pos (16U) -#define USB_OTG_GCCFG_PWRDWN_Msk (0x1UL << USB_OTG_GCCFG_PWRDWN_Pos) /*!< 0x00010000 */ -#define USB_OTG_GCCFG_PWRDWN USB_OTG_GCCFG_PWRDWN_Msk /*!< Power down */ -#define USB_OTG_GCCFG_VBUSASEN_Pos (18U) -#define USB_OTG_GCCFG_VBUSASEN_Msk (0x1UL << USB_OTG_GCCFG_VBUSASEN_Pos) /*!< 0x00040000 */ -#define USB_OTG_GCCFG_VBUSASEN USB_OTG_GCCFG_VBUSASEN_Msk /*!< Enable the VBUS sensing device */ -#define USB_OTG_GCCFG_VBUSBSEN_Pos (19U) -#define USB_OTG_GCCFG_VBUSBSEN_Msk (0x1UL << USB_OTG_GCCFG_VBUSBSEN_Pos) /*!< 0x00080000 */ -#define USB_OTG_GCCFG_VBUSBSEN USB_OTG_GCCFG_VBUSBSEN_Msk /*!< Enable the VBUS sensing device */ -#define USB_OTG_GCCFG_SOFOUTEN_Pos (20U) -#define USB_OTG_GCCFG_SOFOUTEN_Msk (0x1UL << USB_OTG_GCCFG_SOFOUTEN_Pos) /*!< 0x00100000 */ -#define USB_OTG_GCCFG_SOFOUTEN USB_OTG_GCCFG_SOFOUTEN_Msk /*!< SOF output enable */ +/******************** Bit definition for GNPTXSTS register ********************/ +#define GNPTXSTS_NPTXFSAV_Pos (0U) +#define GNPTXSTS_NPTXFSAV_Msk (0xFFFFUL << GNPTXSTS_NPTXFSAV_Pos) /*!< 0x0000FFFF */ +#define GNPTXSTS_NPTXFSAV GNPTXSTS_NPTXFSAV_Msk /*!< Nonperiodic TxFIFO space available */ -/******************** Bit definition for USB_OTG_DEACHINTMSK register ********************/ -#define USB_OTG_DEACHINTMSK_IEP1INTM_Pos (1U) -#define USB_OTG_DEACHINTMSK_IEP1INTM_Msk (0x1UL << USB_OTG_DEACHINTMSK_IEP1INTM_Pos) /*!< 0x00000002 */ -#define USB_OTG_DEACHINTMSK_IEP1INTM USB_OTG_DEACHINTMSK_IEP1INTM_Msk /*!< IN Endpoint 1 interrupt mask bit */ -#define USB_OTG_DEACHINTMSK_OEP1INTM_Pos (17U) -#define USB_OTG_DEACHINTMSK_OEP1INTM_Msk (0x1UL << USB_OTG_DEACHINTMSK_OEP1INTM_Pos) /*!< 0x00020000 */ -#define USB_OTG_DEACHINTMSK_OEP1INTM USB_OTG_DEACHINTMSK_OEP1INTM_Msk /*!< OUT Endpoint 1 interrupt mask bit */ +#define GNPTXSTS_NPTQXSAV_Pos (16U) +#define GNPTXSTS_NPTQXSAV_Msk (0xFFUL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00FF0000 */ +#define GNPTXSTS_NPTQXSAV GNPTXSTS_NPTQXSAV_Msk /*!< Nonperiodic transmit request queue space available */ +#define GNPTXSTS_NPTQXSAV_0 (0x01UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00010000 */ +#define GNPTXSTS_NPTQXSAV_1 (0x02UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00020000 */ +#define GNPTXSTS_NPTQXSAV_2 (0x04UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00040000 */ +#define GNPTXSTS_NPTQXSAV_3 (0x08UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00080000 */ +#define GNPTXSTS_NPTQXSAV_4 (0x10UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00100000 */ +#define GNPTXSTS_NPTQXSAV_5 (0x20UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00200000 */ +#define GNPTXSTS_NPTQXSAV_6 (0x40UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00400000 */ +#define GNPTXSTS_NPTQXSAV_7 (0x80UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00800000 */ -/******************** Bit definition for USB_OTG_CID register ********************/ -#define USB_OTG_CID_PRODUCT_ID_Pos (0U) -#define USB_OTG_CID_PRODUCT_ID_Msk (0xFFFFFFFFUL << USB_OTG_CID_PRODUCT_ID_Pos) /*!< 0xFFFFFFFF */ -#define USB_OTG_CID_PRODUCT_ID USB_OTG_CID_PRODUCT_ID_Msk /*!< Product ID field */ +#define GNPTXSTS_NPTXQTOP_Pos (24U) +#define GNPTXSTS_NPTXQTOP_Msk (0x7FUL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x7F000000 */ +#define GNPTXSTS_NPTXQTOP GNPTXSTS_NPTXQTOP_Msk /*!< Top of the nonperiodic transmit request queue */ +#define GNPTXSTS_NPTXQTOP_0 (0x01UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x01000000 */ +#define GNPTXSTS_NPTXQTOP_1 (0x02UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x02000000 */ +#define GNPTXSTS_NPTXQTOP_2 (0x04UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x04000000 */ +#define GNPTXSTS_NPTXQTOP_3 (0x08UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x08000000 */ +#define GNPTXSTS_NPTXQTOP_4 (0x10UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x10000000 */ +#define GNPTXSTS_NPTXQTOP_5 (0x20UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x20000000 */ +#define GNPTXSTS_NPTXQTOP_6 (0x40UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x40000000 */ -/******************** Bit definition for USB_OTG_DIEPEACHMSK1 register ********************/ -#define USB_OTG_DIEPEACHMSK1_XFRCM_Pos (0U) -#define USB_OTG_DIEPEACHMSK1_XFRCM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ -#define USB_OTG_DIEPEACHMSK1_XFRCM USB_OTG_DIEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ -#define USB_OTG_DIEPEACHMSK1_EPDM_Pos (1U) -#define USB_OTG_DIEPEACHMSK1_EPDM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ -#define USB_OTG_DIEPEACHMSK1_EPDM USB_OTG_DIEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ -#define USB_OTG_DIEPEACHMSK1_TOM_Pos (3U) -#define USB_OTG_DIEPEACHMSK1_TOM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ -#define USB_OTG_DIEPEACHMSK1_TOM USB_OTG_DIEPEACHMSK1_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ -#define USB_OTG_DIEPEACHMSK1_ITTXFEMSK_Pos (4U) -#define USB_OTG_DIEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ -#define USB_OTG_DIEPEACHMSK1_ITTXFEMSK USB_OTG_DIEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ -#define USB_OTG_DIEPEACHMSK1_INEPNMM_Pos (5U) -#define USB_OTG_DIEPEACHMSK1_INEPNMM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ -#define USB_OTG_DIEPEACHMSK1_INEPNMM USB_OTG_DIEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ -#define USB_OTG_DIEPEACHMSK1_INEPNEM_Pos (6U) -#define USB_OTG_DIEPEACHMSK1_INEPNEM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ -#define USB_OTG_DIEPEACHMSK1_INEPNEM USB_OTG_DIEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ -#define USB_OTG_DIEPEACHMSK1_TXFURM_Pos (8U) -#define USB_OTG_DIEPEACHMSK1_TXFURM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ -#define USB_OTG_DIEPEACHMSK1_TXFURM USB_OTG_DIEPEACHMSK1_TXFURM_Msk /*!< FIFO underrun mask */ -#define USB_OTG_DIEPEACHMSK1_BIM_Pos (9U) -#define USB_OTG_DIEPEACHMSK1_BIM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ -#define USB_OTG_DIEPEACHMSK1_BIM USB_OTG_DIEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ -#define USB_OTG_DIEPEACHMSK1_NAKM_Pos (13U) -#define USB_OTG_DIEPEACHMSK1_NAKM_Msk (0x1UL << USB_OTG_DIEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ -#define USB_OTG_DIEPEACHMSK1_NAKM USB_OTG_DIEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ +/******************** Bit definition for DTHRCTL register ********************/ +#define DTHRCTL_NONISOTHREN_Pos (0U) +#define DTHRCTL_NONISOTHREN_Msk (0x1UL << DTHRCTL_NONISOTHREN_Pos) /*!< 0x00000001 */ +#define DTHRCTL_NONISOTHREN DTHRCTL_NONISOTHREN_Msk /*!< Nonisochronous IN endpoints threshold enable */ +#define DTHRCTL_ISOTHREN_Pos (1U) +#define DTHRCTL_ISOTHREN_Msk (0x1UL << DTHRCTL_ISOTHREN_Pos) /*!< 0x00000002 */ +#define DTHRCTL_ISOTHREN DTHRCTL_ISOTHREN_Msk /*!< ISO IN endpoint threshold enable */ -/******************** Bit definition for USB_OTG_HPRT register ********************/ -#define USB_OTG_HPRT_PCSTS_Pos (0U) -#define USB_OTG_HPRT_PCSTS_Msk (0x1UL << USB_OTG_HPRT_PCSTS_Pos) /*!< 0x00000001 */ -#define USB_OTG_HPRT_PCSTS USB_OTG_HPRT_PCSTS_Msk /*!< Port connect status */ -#define USB_OTG_HPRT_PCDET_Pos (1U) -#define USB_OTG_HPRT_PCDET_Msk (0x1UL << USB_OTG_HPRT_PCDET_Pos) /*!< 0x00000002 */ -#define USB_OTG_HPRT_PCDET USB_OTG_HPRT_PCDET_Msk /*!< Port connect detected */ -#define USB_OTG_HPRT_PENA_Pos (2U) -#define USB_OTG_HPRT_PENA_Msk (0x1UL << USB_OTG_HPRT_PENA_Pos) /*!< 0x00000004 */ -#define USB_OTG_HPRT_PENA USB_OTG_HPRT_PENA_Msk /*!< Port enable */ -#define USB_OTG_HPRT_PENCHNG_Pos (3U) -#define USB_OTG_HPRT_PENCHNG_Msk (0x1UL << USB_OTG_HPRT_PENCHNG_Pos) /*!< 0x00000008 */ -#define USB_OTG_HPRT_PENCHNG USB_OTG_HPRT_PENCHNG_Msk /*!< Port enable/disable change */ -#define USB_OTG_HPRT_POCA_Pos (4U) -#define USB_OTG_HPRT_POCA_Msk (0x1UL << USB_OTG_HPRT_POCA_Pos) /*!< 0x00000010 */ -#define USB_OTG_HPRT_POCA USB_OTG_HPRT_POCA_Msk /*!< Port overcurrent active */ -#define USB_OTG_HPRT_POCCHNG_Pos (5U) -#define USB_OTG_HPRT_POCCHNG_Msk (0x1UL << USB_OTG_HPRT_POCCHNG_Pos) /*!< 0x00000020 */ -#define USB_OTG_HPRT_POCCHNG USB_OTG_HPRT_POCCHNG_Msk /*!< Port overcurrent change */ -#define USB_OTG_HPRT_PRES_Pos (6U) -#define USB_OTG_HPRT_PRES_Msk (0x1UL << USB_OTG_HPRT_PRES_Pos) /*!< 0x00000040 */ -#define USB_OTG_HPRT_PRES USB_OTG_HPRT_PRES_Msk /*!< Port resume */ -#define USB_OTG_HPRT_PSUSP_Pos (7U) -#define USB_OTG_HPRT_PSUSP_Msk (0x1UL << USB_OTG_HPRT_PSUSP_Pos) /*!< 0x00000080 */ -#define USB_OTG_HPRT_PSUSP USB_OTG_HPRT_PSUSP_Msk /*!< Port suspend */ -#define USB_OTG_HPRT_PRST_Pos (8U) -#define USB_OTG_HPRT_PRST_Msk (0x1UL << USB_OTG_HPRT_PRST_Pos) /*!< 0x00000100 */ -#define USB_OTG_HPRT_PRST USB_OTG_HPRT_PRST_Msk /*!< Port reset */ +#define DTHRCTL_TXTHRLEN_Pos (2U) +#define DTHRCTL_TXTHRLEN_Msk (0x1FFUL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x000007FC */ +#define DTHRCTL_TXTHRLEN DTHRCTL_TXTHRLEN_Msk /*!< Transmit threshold length */ +#define DTHRCTL_TXTHRLEN_0 (0x001UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000004 */ +#define DTHRCTL_TXTHRLEN_1 (0x002UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000008 */ +#define DTHRCTL_TXTHRLEN_2 (0x004UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000010 */ +#define DTHRCTL_TXTHRLEN_3 (0x008UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000020 */ +#define DTHRCTL_TXTHRLEN_4 (0x010UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000040 */ +#define DTHRCTL_TXTHRLEN_5 (0x020UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000080 */ +#define DTHRCTL_TXTHRLEN_6 (0x040UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000100 */ +#define DTHRCTL_TXTHRLEN_7 (0x080UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000200 */ +#define DTHRCTL_TXTHRLEN_8 (0x100UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000400 */ +#define DTHRCTL_RXTHREN_Pos (16U) +#define DTHRCTL_RXTHREN_Msk (0x1UL << DTHRCTL_RXTHREN_Pos) /*!< 0x00010000 */ +#define DTHRCTL_RXTHREN DTHRCTL_RXTHREN_Msk /*!< Receive threshold enable */ -#define USB_OTG_HPRT_PLSTS_Pos (10U) -#define USB_OTG_HPRT_PLSTS_Msk (0x3UL << USB_OTG_HPRT_PLSTS_Pos) /*!< 0x00000C00 */ -#define USB_OTG_HPRT_PLSTS USB_OTG_HPRT_PLSTS_Msk /*!< Port line status */ -#define USB_OTG_HPRT_PLSTS_0 (0x1UL << USB_OTG_HPRT_PLSTS_Pos) /*!< 0x00000400 */ -#define USB_OTG_HPRT_PLSTS_1 (0x2UL << USB_OTG_HPRT_PLSTS_Pos) /*!< 0x00000800 */ -#define USB_OTG_HPRT_PPWR_Pos (12U) -#define USB_OTG_HPRT_PPWR_Msk (0x1UL << USB_OTG_HPRT_PPWR_Pos) /*!< 0x00001000 */ -#define USB_OTG_HPRT_PPWR USB_OTG_HPRT_PPWR_Msk /*!< Port power */ +#define DTHRCTL_RXTHRLEN_Pos (17U) +#define DTHRCTL_RXTHRLEN_Msk (0x1FFUL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x03FE0000 */ +#define DTHRCTL_RXTHRLEN DTHRCTL_RXTHRLEN_Msk /*!< Receive threshold length */ +#define DTHRCTL_RXTHRLEN_0 (0x001UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00020000 */ +#define DTHRCTL_RXTHRLEN_1 (0x002UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00040000 */ +#define DTHRCTL_RXTHRLEN_2 (0x004UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00080000 */ +#define DTHRCTL_RXTHRLEN_3 (0x008UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00100000 */ +#define DTHRCTL_RXTHRLEN_4 (0x010UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00200000 */ +#define DTHRCTL_RXTHRLEN_5 (0x020UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00400000 */ +#define DTHRCTL_RXTHRLEN_6 (0x040UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00800000 */ +#define DTHRCTL_RXTHRLEN_7 (0x080UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x01000000 */ +#define DTHRCTL_RXTHRLEN_8 (0x100UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x02000000 */ +#define DTHRCTL_ARPEN_Pos (27U) +#define DTHRCTL_ARPEN_Msk (0x1UL << DTHRCTL_ARPEN_Pos) /*!< 0x08000000 */ +#define DTHRCTL_ARPEN DTHRCTL_ARPEN_Msk /*!< Arbiter parking enable */ -#define USB_OTG_HPRT_PTCTL_Pos (13U) -#define USB_OTG_HPRT_PTCTL_Msk (0xFUL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x0001E000 */ -#define USB_OTG_HPRT_PTCTL USB_OTG_HPRT_PTCTL_Msk /*!< Port test control */ -#define USB_OTG_HPRT_PTCTL_0 (0x1UL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x00002000 */ -#define USB_OTG_HPRT_PTCTL_1 (0x2UL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x00004000 */ -#define USB_OTG_HPRT_PTCTL_2 (0x4UL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x00008000 */ -#define USB_OTG_HPRT_PTCTL_3 (0x8UL << USB_OTG_HPRT_PTCTL_Pos) /*!< 0x00010000 */ +/******************** Bit definition for DIEPEMPMSK register ********************/ +#define DIEPEMPMSK_INEPTXFEM_Pos (0U) +#define DIEPEMPMSK_INEPTXFEM_Msk (0xFFFFUL << DIEPEMPMSK_INEPTXFEM_Pos) /*!< 0x0000FFFF */ +#define DIEPEMPMSK_INEPTXFEM DIEPEMPMSK_INEPTXFEM_Msk /*!< IN EP Tx FIFO empty interrupt mask bits */ -#define USB_OTG_HPRT_PSPD_Pos (17U) -#define USB_OTG_HPRT_PSPD_Msk (0x3UL << USB_OTG_HPRT_PSPD_Pos) /*!< 0x00060000 */ -#define USB_OTG_HPRT_PSPD USB_OTG_HPRT_PSPD_Msk /*!< Port speed */ -#define USB_OTG_HPRT_PSPD_0 (0x1UL << USB_OTG_HPRT_PSPD_Pos) /*!< 0x00020000 */ -#define USB_OTG_HPRT_PSPD_1 (0x2UL << USB_OTG_HPRT_PSPD_Pos) /*!< 0x00040000 */ +/******************** Bit definition for DEACHINT register ********************/ +#define DEACHINT_IEP1INT_Pos (1U) +#define DEACHINT_IEP1INT_Msk (0x1UL << DEACHINT_IEP1INT_Pos) /*!< 0x00000002 */ +#define DEACHINT_IEP1INT DEACHINT_IEP1INT_Msk /*!< IN endpoint 1interrupt bit */ +#define DEACHINT_OEP1INT_Pos (17U) +#define DEACHINT_OEP1INT_Msk (0x1UL << DEACHINT_OEP1INT_Pos) /*!< 0x00020000 */ +#define DEACHINT_OEP1INT DEACHINT_OEP1INT_Msk /*!< OUT endpoint 1 interrupt bit */ -/******************** Bit definition for USB_OTG_DOEPEACHMSK1 register ********************/ -#define USB_OTG_DOEPEACHMSK1_XFRCM_Pos (0U) -#define USB_OTG_DOEPEACHMSK1_XFRCM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ -#define USB_OTG_DOEPEACHMSK1_XFRCM USB_OTG_DOEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ -#define USB_OTG_DOEPEACHMSK1_EPDM_Pos (1U) -#define USB_OTG_DOEPEACHMSK1_EPDM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ -#define USB_OTG_DOEPEACHMSK1_EPDM USB_OTG_DOEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ -#define USB_OTG_DOEPEACHMSK1_TOM_Pos (3U) -#define USB_OTG_DOEPEACHMSK1_TOM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ -#define USB_OTG_DOEPEACHMSK1_TOM USB_OTG_DOEPEACHMSK1_TOM_Msk /*!< Timeout condition mask */ -#define USB_OTG_DOEPEACHMSK1_ITTXFEMSK_Pos (4U) -#define USB_OTG_DOEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ -#define USB_OTG_DOEPEACHMSK1_ITTXFEMSK USB_OTG_DOEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ -#define USB_OTG_DOEPEACHMSK1_INEPNMM_Pos (5U) -#define USB_OTG_DOEPEACHMSK1_INEPNMM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ -#define USB_OTG_DOEPEACHMSK1_INEPNMM USB_OTG_DOEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ -#define USB_OTG_DOEPEACHMSK1_INEPNEM_Pos (6U) -#define USB_OTG_DOEPEACHMSK1_INEPNEM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ -#define USB_OTG_DOEPEACHMSK1_INEPNEM USB_OTG_DOEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ -#define USB_OTG_DOEPEACHMSK1_TXFURM_Pos (8U) -#define USB_OTG_DOEPEACHMSK1_TXFURM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ -#define USB_OTG_DOEPEACHMSK1_TXFURM USB_OTG_DOEPEACHMSK1_TXFURM_Msk /*!< OUT packet error mask */ -#define USB_OTG_DOEPEACHMSK1_BIM_Pos (9U) -#define USB_OTG_DOEPEACHMSK1_BIM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ -#define USB_OTG_DOEPEACHMSK1_BIM USB_OTG_DOEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ -#define USB_OTG_DOEPEACHMSK1_BERRM_Pos (12U) -#define USB_OTG_DOEPEACHMSK1_BERRM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_BERRM_Pos) /*!< 0x00001000 */ -#define USB_OTG_DOEPEACHMSK1_BERRM USB_OTG_DOEPEACHMSK1_BERRM_Msk /*!< Bubble error interrupt mask */ -#define USB_OTG_DOEPEACHMSK1_NAKM_Pos (13U) -#define USB_OTG_DOEPEACHMSK1_NAKM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ -#define USB_OTG_DOEPEACHMSK1_NAKM USB_OTG_DOEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ -#define USB_OTG_DOEPEACHMSK1_NYETM_Pos (14U) -#define USB_OTG_DOEPEACHMSK1_NYETM_Msk (0x1UL << USB_OTG_DOEPEACHMSK1_NYETM_Pos) /*!< 0x00004000 */ -#define USB_OTG_DOEPEACHMSK1_NYETM USB_OTG_DOEPEACHMSK1_NYETM_Msk /*!< NYET interrupt mask */ +/******************** Bit definition for GCCFG register ********************/ +#define GCCFG_DCDET_Pos (0U) +#define GCCFG_DCDET_Msk (0x1UL << GCCFG_DCDET_Pos) /*!< 0x00000001 */ +#define GCCFG_DCDET GCCFG_DCDET_Msk /*!< Data contact detection (DCD) status */ +#define GCCFG_PDET_Pos (1U) +#define GCCFG_PDET_Msk (0x1UL << GCCFG_PDET_Pos) /*!< 0x00000002 */ +#define GCCFG_PDET GCCFG_PDET_Msk /*!< Primary detection (PD) status */ +#define GCCFG_SDET_Pos (2U) +#define GCCFG_SDET_Msk (0x1UL << GCCFG_SDET_Pos) /*!< 0x00000004 */ +#define GCCFG_SDET GCCFG_SDET_Msk /*!< Secondary detection (SD) status */ +#define GCCFG_PS2DET_Pos (3U) +#define GCCFG_PS2DET_Msk (0x1UL << GCCFG_PS2DET_Pos) /*!< 0x00000008 */ +#define GCCFG_PS2DET GCCFG_PS2DET_Msk /*!< DM pull-up detection status */ +#define GCCFG_PWRDWN_Pos (16U) +#define GCCFG_PWRDWN_Msk (0x1UL << GCCFG_PWRDWN_Pos) /*!< 0x00010000 */ +#define GCCFG_PWRDWN GCCFG_PWRDWN_Msk /*!< Power down */ +#define GCCFG_BCDEN_Pos (17U) +#define GCCFG_BCDEN_Msk (0x1UL << GCCFG_BCDEN_Pos) /*!< 0x00020000 */ +#define GCCFG_BCDEN GCCFG_BCDEN_Msk /*!< Battery charging detector (BCD) enable */ +#define GCCFG_DCDEN_Pos (18U) +#define GCCFG_DCDEN_Msk (0x1UL << GCCFG_DCDEN_Pos) /*!< 0x00040000 */ +#define GCCFG_DCDEN GCCFG_DCDEN_Msk /*!< Data contact detection (DCD) mode enable*/ +#define GCCFG_PDEN_Pos (19U) +#define GCCFG_PDEN_Msk (0x1UL << GCCFG_PDEN_Pos) /*!< 0x00080000 */ +#define GCCFG_PDEN GCCFG_PDEN_Msk /*!< Primary detection (PD) mode enable*/ +#define GCCFG_SDEN_Pos (20U) +#define GCCFG_SDEN_Msk (0x1UL << GCCFG_SDEN_Pos) /*!< 0x00100000 */ +#define GCCFG_SDEN GCCFG_SDEN_Msk /*!< Secondary detection (SD) mode enable */ +#define GCCFG_VBDEN_Pos (21U) +#define GCCFG_VBDEN_Msk (0x1UL << GCCFG_VBDEN_Pos) /*!< 0x00200000 */ +#define GCCFG_VBDEN GCCFG_VBDEN_Msk /*!< VBUS mode enable */ +#define GCCFG_OTGIDEN_Pos (22U) +#define GCCFG_OTGIDEN_Msk (0x1UL << GCCFG_OTGIDEN_Pos) /*!< 0x00400000 */ +#define GCCFG_OTGIDEN GCCFG_OTGIDEN_Msk /*!< OTG Id enable */ +#define GCCFG_PHYHSEN_Pos (23U) +#define GCCFG_PHYHSEN_Msk (0x1UL << GCCFG_PHYHSEN_Pos) /*!< 0x00800000 */ +#define GCCFG_PHYHSEN GCCFG_PHYHSEN_Msk /*!< HS PHY enable */ -/******************** Bit definition for USB_OTG_HPTXFSIZ register ********************/ -#define USB_OTG_HPTXFSIZ_PTXSA_Pos (0U) -#define USB_OTG_HPTXFSIZ_PTXSA_Msk (0xFFFFUL << USB_OTG_HPTXFSIZ_PTXSA_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_HPTXFSIZ_PTXSA USB_OTG_HPTXFSIZ_PTXSA_Msk /*!< Host periodic TxFIFO start address */ -#define USB_OTG_HPTXFSIZ_PTXFD_Pos (16U) -#define USB_OTG_HPTXFSIZ_PTXFD_Msk (0xFFFFUL << USB_OTG_HPTXFSIZ_PTXFD_Pos) /*!< 0xFFFF0000 */ -#define USB_OTG_HPTXFSIZ_PTXFD USB_OTG_HPTXFSIZ_PTXFD_Msk /*!< Host periodic TxFIFO depth */ +/******************** Bit definition for DEACHINTMSK register ********************/ +#define DEACHINTMSK_IEP1INTM_Pos (1U) +#define DEACHINTMSK_IEP1INTM_Msk (0x1UL << DEACHINTMSK_IEP1INTM_Pos) /*!< 0x00000002 */ +#define DEACHINTMSK_IEP1INTM DEACHINTMSK_IEP1INTM_Msk /*!< IN Endpoint 1 interrupt mask bit */ +#define DEACHINTMSK_OEP1INTM_Pos (17U) +#define DEACHINTMSK_OEP1INTM_Msk (0x1UL << DEACHINTMSK_OEP1INTM_Pos) /*!< 0x00020000 */ +#define DEACHINTMSK_OEP1INTM DEACHINTMSK_OEP1INTM_Msk /*!< OUT Endpoint 1 interrupt mask bit */ -/******************** Bit definition for USB_OTG_DIEPCTL register ********************/ -#define USB_OTG_DIEPCTL_MPSIZ_Pos (0U) -#define USB_OTG_DIEPCTL_MPSIZ_Msk (0x7FFUL << USB_OTG_DIEPCTL_MPSIZ_Pos) /*!< 0x000007FF */ -#define USB_OTG_DIEPCTL_MPSIZ USB_OTG_DIEPCTL_MPSIZ_Msk /*!< Maximum packet size */ -#define USB_OTG_DIEPCTL_USBAEP_Pos (15U) -#define USB_OTG_DIEPCTL_USBAEP_Msk (0x1UL << USB_OTG_DIEPCTL_USBAEP_Pos) /*!< 0x00008000 */ -#define USB_OTG_DIEPCTL_USBAEP USB_OTG_DIEPCTL_USBAEP_Msk /*!< USB active endpoint */ -#define USB_OTG_DIEPCTL_EONUM_DPID_Pos (16U) -#define USB_OTG_DIEPCTL_EONUM_DPID_Msk (0x1UL << USB_OTG_DIEPCTL_EONUM_DPID_Pos) /*!< 0x00010000 */ -#define USB_OTG_DIEPCTL_EONUM_DPID USB_OTG_DIEPCTL_EONUM_DPID_Msk /*!< Even/odd frame */ -#define USB_OTG_DIEPCTL_NAKSTS_Pos (17U) -#define USB_OTG_DIEPCTL_NAKSTS_Msk (0x1UL << USB_OTG_DIEPCTL_NAKSTS_Pos) /*!< 0x00020000 */ -#define USB_OTG_DIEPCTL_NAKSTS USB_OTG_DIEPCTL_NAKSTS_Msk /*!< NAK status */ +/******************** Bit definition for CID register ********************/ +#define CID_PRODUCT_ID_Pos (0U) +#define CID_PRODUCT_ID_Msk (0xFFFFFFFFUL << CID_PRODUCT_ID_Pos) /*!< 0xFFFFFFFF */ +#define CID_PRODUCT_ID CID_PRODUCT_ID_Msk /*!< Product ID field */ -#define USB_OTG_DIEPCTL_EPTYP_Pos (18U) -#define USB_OTG_DIEPCTL_EPTYP_Msk (0x3UL << USB_OTG_DIEPCTL_EPTYP_Pos) /*!< 0x000C0000 */ -#define USB_OTG_DIEPCTL_EPTYP USB_OTG_DIEPCTL_EPTYP_Msk /*!< Endpoint type */ -#define USB_OTG_DIEPCTL_EPTYP_0 (0x1UL << USB_OTG_DIEPCTL_EPTYP_Pos) /*!< 0x00040000 */ -#define USB_OTG_DIEPCTL_EPTYP_1 (0x2UL << USB_OTG_DIEPCTL_EPTYP_Pos) /*!< 0x00080000 */ -#define USB_OTG_DIEPCTL_STALL_Pos (21U) -#define USB_OTG_DIEPCTL_STALL_Msk (0x1UL << USB_OTG_DIEPCTL_STALL_Pos) /*!< 0x00200000 */ -#define USB_OTG_DIEPCTL_STALL USB_OTG_DIEPCTL_STALL_Msk /*!< STALL handshake */ +/******************** Bit definition for GLPMCFG register ********************/ +#define GLPMCFG_LPMEN_Pos (0U) +#define GLPMCFG_LPMEN_Msk (0x1UL << GLPMCFG_LPMEN_Pos) /*!< 0x00000001 */ +#define GLPMCFG_LPMEN GLPMCFG_LPMEN_Msk /*!< LPM support enable */ +#define GLPMCFG_LPMACK_Pos (1U) +#define GLPMCFG_LPMACK_Msk (0x1UL << GLPMCFG_LPMACK_Pos) /*!< 0x00000002 */ +#define GLPMCFG_LPMACK GLPMCFG_LPMACK_Msk /*!< LPM Token acknowledge enable */ +#define GLPMCFG_BESL_Pos (2U) +#define GLPMCFG_BESL_Msk (0xFUL << GLPMCFG_BESL_Pos) /*!< 0x0000003C */ +#define GLPMCFG_BESL GLPMCFG_BESL_Msk /*!< BESL value received with last ACKed LPM Token */ +#define GLPMCFG_REMWAKE_Pos (6U) +#define GLPMCFG_REMWAKE_Msk (0x1UL << GLPMCFG_REMWAKE_Pos) /*!< 0x00000040 */ +#define GLPMCFG_REMWAKE GLPMCFG_REMWAKE_Msk /*!< bRemoteWake value received with last ACKed LPM Token */ +#define GLPMCFG_L1SSEN_Pos (7U) +#define GLPMCFG_L1SSEN_Msk (0x1UL << GLPMCFG_L1SSEN_Pos) /*!< 0x00000080 */ +#define GLPMCFG_L1SSEN GLPMCFG_L1SSEN_Msk /*!< L1 shallow sleep enable */ +#define GLPMCFG_BESLTHRS_Pos (8U) +#define GLPMCFG_BESLTHRS_Msk (0xFUL << GLPMCFG_BESLTHRS_Pos) /*!< 0x00000F00 */ +#define GLPMCFG_BESLTHRS GLPMCFG_BESLTHRS_Msk /*!< BESL threshold */ +#define GLPMCFG_L1DSEN_Pos (12U) +#define GLPMCFG_L1DSEN_Msk (0x1UL << GLPMCFG_L1DSEN_Pos) /*!< 0x00001000 */ +#define GLPMCFG_L1DSEN GLPMCFG_L1DSEN_Msk /*!< L1 deep sleep enable */ +#define GLPMCFG_LPMRSP_Pos (13U) +#define GLPMCFG_LPMRSP_Msk (0x3UL << GLPMCFG_LPMRSP_Pos) /*!< 0x00006000 */ +#define GLPMCFG_LPMRSP GLPMCFG_LPMRSP_Msk /*!< LPM response */ +#define GLPMCFG_SLPSTS_Pos (15U) +#define GLPMCFG_SLPSTS_Msk (0x1UL << GLPMCFG_SLPSTS_Pos) /*!< 0x00008000 */ +#define GLPMCFG_SLPSTS GLPMCFG_SLPSTS_Msk /*!< Port sleep status */ +#define GLPMCFG_L1RSMOK_Pos (16U) +#define GLPMCFG_L1RSMOK_Msk (0x1UL << GLPMCFG_L1RSMOK_Pos) /*!< 0x00010000 */ +#define GLPMCFG_L1RSMOK GLPMCFG_L1RSMOK_Msk /*!< Sleep State Resume OK */ +#define GLPMCFG_LPMCHIDX_Pos (17U) +#define GLPMCFG_LPMCHIDX_Msk (0xFUL << GLPMCFG_LPMCHIDX_Pos) /*!< 0x001E0000 */ +#define GLPMCFG_LPMCHIDX GLPMCFG_LPMCHIDX_Msk /*!< LPM Channel Index */ +#define GLPMCFG_LPMRCNT_Pos (21U) +#define GLPMCFG_LPMRCNT_Msk (0x7UL << GLPMCFG_LPMRCNT_Pos) /*!< 0x00E00000 */ +#define GLPMCFG_LPMRCNT GLPMCFG_LPMRCNT_Msk /*!< LPM retry count */ +#define GLPMCFG_SNDLPM_Pos (24U) +#define GLPMCFG_SNDLPM_Msk (0x1UL << GLPMCFG_SNDLPM_Pos) /*!< 0x01000000 */ +#define GLPMCFG_SNDLPM GLPMCFG_SNDLPM_Msk /*!< Send LPM transaction */ +#define GLPMCFG_LPMRCNTSTS_Pos (25U) +#define GLPMCFG_LPMRCNTSTS_Msk (0x7UL << GLPMCFG_LPMRCNTSTS_Pos) /*!< 0x0E000000 */ +#define GLPMCFG_LPMRCNTSTS GLPMCFG_LPMRCNTSTS_Msk /*!< LPM retry count status */ +#define GLPMCFG_ENBESL_Pos (28U) +#define GLPMCFG_ENBESL_Msk (0x1UL << GLPMCFG_ENBESL_Pos) /*!< 0x10000000 */ +#define GLPMCFG_ENBESL GLPMCFG_ENBESL_Msk /*!< Enable best effort service latency */ -#define USB_OTG_DIEPCTL_TXFNUM_Pos (22U) -#define USB_OTG_DIEPCTL_TXFNUM_Msk (0xFUL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x03C00000 */ -#define USB_OTG_DIEPCTL_TXFNUM USB_OTG_DIEPCTL_TXFNUM_Msk /*!< TxFIFO number */ -#define USB_OTG_DIEPCTL_TXFNUM_0 (0x1UL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x00400000 */ -#define USB_OTG_DIEPCTL_TXFNUM_1 (0x2UL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x00800000 */ -#define USB_OTG_DIEPCTL_TXFNUM_2 (0x4UL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x01000000 */ -#define USB_OTG_DIEPCTL_TXFNUM_3 (0x8UL << USB_OTG_DIEPCTL_TXFNUM_Pos) /*!< 0x02000000 */ -#define USB_OTG_DIEPCTL_CNAK_Pos (26U) -#define USB_OTG_DIEPCTL_CNAK_Msk (0x1UL << USB_OTG_DIEPCTL_CNAK_Pos) /*!< 0x04000000 */ -#define USB_OTG_DIEPCTL_CNAK USB_OTG_DIEPCTL_CNAK_Msk /*!< Clear NAK */ -#define USB_OTG_DIEPCTL_SNAK_Pos (27U) -#define USB_OTG_DIEPCTL_SNAK_Msk (0x1UL << USB_OTG_DIEPCTL_SNAK_Pos) /*!< 0x08000000 */ -#define USB_OTG_DIEPCTL_SNAK USB_OTG_DIEPCTL_SNAK_Msk /*!< Set NAK */ -#define USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Pos (28U) -#define USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Msk (0x1UL << USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Pos) /*!< 0x10000000 */ -#define USB_OTG_DIEPCTL_SD0PID_SEVNFRM USB_OTG_DIEPCTL_SD0PID_SEVNFRM_Msk /*!< Set DATA0 PID */ -#define USB_OTG_DIEPCTL_SODDFRM_Pos (29U) -#define USB_OTG_DIEPCTL_SODDFRM_Msk (0x1UL << USB_OTG_DIEPCTL_SODDFRM_Pos) /*!< 0x20000000 */ -#define USB_OTG_DIEPCTL_SODDFRM USB_OTG_DIEPCTL_SODDFRM_Msk /*!< Set odd frame */ -#define USB_OTG_DIEPCTL_EPDIS_Pos (30U) -#define USB_OTG_DIEPCTL_EPDIS_Msk (0x1UL << USB_OTG_DIEPCTL_EPDIS_Pos) /*!< 0x40000000 */ -#define USB_OTG_DIEPCTL_EPDIS USB_OTG_DIEPCTL_EPDIS_Msk /*!< Endpoint disable */ -#define USB_OTG_DIEPCTL_EPENA_Pos (31U) -#define USB_OTG_DIEPCTL_EPENA_Msk (0x1UL << USB_OTG_DIEPCTL_EPENA_Pos) /*!< 0x80000000 */ -#define USB_OTG_DIEPCTL_EPENA USB_OTG_DIEPCTL_EPENA_Msk /*!< Endpoint enable */ +/******************** Bit definition for DIEPEACHMSK1 register ********************/ +#define DIEPEACHMSK1_XFRCM_Pos (0U) +#define DIEPEACHMSK1_XFRCM_Msk (0x1UL << DIEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ +#define DIEPEACHMSK1_XFRCM DIEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define DIEPEACHMSK1_EPDM_Pos (1U) +#define DIEPEACHMSK1_EPDM_Msk (0x1UL << DIEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ +#define DIEPEACHMSK1_EPDM DIEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define DIEPEACHMSK1_TOM_Pos (3U) +#define DIEPEACHMSK1_TOM_Msk (0x1UL << DIEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ +#define DIEPEACHMSK1_TOM DIEPEACHMSK1_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ +#define DIEPEACHMSK1_ITTXFEMSK_Pos (4U) +#define DIEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << DIEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ +#define DIEPEACHMSK1_ITTXFEMSK DIEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define DIEPEACHMSK1_INEPNMM_Pos (5U) +#define DIEPEACHMSK1_INEPNMM_Msk (0x1UL << DIEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ +#define DIEPEACHMSK1_INEPNMM DIEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define DIEPEACHMSK1_INEPNEM_Pos (6U) +#define DIEPEACHMSK1_INEPNEM_Msk (0x1UL << DIEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ +#define DIEPEACHMSK1_INEPNEM DIEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define DIEPEACHMSK1_TXFURM_Pos (8U) +#define DIEPEACHMSK1_TXFURM_Msk (0x1UL << DIEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ +#define DIEPEACHMSK1_TXFURM DIEPEACHMSK1_TXFURM_Msk /*!< FIFO underrun mask */ +#define DIEPEACHMSK1_BIM_Pos (9U) +#define DIEPEACHMSK1_BIM_Msk (0x1UL << DIEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ +#define DIEPEACHMSK1_BIM DIEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ +#define DIEPEACHMSK1_NAKM_Pos (13U) +#define DIEPEACHMSK1_NAKM_Msk (0x1UL << DIEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ +#define DIEPEACHMSK1_NAKM DIEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ -/******************** Bit definition for USB_OTG_HCCHAR register ********************/ -#define USB_OTG_HCCHAR_MPSIZ_Pos (0U) -#define USB_OTG_HCCHAR_MPSIZ_Msk (0x7FFUL << USB_OTG_HCCHAR_MPSIZ_Pos) /*!< 0x000007FF */ -#define USB_OTG_HCCHAR_MPSIZ USB_OTG_HCCHAR_MPSIZ_Msk /*!< Maximum packet size */ +/******************** Bit definition for HPRT register ********************/ +#define HPRT_PCSTS_Pos (0U) +#define HPRT_PCSTS_Msk (0x1UL << HPRT_PCSTS_Pos) /*!< 0x00000001 */ +#define HPRT_PCSTS HPRT_PCSTS_Msk /*!< Port connect status */ +#define HPRT_PCDET_Pos (1U) +#define HPRT_PCDET_Msk (0x1UL << HPRT_PCDET_Pos) /*!< 0x00000002 */ +#define HPRT_PCDET HPRT_PCDET_Msk /*!< Port connect detected */ +#define HPRT_PENA_Pos (2U) +#define HPRT_PENA_Msk (0x1UL << HPRT_PENA_Pos) /*!< 0x00000004 */ +#define HPRT_PENA HPRT_PENA_Msk /*!< Port enable */ +#define HPRT_PENCHNG_Pos (3U) +#define HPRT_PENCHNG_Msk (0x1UL << HPRT_PENCHNG_Pos) /*!< 0x00000008 */ +#define HPRT_PENCHNG HPRT_PENCHNG_Msk /*!< Port enable/disable change */ +#define HPRT_POCA_Pos (4U) +#define HPRT_POCA_Msk (0x1UL << HPRT_POCA_Pos) /*!< 0x00000010 */ +#define HPRT_POCA HPRT_POCA_Msk /*!< Port overcurrent active */ +#define HPRT_POCCHNG_Pos (5U) +#define HPRT_POCCHNG_Msk (0x1UL << HPRT_POCCHNG_Pos) /*!< 0x00000020 */ +#define HPRT_POCCHNG HPRT_POCCHNG_Msk /*!< Port overcurrent change */ +#define HPRT_PRES_Pos (6U) +#define HPRT_PRES_Msk (0x1UL << HPRT_PRES_Pos) /*!< 0x00000040 */ +#define HPRT_PRES HPRT_PRES_Msk /*!< Port resume */ +#define HPRT_PSUSP_Pos (7U) +#define HPRT_PSUSP_Msk (0x1UL << HPRT_PSUSP_Pos) /*!< 0x00000080 */ +#define HPRT_PSUSP HPRT_PSUSP_Msk /*!< Port suspend */ +#define HPRT_PRST_Pos (8U) +#define HPRT_PRST_Msk (0x1UL << HPRT_PRST_Pos) /*!< 0x00000100 */ +#define HPRT_PRST HPRT_PRST_Msk /*!< Port reset */ -#define USB_OTG_HCCHAR_EPNUM_Pos (11U) -#define USB_OTG_HCCHAR_EPNUM_Msk (0xFUL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00007800 */ -#define USB_OTG_HCCHAR_EPNUM USB_OTG_HCCHAR_EPNUM_Msk /*!< Endpoint number */ -#define USB_OTG_HCCHAR_EPNUM_0 (0x1UL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00000800 */ -#define USB_OTG_HCCHAR_EPNUM_1 (0x2UL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00001000 */ -#define USB_OTG_HCCHAR_EPNUM_2 (0x4UL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00002000 */ -#define USB_OTG_HCCHAR_EPNUM_3 (0x8UL << USB_OTG_HCCHAR_EPNUM_Pos) /*!< 0x00004000 */ -#define USB_OTG_HCCHAR_EPDIR_Pos (15U) -#define USB_OTG_HCCHAR_EPDIR_Msk (0x1UL << USB_OTG_HCCHAR_EPDIR_Pos) /*!< 0x00008000 */ -#define USB_OTG_HCCHAR_EPDIR USB_OTG_HCCHAR_EPDIR_Msk /*!< Endpoint direction */ -#define USB_OTG_HCCHAR_LSDEV_Pos (17U) -#define USB_OTG_HCCHAR_LSDEV_Msk (0x1UL << USB_OTG_HCCHAR_LSDEV_Pos) /*!< 0x00020000 */ -#define USB_OTG_HCCHAR_LSDEV USB_OTG_HCCHAR_LSDEV_Msk /*!< Low-speed device */ +#define HPRT_PLSTS_Pos (10U) +#define HPRT_PLSTS_Msk (0x3UL << HPRT_PLSTS_Pos) /*!< 0x00000C00 */ +#define HPRT_PLSTS HPRT_PLSTS_Msk /*!< Port line status */ +#define HPRT_PLSTS_0 (0x1UL << HPRT_PLSTS_Pos) /*!< 0x00000400 */ +#define HPRT_PLSTS_1 (0x2UL << HPRT_PLSTS_Pos) /*!< 0x00000800 */ +#define HPRT_PPWR_Pos (12U) +#define HPRT_PPWR_Msk (0x1UL << HPRT_PPWR_Pos) /*!< 0x00001000 */ +#define HPRT_PPWR HPRT_PPWR_Msk /*!< Port power */ -#define USB_OTG_HCCHAR_EPTYP_Pos (18U) -#define USB_OTG_HCCHAR_EPTYP_Msk (0x3UL << USB_OTG_HCCHAR_EPTYP_Pos) /*!< 0x000C0000 */ -#define USB_OTG_HCCHAR_EPTYP USB_OTG_HCCHAR_EPTYP_Msk /*!< Endpoint type */ -#define USB_OTG_HCCHAR_EPTYP_0 (0x1UL << USB_OTG_HCCHAR_EPTYP_Pos) /*!< 0x00040000 */ -#define USB_OTG_HCCHAR_EPTYP_1 (0x2UL << USB_OTG_HCCHAR_EPTYP_Pos) /*!< 0x00080000 */ - -#define USB_OTG_HCCHAR_MC_Pos (20U) -#define USB_OTG_HCCHAR_MC_Msk (0x3UL << USB_OTG_HCCHAR_MC_Pos) /*!< 0x00300000 */ -#define USB_OTG_HCCHAR_MC USB_OTG_HCCHAR_MC_Msk /*!< Multi Count (MC) / Error Count (EC) */ -#define USB_OTG_HCCHAR_MC_0 (0x1UL << USB_OTG_HCCHAR_MC_Pos) /*!< 0x00100000 */ -#define USB_OTG_HCCHAR_MC_1 (0x2UL << USB_OTG_HCCHAR_MC_Pos) /*!< 0x00200000 */ +#define HPRT_PTCTL_Pos (13U) +#define HPRT_PTCTL_Msk (0xFUL << HPRT_PTCTL_Pos) /*!< 0x0001E000 */ +#define HPRT_PTCTL HPRT_PTCTL_Msk /*!< Port test control */ +#define HPRT_PTCTL_0 (0x1UL << HPRT_PTCTL_Pos) /*!< 0x00002000 */ +#define HPRT_PTCTL_1 (0x2UL << HPRT_PTCTL_Pos) /*!< 0x00004000 */ +#define HPRT_PTCTL_2 (0x4UL << HPRT_PTCTL_Pos) /*!< 0x00008000 */ +#define HPRT_PTCTL_3 (0x8UL << HPRT_PTCTL_Pos) /*!< 0x00010000 */ -#define USB_OTG_HCCHAR_DAD_Pos (22U) -#define USB_OTG_HCCHAR_DAD_Msk (0x7FUL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x1FC00000 */ -#define USB_OTG_HCCHAR_DAD USB_OTG_HCCHAR_DAD_Msk /*!< Device address */ -#define USB_OTG_HCCHAR_DAD_0 (0x01UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x00400000 */ -#define USB_OTG_HCCHAR_DAD_1 (0x02UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x00800000 */ -#define USB_OTG_HCCHAR_DAD_2 (0x04UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x01000000 */ -#define USB_OTG_HCCHAR_DAD_3 (0x08UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x02000000 */ -#define USB_OTG_HCCHAR_DAD_4 (0x10UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x04000000 */ -#define USB_OTG_HCCHAR_DAD_5 (0x20UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x08000000 */ -#define USB_OTG_HCCHAR_DAD_6 (0x40UL << USB_OTG_HCCHAR_DAD_Pos) /*!< 0x10000000 */ -#define USB_OTG_HCCHAR_ODDFRM_Pos (29U) -#define USB_OTG_HCCHAR_ODDFRM_Msk (0x1UL << USB_OTG_HCCHAR_ODDFRM_Pos) /*!< 0x20000000 */ -#define USB_OTG_HCCHAR_ODDFRM USB_OTG_HCCHAR_ODDFRM_Msk /*!< Odd frame */ -#define USB_OTG_HCCHAR_CHDIS_Pos (30U) -#define USB_OTG_HCCHAR_CHDIS_Msk (0x1UL << USB_OTG_HCCHAR_CHDIS_Pos) /*!< 0x40000000 */ -#define USB_OTG_HCCHAR_CHDIS USB_OTG_HCCHAR_CHDIS_Msk /*!< Channel disable */ -#define USB_OTG_HCCHAR_CHENA_Pos (31U) -#define USB_OTG_HCCHAR_CHENA_Msk (0x1UL << USB_OTG_HCCHAR_CHENA_Pos) /*!< 0x80000000 */ -#define USB_OTG_HCCHAR_CHENA USB_OTG_HCCHAR_CHENA_Msk /*!< Channel enable */ +#define HPRT_PSPD_Pos (17U) +#define HPRT_PSPD_Msk (0x3UL << HPRT_PSPD_Pos) /*!< 0x00060000 */ +#define HPRT_PSPD HPRT_PSPD_Msk /*!< Port speed */ +#define HPRT_PSPD_0 (0x1UL << HPRT_PSPD_Pos) /*!< 0x00020000 */ +#define HPRT_PSPD_1 (0x2UL << HPRT_PSPD_Pos) /*!< 0x00040000 */ -/******************** Bit definition for USB_OTG_HCSPLT register ********************/ +/******************** Bit definition for DOEPEACHMSK1 register ********************/ +#define DOEPEACHMSK1_XFRCM_Pos (0U) +#define DOEPEACHMSK1_XFRCM_Msk (0x1UL << DOEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ +#define DOEPEACHMSK1_XFRCM DOEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define DOEPEACHMSK1_EPDM_Pos (1U) +#define DOEPEACHMSK1_EPDM_Msk (0x1UL << DOEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ +#define DOEPEACHMSK1_EPDM DOEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define DOEPEACHMSK1_TOM_Pos (3U) +#define DOEPEACHMSK1_TOM_Msk (0x1UL << DOEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ +#define DOEPEACHMSK1_TOM DOEPEACHMSK1_TOM_Msk /*!< Timeout condition mask */ +#define DOEPEACHMSK1_ITTXFEMSK_Pos (4U) +#define DOEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << DOEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ +#define DOEPEACHMSK1_ITTXFEMSK DOEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define DOEPEACHMSK1_INEPNMM_Pos (5U) +#define DOEPEACHMSK1_INEPNMM_Msk (0x1UL << DOEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ +#define DOEPEACHMSK1_INEPNMM DOEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define DOEPEACHMSK1_INEPNEM_Pos (6U) +#define DOEPEACHMSK1_INEPNEM_Msk (0x1UL << DOEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ +#define DOEPEACHMSK1_INEPNEM DOEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define DOEPEACHMSK1_TXFURM_Pos (8U) +#define DOEPEACHMSK1_TXFURM_Msk (0x1UL << DOEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ +#define DOEPEACHMSK1_TXFURM DOEPEACHMSK1_TXFURM_Msk /*!< OUT packet error mask */ +#define DOEPEACHMSK1_BIM_Pos (9U) +#define DOEPEACHMSK1_BIM_Msk (0x1UL << DOEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ +#define DOEPEACHMSK1_BIM DOEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ +#define DOEPEACHMSK1_BERRM_Pos (12U) +#define DOEPEACHMSK1_BERRM_Msk (0x1UL << DOEPEACHMSK1_BERRM_Pos) /*!< 0x00001000 */ +#define DOEPEACHMSK1_BERRM DOEPEACHMSK1_BERRM_Msk /*!< Bubble error interrupt mask */ +#define DOEPEACHMSK1_NAKM_Pos (13U) +#define DOEPEACHMSK1_NAKM_Msk (0x1UL << DOEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ +#define DOEPEACHMSK1_NAKM DOEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ +#define DOEPEACHMSK1_NYETM_Pos (14U) +#define DOEPEACHMSK1_NYETM_Msk (0x1UL << DOEPEACHMSK1_NYETM_Pos) /*!< 0x00004000 */ +#define DOEPEACHMSK1_NYETM DOEPEACHMSK1_NYETM_Msk /*!< NYET interrupt mask */ -#define USB_OTG_HCSPLT_PRTADDR_Pos (0U) -#define USB_OTG_HCSPLT_PRTADDR_Msk (0x7FUL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x0000007F */ -#define USB_OTG_HCSPLT_PRTADDR USB_OTG_HCSPLT_PRTADDR_Msk /*!< Port address */ -#define USB_OTG_HCSPLT_PRTADDR_0 (0x01UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000001 */ -#define USB_OTG_HCSPLT_PRTADDR_1 (0x02UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000002 */ -#define USB_OTG_HCSPLT_PRTADDR_2 (0x04UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000004 */ -#define USB_OTG_HCSPLT_PRTADDR_3 (0x08UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000008 */ -#define USB_OTG_HCSPLT_PRTADDR_4 (0x10UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000010 */ -#define USB_OTG_HCSPLT_PRTADDR_5 (0x20UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000020 */ -#define USB_OTG_HCSPLT_PRTADDR_6 (0x40UL << USB_OTG_HCSPLT_PRTADDR_Pos) /*!< 0x00000040 */ +/******************** Bit definition for HPTXFSIZ register ********************/ +#define HPTXFSIZ_PTXSA_Pos (0U) +#define HPTXFSIZ_PTXSA_Msk (0xFFFFUL << HPTXFSIZ_PTXSA_Pos) /*!< 0x0000FFFF */ +#define HPTXFSIZ_PTXSA HPTXFSIZ_PTXSA_Msk /*!< Host periodic TxFIFO start address */ +#define HPTXFSIZ_PTXFD_Pos (16U) +#define HPTXFSIZ_PTXFD_Msk (0xFFFFUL << HPTXFSIZ_PTXFD_Pos) /*!< 0xFFFF0000 */ +#define HPTXFSIZ_PTXFD HPTXFSIZ_PTXFD_Msk /*!< Host periodic TxFIFO depth */ -#define USB_OTG_HCSPLT_HUBADDR_Pos (7U) -#define USB_OTG_HCSPLT_HUBADDR_Msk (0x7FUL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00003F80 */ -#define USB_OTG_HCSPLT_HUBADDR USB_OTG_HCSPLT_HUBADDR_Msk /*!< Hub address */ -#define USB_OTG_HCSPLT_HUBADDR_0 (0x01UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000080 */ -#define USB_OTG_HCSPLT_HUBADDR_1 (0x02UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000100 */ -#define USB_OTG_HCSPLT_HUBADDR_2 (0x04UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000200 */ -#define USB_OTG_HCSPLT_HUBADDR_3 (0x08UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000400 */ -#define USB_OTG_HCSPLT_HUBADDR_4 (0x10UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00000800 */ -#define USB_OTG_HCSPLT_HUBADDR_5 (0x20UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00001000 */ -#define USB_OTG_HCSPLT_HUBADDR_6 (0x40UL << USB_OTG_HCSPLT_HUBADDR_Pos) /*!< 0x00002000 */ +/******************** Bit definition for DIEPCTL register ********************/ +#define DIEPCTL_MPSIZ_Pos (0U) +#define DIEPCTL_MPSIZ_Msk (0x7FFUL << DIEPCTL_MPSIZ_Pos) /*!< 0x000007FF */ +#define DIEPCTL_MPSIZ DIEPCTL_MPSIZ_Msk /*!< Maximum packet size */ +#define DIEPCTL_USBAEP_Pos (15U) +#define DIEPCTL_USBAEP_Msk (0x1UL << DIEPCTL_USBAEP_Pos) /*!< 0x00008000 */ +#define DIEPCTL_USBAEP DIEPCTL_USBAEP_Msk /*!< USB active endpoint */ +#define DIEPCTL_EONUM_DPID_Pos (16U) +#define DIEPCTL_EONUM_DPID_Msk (0x1UL << DIEPCTL_EONUM_DPID_Pos) /*!< 0x00010000 */ +#define DIEPCTL_EONUM_DPID DIEPCTL_EONUM_DPID_Msk /*!< Even/odd frame */ +#define DIEPCTL_NAKSTS_Pos (17U) +#define DIEPCTL_NAKSTS_Msk (0x1UL << DIEPCTL_NAKSTS_Pos) /*!< 0x00020000 */ +#define DIEPCTL_NAKSTS DIEPCTL_NAKSTS_Msk /*!< NAK status */ -#define USB_OTG_HCSPLT_XACTPOS_Pos (14U) -#define USB_OTG_HCSPLT_XACTPOS_Msk (0x3UL << USB_OTG_HCSPLT_XACTPOS_Pos) /*!< 0x0000C000 */ -#define USB_OTG_HCSPLT_XACTPOS USB_OTG_HCSPLT_XACTPOS_Msk /*!< XACTPOS */ -#define USB_OTG_HCSPLT_XACTPOS_0 (0x1UL << USB_OTG_HCSPLT_XACTPOS_Pos) /*!< 0x00004000 */ -#define USB_OTG_HCSPLT_XACTPOS_1 (0x2UL << USB_OTG_HCSPLT_XACTPOS_Pos) /*!< 0x00008000 */ -#define USB_OTG_HCSPLT_COMPLSPLT_Pos (16U) -#define USB_OTG_HCSPLT_COMPLSPLT_Msk (0x1UL << USB_OTG_HCSPLT_COMPLSPLT_Pos) /*!< 0x00010000 */ -#define USB_OTG_HCSPLT_COMPLSPLT USB_OTG_HCSPLT_COMPLSPLT_Msk /*!< Do complete split */ -#define USB_OTG_HCSPLT_SPLITEN_Pos (31U) -#define USB_OTG_HCSPLT_SPLITEN_Msk (0x1UL << USB_OTG_HCSPLT_SPLITEN_Pos) /*!< 0x80000000 */ -#define USB_OTG_HCSPLT_SPLITEN USB_OTG_HCSPLT_SPLITEN_Msk /*!< Split enable */ +#define DIEPCTL_EPTYP_Pos (18U) +#define DIEPCTL_EPTYP_Msk (0x3UL << DIEPCTL_EPTYP_Pos) /*!< 0x000C0000 */ +#define DIEPCTL_EPTYP DIEPCTL_EPTYP_Msk /*!< Endpoint type */ +#define DIEPCTL_EPTYP_0 (0x1UL << DIEPCTL_EPTYP_Pos) /*!< 0x00040000 */ +#define DIEPCTL_EPTYP_1 (0x2UL << DIEPCTL_EPTYP_Pos) /*!< 0x00080000 */ +#define DIEPCTL_STALL_Pos (21U) +#define DIEPCTL_STALL_Msk (0x1UL << DIEPCTL_STALL_Pos) /*!< 0x00200000 */ +#define DIEPCTL_STALL DIEPCTL_STALL_Msk /*!< STALL handshake */ -/******************** Bit definition for USB_OTG_HCINT register ********************/ -#define USB_OTG_HCINT_XFRC_Pos (0U) -#define USB_OTG_HCINT_XFRC_Msk (0x1UL << USB_OTG_HCINT_XFRC_Pos) /*!< 0x00000001 */ -#define USB_OTG_HCINT_XFRC USB_OTG_HCINT_XFRC_Msk /*!< Transfer completed */ -#define USB_OTG_HCINT_CHH_Pos (1U) -#define USB_OTG_HCINT_CHH_Msk (0x1UL << USB_OTG_HCINT_CHH_Pos) /*!< 0x00000002 */ -#define USB_OTG_HCINT_CHH USB_OTG_HCINT_CHH_Msk /*!< Channel halted */ -#define USB_OTG_HCINT_AHBERR_Pos (2U) -#define USB_OTG_HCINT_AHBERR_Msk (0x1UL << USB_OTG_HCINT_AHBERR_Pos) /*!< 0x00000004 */ -#define USB_OTG_HCINT_AHBERR USB_OTG_HCINT_AHBERR_Msk /*!< AHB error */ -#define USB_OTG_HCINT_STALL_Pos (3U) -#define USB_OTG_HCINT_STALL_Msk (0x1UL << USB_OTG_HCINT_STALL_Pos) /*!< 0x00000008 */ -#define USB_OTG_HCINT_STALL USB_OTG_HCINT_STALL_Msk /*!< STALL response received interrupt */ -#define USB_OTG_HCINT_NAK_Pos (4U) -#define USB_OTG_HCINT_NAK_Msk (0x1UL << USB_OTG_HCINT_NAK_Pos) /*!< 0x00000010 */ -#define USB_OTG_HCINT_NAK USB_OTG_HCINT_NAK_Msk /*!< NAK response received interrupt */ -#define USB_OTG_HCINT_ACK_Pos (5U) -#define USB_OTG_HCINT_ACK_Msk (0x1UL << USB_OTG_HCINT_ACK_Pos) /*!< 0x00000020 */ -#define USB_OTG_HCINT_ACK USB_OTG_HCINT_ACK_Msk /*!< ACK response received/transmitted interrupt */ -#define USB_OTG_HCINT_NYET_Pos (6U) -#define USB_OTG_HCINT_NYET_Msk (0x1UL << USB_OTG_HCINT_NYET_Pos) /*!< 0x00000040 */ -#define USB_OTG_HCINT_NYET USB_OTG_HCINT_NYET_Msk /*!< Response received interrupt */ -#define USB_OTG_HCINT_TXERR_Pos (7U) -#define USB_OTG_HCINT_TXERR_Msk (0x1UL << USB_OTG_HCINT_TXERR_Pos) /*!< 0x00000080 */ -#define USB_OTG_HCINT_TXERR USB_OTG_HCINT_TXERR_Msk /*!< Transaction error */ -#define USB_OTG_HCINT_BBERR_Pos (8U) -#define USB_OTG_HCINT_BBERR_Msk (0x1UL << USB_OTG_HCINT_BBERR_Pos) /*!< 0x00000100 */ -#define USB_OTG_HCINT_BBERR USB_OTG_HCINT_BBERR_Msk /*!< Babble error */ -#define USB_OTG_HCINT_FRMOR_Pos (9U) -#define USB_OTG_HCINT_FRMOR_Msk (0x1UL << USB_OTG_HCINT_FRMOR_Pos) /*!< 0x00000200 */ -#define USB_OTG_HCINT_FRMOR USB_OTG_HCINT_FRMOR_Msk /*!< Frame overrun */ -#define USB_OTG_HCINT_DTERR_Pos (10U) -#define USB_OTG_HCINT_DTERR_Msk (0x1UL << USB_OTG_HCINT_DTERR_Pos) /*!< 0x00000400 */ -#define USB_OTG_HCINT_DTERR USB_OTG_HCINT_DTERR_Msk /*!< Data toggle error */ +#define DIEPCTL_TXFNUM_Pos (22U) +#define DIEPCTL_TXFNUM_Msk (0xFUL << DIEPCTL_TXFNUM_Pos) /*!< 0x03C00000 */ +#define DIEPCTL_TXFNUM DIEPCTL_TXFNUM_Msk /*!< TxFIFO number */ +#define DIEPCTL_TXFNUM_0 (0x1UL << DIEPCTL_TXFNUM_Pos) /*!< 0x00400000 */ +#define DIEPCTL_TXFNUM_1 (0x2UL << DIEPCTL_TXFNUM_Pos) /*!< 0x00800000 */ +#define DIEPCTL_TXFNUM_2 (0x4UL << DIEPCTL_TXFNUM_Pos) /*!< 0x01000000 */ +#define DIEPCTL_TXFNUM_3 (0x8UL << DIEPCTL_TXFNUM_Pos) /*!< 0x02000000 */ +#define DIEPCTL_CNAK_Pos (26U) +#define DIEPCTL_CNAK_Msk (0x1UL << DIEPCTL_CNAK_Pos) /*!< 0x04000000 */ +#define DIEPCTL_CNAK DIEPCTL_CNAK_Msk /*!< Clear NAK */ +#define DIEPCTL_SNAK_Pos (27U) +#define DIEPCTL_SNAK_Msk (0x1UL << DIEPCTL_SNAK_Pos) /*!< 0x08000000 */ +#define DIEPCTL_SNAK DIEPCTL_SNAK_Msk /*!< Set NAK */ +#define DIEPCTL_SD0PID_SEVNFRM_Pos (28U) +#define DIEPCTL_SD0PID_SEVNFRM_Msk (0x1UL << DIEPCTL_SD0PID_SEVNFRM_Pos) /*!< 0x10000000 */ +#define DIEPCTL_SD0PID_SEVNFRM DIEPCTL_SD0PID_SEVNFRM_Msk /*!< Set DATA0 PID */ +#define DIEPCTL_SODDFRM_Pos (29U) +#define DIEPCTL_SODDFRM_Msk (0x1UL << DIEPCTL_SODDFRM_Pos) /*!< 0x20000000 */ +#define DIEPCTL_SODDFRM DIEPCTL_SODDFRM_Msk /*!< Set odd frame */ +#define DIEPCTL_EPDIS_Pos (30U) +#define DIEPCTL_EPDIS_Msk (0x1UL << DIEPCTL_EPDIS_Pos) /*!< 0x40000000 */ +#define DIEPCTL_EPDIS DIEPCTL_EPDIS_Msk /*!< Endpoint disable */ +#define DIEPCTL_EPENA_Pos (31U) +#define DIEPCTL_EPENA_Msk (0x1UL << DIEPCTL_EPENA_Pos) /*!< 0x80000000 */ +#define DIEPCTL_EPENA DIEPCTL_EPENA_Msk /*!< Endpoint enable */ -/******************** Bit definition for USB_OTG_DIEPINT register ********************/ -#define USB_OTG_DIEPINT_XFRC_Pos (0U) -#define USB_OTG_DIEPINT_XFRC_Msk (0x1UL << USB_OTG_DIEPINT_XFRC_Pos) /*!< 0x00000001 */ -#define USB_OTG_DIEPINT_XFRC USB_OTG_DIEPINT_XFRC_Msk /*!< Transfer completed interrupt */ -#define USB_OTG_DIEPINT_EPDISD_Pos (1U) -#define USB_OTG_DIEPINT_EPDISD_Msk (0x1UL << USB_OTG_DIEPINT_EPDISD_Pos) /*!< 0x00000002 */ -#define USB_OTG_DIEPINT_EPDISD USB_OTG_DIEPINT_EPDISD_Msk /*!< Endpoint disabled interrupt */ -#define USB_OTG_DIEPINT_AHBERR_Pos (2U) -#define USB_OTG_DIEPINT_AHBERR_Msk (0x1UL << USB_OTG_DIEPINT_AHBERR_Pos) /*!< 0x00000004 */ -#define USB_OTG_DIEPINT_AHBERR USB_OTG_DIEPINT_AHBERR_Msk /*!< AHB Error (AHBErr) during an IN transaction */ -#define USB_OTG_DIEPINT_TOC_Pos (3U) -#define USB_OTG_DIEPINT_TOC_Msk (0x1UL << USB_OTG_DIEPINT_TOC_Pos) /*!< 0x00000008 */ -#define USB_OTG_DIEPINT_TOC USB_OTG_DIEPINT_TOC_Msk /*!< Timeout condition */ -#define USB_OTG_DIEPINT_ITTXFE_Pos (4U) -#define USB_OTG_DIEPINT_ITTXFE_Msk (0x1UL << USB_OTG_DIEPINT_ITTXFE_Pos) /*!< 0x00000010 */ -#define USB_OTG_DIEPINT_ITTXFE USB_OTG_DIEPINT_ITTXFE_Msk /*!< IN token received when TxFIFO is empty */ -#define USB_OTG_DIEPINT_INEPNM_Pos (5U) -#define USB_OTG_DIEPINT_INEPNM_Msk (0x1UL << USB_OTG_DIEPINT_INEPNM_Pos) /*!< 0x00000004 */ -#define USB_OTG_DIEPINT_INEPNM USB_OTG_DIEPINT_INEPNM_Msk /*!< IN token received with EP mismatch */ -#define USB_OTG_DIEPINT_INEPNE_Pos (6U) -#define USB_OTG_DIEPINT_INEPNE_Msk (0x1UL << USB_OTG_DIEPINT_INEPNE_Pos) /*!< 0x00000040 */ -#define USB_OTG_DIEPINT_INEPNE USB_OTG_DIEPINT_INEPNE_Msk /*!< IN endpoint NAK effective */ -#define USB_OTG_DIEPINT_TXFE_Pos (7U) -#define USB_OTG_DIEPINT_TXFE_Msk (0x1UL << USB_OTG_DIEPINT_TXFE_Pos) /*!< 0x00000080 */ -#define USB_OTG_DIEPINT_TXFE USB_OTG_DIEPINT_TXFE_Msk /*!< Transmit FIFO empty */ -#define USB_OTG_DIEPINT_TXFIFOUDRN_Pos (8U) -#define USB_OTG_DIEPINT_TXFIFOUDRN_Msk (0x1UL << USB_OTG_DIEPINT_TXFIFOUDRN_Pos) /*!< 0x00000100 */ -#define USB_OTG_DIEPINT_TXFIFOUDRN USB_OTG_DIEPINT_TXFIFOUDRN_Msk /*!< Transmit Fifo Underrun */ -#define USB_OTG_DIEPINT_BNA_Pos (9U) -#define USB_OTG_DIEPINT_BNA_Msk (0x1UL << USB_OTG_DIEPINT_BNA_Pos) /*!< 0x00000200 */ -#define USB_OTG_DIEPINT_BNA USB_OTG_DIEPINT_BNA_Msk /*!< Buffer not available interrupt */ -#define USB_OTG_DIEPINT_PKTDRPSTS_Pos (11U) -#define USB_OTG_DIEPINT_PKTDRPSTS_Msk (0x1UL << USB_OTG_DIEPINT_PKTDRPSTS_Pos) /*!< 0x00000800 */ -#define USB_OTG_DIEPINT_PKTDRPSTS USB_OTG_DIEPINT_PKTDRPSTS_Msk /*!< Packet dropped status */ -#define USB_OTG_DIEPINT_BERR_Pos (12U) -#define USB_OTG_DIEPINT_BERR_Msk (0x1UL << USB_OTG_DIEPINT_BERR_Pos) /*!< 0x00001000 */ -#define USB_OTG_DIEPINT_BERR USB_OTG_DIEPINT_BERR_Msk /*!< Babble error interrupt */ -#define USB_OTG_DIEPINT_NAK_Pos (13U) -#define USB_OTG_DIEPINT_NAK_Msk (0x1UL << USB_OTG_DIEPINT_NAK_Pos) /*!< 0x00002000 */ -#define USB_OTG_DIEPINT_NAK USB_OTG_DIEPINT_NAK_Msk /*!< NAK interrupt */ +/******************** Bit definition for HCCHAR register ********************/ +#define HCCHAR_MPSIZ_Pos (0U) +#define HCCHAR_MPSIZ_Msk (0x7FFUL << HCCHAR_MPSIZ_Pos) /*!< 0x000007FF */ +#define HCCHAR_MPSIZ HCCHAR_MPSIZ_Msk /*!< Maximum packet size */ -/******************** Bit definition for USB_OTG_HCINTMSK register ********************/ -#define USB_OTG_HCINTMSK_XFRCM_Pos (0U) -#define USB_OTG_HCINTMSK_XFRCM_Msk (0x1UL << USB_OTG_HCINTMSK_XFRCM_Pos) /*!< 0x00000001 */ -#define USB_OTG_HCINTMSK_XFRCM USB_OTG_HCINTMSK_XFRCM_Msk /*!< Transfer completed mask */ -#define USB_OTG_HCINTMSK_CHHM_Pos (1U) -#define USB_OTG_HCINTMSK_CHHM_Msk (0x1UL << USB_OTG_HCINTMSK_CHHM_Pos) /*!< 0x00000002 */ -#define USB_OTG_HCINTMSK_CHHM USB_OTG_HCINTMSK_CHHM_Msk /*!< Channel halted mask */ -#define USB_OTG_HCINTMSK_AHBERR_Pos (2U) -#define USB_OTG_HCINTMSK_AHBERR_Msk (0x1UL << USB_OTG_HCINTMSK_AHBERR_Pos) /*!< 0x00000004 */ -#define USB_OTG_HCINTMSK_AHBERR USB_OTG_HCINTMSK_AHBERR_Msk /*!< AHB error */ -#define USB_OTG_HCINTMSK_STALLM_Pos (3U) -#define USB_OTG_HCINTMSK_STALLM_Msk (0x1UL << USB_OTG_HCINTMSK_STALLM_Pos) /*!< 0x00000008 */ -#define USB_OTG_HCINTMSK_STALLM USB_OTG_HCINTMSK_STALLM_Msk /*!< STALL response received interrupt mask */ -#define USB_OTG_HCINTMSK_NAKM_Pos (4U) -#define USB_OTG_HCINTMSK_NAKM_Msk (0x1UL << USB_OTG_HCINTMSK_NAKM_Pos) /*!< 0x00000010 */ -#define USB_OTG_HCINTMSK_NAKM USB_OTG_HCINTMSK_NAKM_Msk /*!< NAK response received interrupt mask */ -#define USB_OTG_HCINTMSK_ACKM_Pos (5U) -#define USB_OTG_HCINTMSK_ACKM_Msk (0x1UL << USB_OTG_HCINTMSK_ACKM_Pos) /*!< 0x00000020 */ -#define USB_OTG_HCINTMSK_ACKM USB_OTG_HCINTMSK_ACKM_Msk /*!< ACK response received/transmitted interrupt mask */ -#define USB_OTG_HCINTMSK_NYET_Pos (6U) -#define USB_OTG_HCINTMSK_NYET_Msk (0x1UL << USB_OTG_HCINTMSK_NYET_Pos) /*!< 0x00000040 */ -#define USB_OTG_HCINTMSK_NYET USB_OTG_HCINTMSK_NYET_Msk /*!< response received interrupt mask */ -#define USB_OTG_HCINTMSK_TXERRM_Pos (7U) -#define USB_OTG_HCINTMSK_TXERRM_Msk (0x1UL << USB_OTG_HCINTMSK_TXERRM_Pos) /*!< 0x00000080 */ -#define USB_OTG_HCINTMSK_TXERRM USB_OTG_HCINTMSK_TXERRM_Msk /*!< Transaction error mask */ -#define USB_OTG_HCINTMSK_BBERRM_Pos (8U) -#define USB_OTG_HCINTMSK_BBERRM_Msk (0x1UL << USB_OTG_HCINTMSK_BBERRM_Pos) /*!< 0x00000100 */ -#define USB_OTG_HCINTMSK_BBERRM USB_OTG_HCINTMSK_BBERRM_Msk /*!< Babble error mask */ -#define USB_OTG_HCINTMSK_FRMORM_Pos (9U) -#define USB_OTG_HCINTMSK_FRMORM_Msk (0x1UL << USB_OTG_HCINTMSK_FRMORM_Pos) /*!< 0x00000200 */ -#define USB_OTG_HCINTMSK_FRMORM USB_OTG_HCINTMSK_FRMORM_Msk /*!< Frame overrun mask */ -#define USB_OTG_HCINTMSK_DTERRM_Pos (10U) -#define USB_OTG_HCINTMSK_DTERRM_Msk (0x1UL << USB_OTG_HCINTMSK_DTERRM_Pos) /*!< 0x00000400 */ -#define USB_OTG_HCINTMSK_DTERRM USB_OTG_HCINTMSK_DTERRM_Msk /*!< Data toggle error mask */ +#define HCCHAR_EPNUM_Pos (11U) +#define HCCHAR_EPNUM_Msk (0xFUL << HCCHAR_EPNUM_Pos) /*!< 0x00007800 */ +#define HCCHAR_EPNUM HCCHAR_EPNUM_Msk /*!< Endpoint number */ +#define HCCHAR_EPNUM_0 (0x1UL << HCCHAR_EPNUM_Pos) /*!< 0x00000800 */ +#define HCCHAR_EPNUM_1 (0x2UL << HCCHAR_EPNUM_Pos) /*!< 0x00001000 */ +#define HCCHAR_EPNUM_2 (0x4UL << HCCHAR_EPNUM_Pos) /*!< 0x00002000 */ +#define HCCHAR_EPNUM_3 (0x8UL << HCCHAR_EPNUM_Pos) /*!< 0x00004000 */ +#define HCCHAR_EPDIR_Pos (15U) +#define HCCHAR_EPDIR_Msk (0x1UL << HCCHAR_EPDIR_Pos) /*!< 0x00008000 */ +#define HCCHAR_EPDIR HCCHAR_EPDIR_Msk /*!< Endpoint direction */ +#define HCCHAR_LSDEV_Pos (17U) +#define HCCHAR_LSDEV_Msk (0x1UL << HCCHAR_LSDEV_Pos) /*!< 0x00020000 */ +#define HCCHAR_LSDEV HCCHAR_LSDEV_Msk /*!< Low-speed device */ -/******************** Bit definition for USB_OTG_DIEPTSIZ register ********************/ +#define HCCHAR_EPTYP_Pos (18U) +#define HCCHAR_EPTYP_Msk (0x3UL << HCCHAR_EPTYP_Pos) /*!< 0x000C0000 */ +#define HCCHAR_EPTYP HCCHAR_EPTYP_Msk /*!< Endpoint type */ +#define HCCHAR_EPTYP_0 (0x1UL << HCCHAR_EPTYP_Pos) /*!< 0x00040000 */ +#define HCCHAR_EPTYP_1 (0x2UL << HCCHAR_EPTYP_Pos) /*!< 0x00080000 */ -#define USB_OTG_DIEPTSIZ_XFRSIZ_Pos (0U) -#define USB_OTG_DIEPTSIZ_XFRSIZ_Msk (0x7FFFFUL << USB_OTG_DIEPTSIZ_XFRSIZ_Pos) /*!< 0x0007FFFF */ -#define USB_OTG_DIEPTSIZ_XFRSIZ USB_OTG_DIEPTSIZ_XFRSIZ_Msk /*!< Transfer size */ -#define USB_OTG_DIEPTSIZ_PKTCNT_Pos (19U) -#define USB_OTG_DIEPTSIZ_PKTCNT_Msk (0x3FFUL << USB_OTG_DIEPTSIZ_PKTCNT_Pos) /*!< 0x1FF80000 */ -#define USB_OTG_DIEPTSIZ_PKTCNT USB_OTG_DIEPTSIZ_PKTCNT_Msk /*!< Packet count */ -#define USB_OTG_DIEPTSIZ_MULCNT_Pos (29U) -#define USB_OTG_DIEPTSIZ_MULCNT_Msk (0x3UL << USB_OTG_DIEPTSIZ_MULCNT_Pos) /*!< 0x60000000 */ -#define USB_OTG_DIEPTSIZ_MULCNT USB_OTG_DIEPTSIZ_MULCNT_Msk /*!< Packet count */ -/******************** Bit definition for USB_OTG_HCTSIZ register ********************/ -#define USB_OTG_HCTSIZ_XFRSIZ_Pos (0U) -#define USB_OTG_HCTSIZ_XFRSIZ_Msk (0x7FFFFUL << USB_OTG_HCTSIZ_XFRSIZ_Pos) /*!< 0x0007FFFF */ -#define USB_OTG_HCTSIZ_XFRSIZ USB_OTG_HCTSIZ_XFRSIZ_Msk /*!< Transfer size */ -#define USB_OTG_HCTSIZ_PKTCNT_Pos (19U) -#define USB_OTG_HCTSIZ_PKTCNT_Msk (0x3FFUL << USB_OTG_HCTSIZ_PKTCNT_Pos) /*!< 0x1FF80000 */ -#define USB_OTG_HCTSIZ_PKTCNT USB_OTG_HCTSIZ_PKTCNT_Msk /*!< Packet count */ -#define USB_OTG_HCTSIZ_DOPING_Pos (31U) -#define USB_OTG_HCTSIZ_DOPING_Msk (0x1UL << USB_OTG_HCTSIZ_DOPING_Pos) /*!< 0x80000000 */ -#define USB_OTG_HCTSIZ_DOPING USB_OTG_HCTSIZ_DOPING_Msk /*!< Do PING */ -#define USB_OTG_HCTSIZ_DPID_Pos (29U) -#define USB_OTG_HCTSIZ_DPID_Msk (0x3UL << USB_OTG_HCTSIZ_DPID_Pos) /*!< 0x60000000 */ -#define USB_OTG_HCTSIZ_DPID USB_OTG_HCTSIZ_DPID_Msk /*!< Data PID */ -#define USB_OTG_HCTSIZ_DPID_0 (0x1UL << USB_OTG_HCTSIZ_DPID_Pos) /*!< 0x20000000 */ -#define USB_OTG_HCTSIZ_DPID_1 (0x2UL << USB_OTG_HCTSIZ_DPID_Pos) /*!< 0x40000000 */ +#define HCCHAR_MC_Pos (20U) +#define HCCHAR_MC_Msk (0x3UL << HCCHAR_MC_Pos) /*!< 0x00300000 */ +#define HCCHAR_MC HCCHAR_MC_Msk /*!< Multi Count (MC) / Error Count (EC) */ +#define HCCHAR_MC_0 (0x1UL << HCCHAR_MC_Pos) /*!< 0x00100000 */ +#define HCCHAR_MC_1 (0x2UL << HCCHAR_MC_Pos) /*!< 0x00200000 */ -/******************** Bit definition for USB_OTG_DIEPDMA register ********************/ -#define USB_OTG_DIEPDMA_DMAADDR_Pos (0U) -#define USB_OTG_DIEPDMA_DMAADDR_Msk (0xFFFFFFFFUL << USB_OTG_DIEPDMA_DMAADDR_Pos) /*!< 0xFFFFFFFF */ -#define USB_OTG_DIEPDMA_DMAADDR USB_OTG_DIEPDMA_DMAADDR_Msk /*!< DMA address */ +#define HCCHAR_DAD_Pos (22U) +#define HCCHAR_DAD_Msk (0x7FUL << HCCHAR_DAD_Pos) /*!< 0x1FC00000 */ +#define HCCHAR_DAD HCCHAR_DAD_Msk /*!< Device address */ +#define HCCHAR_DAD_0 (0x01UL << HCCHAR_DAD_Pos) /*!< 0x00400000 */ +#define HCCHAR_DAD_1 (0x02UL << HCCHAR_DAD_Pos) /*!< 0x00800000 */ +#define HCCHAR_DAD_2 (0x04UL << HCCHAR_DAD_Pos) /*!< 0x01000000 */ +#define HCCHAR_DAD_3 (0x08UL << HCCHAR_DAD_Pos) /*!< 0x02000000 */ +#define HCCHAR_DAD_4 (0x10UL << HCCHAR_DAD_Pos) /*!< 0x04000000 */ +#define HCCHAR_DAD_5 (0x20UL << HCCHAR_DAD_Pos) /*!< 0x08000000 */ +#define HCCHAR_DAD_6 (0x40UL << HCCHAR_DAD_Pos) /*!< 0x10000000 */ +#define HCCHAR_ODDFRM_Pos (29U) +#define HCCHAR_ODDFRM_Msk (0x1UL << HCCHAR_ODDFRM_Pos) /*!< 0x20000000 */ +#define HCCHAR_ODDFRM HCCHAR_ODDFRM_Msk /*!< Odd frame */ +#define HCCHAR_CHDIS_Pos (30U) +#define HCCHAR_CHDIS_Msk (0x1UL << HCCHAR_CHDIS_Pos) /*!< 0x40000000 */ +#define HCCHAR_CHDIS HCCHAR_CHDIS_Msk /*!< Channel disable */ +#define HCCHAR_CHENA_Pos (31U) +#define HCCHAR_CHENA_Msk (0x1UL << HCCHAR_CHENA_Pos) /*!< 0x80000000 */ +#define HCCHAR_CHENA HCCHAR_CHENA_Msk /*!< Channel enable */ -/******************** Bit definition for USB_OTG_HCDMA register ********************/ -#define USB_OTG_HCDMA_DMAADDR_Pos (0U) -#define USB_OTG_HCDMA_DMAADDR_Msk (0xFFFFFFFFUL << USB_OTG_HCDMA_DMAADDR_Pos) /*!< 0xFFFFFFFF */ -#define USB_OTG_HCDMA_DMAADDR USB_OTG_HCDMA_DMAADDR_Msk /*!< DMA address */ +/******************** Bit definition for HCSPLT register ********************/ -/******************** Bit definition for USB_OTG_DTXFSTS register ********************/ -#define USB_OTG_DTXFSTS_INEPTFSAV_Pos (0U) -#define USB_OTG_DTXFSTS_INEPTFSAV_Msk (0xFFFFUL << USB_OTG_DTXFSTS_INEPTFSAV_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_DTXFSTS_INEPTFSAV USB_OTG_DTXFSTS_INEPTFSAV_Msk /*!< IN endpoint TxFIFO space available */ +#define HCSPLT_PRTADDR_Pos (0U) +#define HCSPLT_PRTADDR_Msk (0x7FUL << HCSPLT_PRTADDR_Pos) /*!< 0x0000007F */ +#define HCSPLT_PRTADDR HCSPLT_PRTADDR_Msk /*!< Port address */ +#define HCSPLT_PRTADDR_0 (0x01UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000001 */ +#define HCSPLT_PRTADDR_1 (0x02UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000002 */ +#define HCSPLT_PRTADDR_2 (0x04UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000004 */ +#define HCSPLT_PRTADDR_3 (0x08UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000008 */ +#define HCSPLT_PRTADDR_4 (0x10UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000010 */ +#define HCSPLT_PRTADDR_5 (0x20UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000020 */ +#define HCSPLT_PRTADDR_6 (0x40UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000040 */ -/******************** Bit definition for USB_OTG_DIEPTXF register ********************/ -#define USB_OTG_DIEPTXF_INEPTXSA_Pos (0U) -#define USB_OTG_DIEPTXF_INEPTXSA_Msk (0xFFFFUL << USB_OTG_DIEPTXF_INEPTXSA_Pos) /*!< 0x0000FFFF */ -#define USB_OTG_DIEPTXF_INEPTXSA USB_OTG_DIEPTXF_INEPTXSA_Msk /*!< IN endpoint FIFOx transmit RAM start address */ -#define USB_OTG_DIEPTXF_INEPTXFD_Pos (16U) -#define USB_OTG_DIEPTXF_INEPTXFD_Msk (0xFFFFUL << USB_OTG_DIEPTXF_INEPTXFD_Pos) /*!< 0xFFFF0000 */ -#define USB_OTG_DIEPTXF_INEPTXFD USB_OTG_DIEPTXF_INEPTXFD_Msk /*!< IN endpoint TxFIFO depth */ +#define HCSPLT_HUBADDR_Pos (7U) +#define HCSPLT_HUBADDR_Msk (0x7FUL << HCSPLT_HUBADDR_Pos) /*!< 0x00003F80 */ +#define HCSPLT_HUBADDR HCSPLT_HUBADDR_Msk /*!< Hub address */ +#define HCSPLT_HUBADDR_0 (0x01UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000080 */ +#define HCSPLT_HUBADDR_1 (0x02UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000100 */ +#define HCSPLT_HUBADDR_2 (0x04UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000200 */ +#define HCSPLT_HUBADDR_3 (0x08UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000400 */ +#define HCSPLT_HUBADDR_4 (0x10UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000800 */ +#define HCSPLT_HUBADDR_5 (0x20UL << HCSPLT_HUBADDR_Pos) /*!< 0x00001000 */ +#define HCSPLT_HUBADDR_6 (0x40UL << HCSPLT_HUBADDR_Pos) /*!< 0x00002000 */ -/******************** Bit definition for USB_OTG_DOEPCTL register ********************/ +#define HCSPLT_XACTPOS_Pos (14U) +#define HCSPLT_XACTPOS_Msk (0x3UL << HCSPLT_XACTPOS_Pos) /*!< 0x0000C000 */ +#define HCSPLT_XACTPOS HCSPLT_XACTPOS_Msk /*!< XACTPOS */ +#define HCSPLT_XACTPOS_0 (0x1UL << HCSPLT_XACTPOS_Pos) /*!< 0x00004000 */ +#define HCSPLT_XACTPOS_1 (0x2UL << HCSPLT_XACTPOS_Pos) /*!< 0x00008000 */ +#define HCSPLT_COMPLSPLT_Pos (16U) +#define HCSPLT_COMPLSPLT_Msk (0x1UL << HCSPLT_COMPLSPLT_Pos) /*!< 0x00010000 */ +#define HCSPLT_COMPLSPLT HCSPLT_COMPLSPLT_Msk /*!< Do complete split */ +#define HCSPLT_SPLITEN_Pos (31U) +#define HCSPLT_SPLITEN_Msk (0x1UL << HCSPLT_SPLITEN_Pos) /*!< 0x80000000 */ +#define HCSPLT_SPLITEN HCSPLT_SPLITEN_Msk /*!< Split enable */ -#define USB_OTG_DOEPCTL_MPSIZ_Pos (0U) -#define USB_OTG_DOEPCTL_MPSIZ_Msk (0x7FFUL << USB_OTG_DOEPCTL_MPSIZ_Pos) /*!< 0x000007FF */ -#define USB_OTG_DOEPCTL_MPSIZ USB_OTG_DOEPCTL_MPSIZ_Msk /*!< Maximum packet size */ /*! Date: Mon, 25 Oct 2021 00:11:17 +0700 Subject: [PATCH 12/51] minor rename --- src/portable/synopsys/dwc2/dcd_dwc2.c | 124 +++++++++++++------------- 1 file changed, 62 insertions(+), 62 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 5811afa5a..0be587cb2 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -83,7 +83,7 @@ xfer_ctl_t xfer_status[EP_MAX][2]; // EP0 transfers are limited to 1 packet - larger sizes has to be split static uint16_t ep0_pending[2]; // Index determines direction as tusb_dir_t type -// TX FIFO RAM allocation so far in words - RX FIFO size is readily available from usb_otg->GRXFSIZ +// TX FIFO RAM allocation so far in words - RX FIFO size is readily available from core->GRXFSIZ static uint16_t _allocated_fifo_words_tx; // TX FIFO size in words (IN EPs) static bool _out_ep_closed; // Flag to check if RX FIFO size needs an update (reduce its size) @@ -97,7 +97,7 @@ static void update_grxfsiz(uint8_t rhport) { (void) rhport; - dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_core_t * core = GLOBAL_BASE(rhport); // Determine largest EP size for RX FIFO uint16_t max_epsize = 0; @@ -107,7 +107,7 @@ static void update_grxfsiz(uint8_t rhport) } // Update size of RX FIFO - usb_otg->GRXFSIZ = calc_rx_ff_size(max_epsize); + core->GRXFSIZ = calc_rx_ff_size(max_epsize); } // Setup the control endpoint 0. @@ -115,7 +115,7 @@ static void bus_reset(uint8_t rhport) { (void) rhport; - dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_core_t * core = GLOBAL_BASE(rhport); dwc2_device_t * dev = DEVICE_BASE(rhport); dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); dwc2_epin_t * in_ep = IN_EP_BASE(rhport); @@ -186,12 +186,12 @@ static void bus_reset(uint8_t rhport) // are enabled at least "2 x (Largest-EPsize/4) + 1" are recommended. Maybe provide a macro for application to // overwrite this. - usb_otg->GRXFSIZ = calc_rx_ff_size(TUD_OPT_HIGH_SPEED ? 512 : 64); + core->GRXFSIZ = calc_rx_ff_size(TUD_OPT_HIGH_SPEED ? 512 : 64); _allocated_fifo_words_tx = 16; // Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) - usb_otg->DIEPTXF0_HNPTXFSIZ = (16 << TX0FD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + core->DIEPTXF0_HNPTXFSIZ = (16 << TX0FD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); // Fixed control EP0 size to 64 bytes in_ep[0].DIEPCTL &= ~(0x03 << DIEPCTL_MPSIZ_Pos); @@ -199,19 +199,19 @@ static void bus_reset(uint8_t rhport) out_ep[0].DOEPTSIZ |= (3 << DOEPTSIZ_STUPCNT_Pos); - usb_otg->GINTMSK |= GINTMSK_OEPINT | GINTMSK_IEPINT; + core->GINTMSK |= GINTMSK_OEPINT | GINTMSK_IEPINT; } // Set turn-around timeout according to link speed extern uint32_t SystemCoreClock; -static void set_turnaround(dwc2_core_t * usb_otg, tusb_speed_t speed) +static void set_turnaround(dwc2_core_t * core, tusb_speed_t speed) { - usb_otg->GUSBCFG &= ~GUSBCFG_TRDT; + core->GUSBCFG &= ~GUSBCFG_TRDT; if ( speed == TUSB_SPEED_HIGH ) { // Use fixed 0x09 for Highspeed - usb_otg->GUSBCFG |= (0x09 << GUSBCFG_TRDT_Pos); + core->GUSBCFG |= (0x09 << GUSBCFG_TRDT_Pos); } else { @@ -240,7 +240,7 @@ static void set_turnaround(dwc2_core_t * usb_otg, tusb_speed_t speed) turnaround = 0xFU; // Fullspeed depends on MCU clocks, but we will use 0x06 for 32+ Mhz - usb_otg->GUSBCFG |= (turnaround << GUSBCFG_TRDT_Pos); + core->GUSBCFG |= (turnaround << GUSBCFG_TRDT_Pos); } } @@ -370,7 +370,7 @@ void dcd_init (uint8_t rhport) { // Programming model begins in the last section of the chapter on the USB // peripheral in each Reference Manual. - dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_core_t * core = GLOBAL_BASE(rhport); // No HNP/SRP (no OTG support), program timeout later. if ( rhport == 1 ) @@ -378,23 +378,23 @@ void dcd_init (uint8_t rhport) // On selected MCUs HS port1 can be used with external PHY via ULPI interface #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED // deactivate internal PHY - usb_otg->GCCFG &= ~GCCFG_PWRDWN; + core->GCCFG &= ~GCCFG_PWRDWN; // Init The UTMI Interface - usb_otg->GUSBCFG &= ~(GUSBCFG_TSDPS | GUSBCFG_ULPIFSLS | GUSBCFG_PHYSEL); + core->GUSBCFG &= ~(GUSBCFG_TSDPS | GUSBCFG_ULPIFSLS | GUSBCFG_PHYSEL); // Select default internal VBUS Indicator and Drive for ULPI - usb_otg->GUSBCFG &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI); + core->GUSBCFG &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI); #else - usb_otg->GUSBCFG |= GUSBCFG_PHYSEL; + core->GUSBCFG |= GUSBCFG_PHYSEL; #endif #if defined(USB_HS_PHYC) // Highspeed with embedded UTMI PHYC // Select UTMI Interface - usb_otg->GUSBCFG &= ~GUSBCFG_ULPI_UTMI_SEL; - usb_otg->GCCFG |= GCCFG_PHYHSEN; + core->GUSBCFG &= ~GUSBCFG_ULPI_UTMI_SEL; + core->GCCFG |= GCCFG_PHYHSEN; // Enables control of a High Speed USB PHY USB_HS_PHYCInit(); @@ -402,25 +402,25 @@ void dcd_init (uint8_t rhport) } else { // Enable internal PHY - usb_otg->GUSBCFG |= GUSBCFG_PHYSEL; + core->GUSBCFG |= GUSBCFG_PHYSEL; } // Reset core after selecting PHYst // Wait AHB IDLE, reset then wait until it is cleared - while ((usb_otg->GRSTCTL & GRSTCTL_AHBIDL) == 0U) {} - usb_otg->GRSTCTL |= GRSTCTL_CSRST; - while ((usb_otg->GRSTCTL & GRSTCTL_CSRST) == GRSTCTL_CSRST) {} + while ((core->GRSTCTL & GRSTCTL_AHBIDL) == 0U) {} + core->GRSTCTL |= GRSTCTL_CSRST; + while ((core->GRSTCTL & GRSTCTL_CSRST) == GRSTCTL_CSRST) {} // Restart PHY clock *((volatile uint32_t *)(DWC2_REG_BASE + DWC2_PCGCCTL_BASE)) = 0; // Clear all interrupts - usb_otg->GINTSTS |= usb_otg->GINTSTS; + core->GINTSTS |= core->GINTSTS; // Required as part of core initialization. // TODO: How should mode mismatch be handled? It will cause // the core to stop working/require reset. - usb_otg->GINTMSK |= GINTMSK_OTGINT | GINTMSK_MMISM; + core->GINTMSK |= GINTMSK_OTGINT | GINTMSK_MMISM; dwc2_device_t * dev = DEVICE_BASE(rhport); @@ -431,14 +431,14 @@ void dcd_init (uint8_t rhport) set_speed(rhport, TUD_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL); // Enable internal USB transceiver, unless using HS core (port 1) with external PHY. - if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) usb_otg->GCCFG |= GCCFG_PWRDWN; + if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) core->GCCFG |= GCCFG_PWRDWN; - usb_otg->GINTMSK |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | - GINTMSK_USBSUSPM | GINTMSK_WUIM | - GINTMSK_RXFLVLM | (USE_SOF ? GINTMSK_SOFM : 0); + core->GINTMSK |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | + GINTMSK_USBSUSPM | GINTMSK_WUIM | + GINTMSK_RXFLVLM | (USE_SOF ? GINTMSK_SOFM : 0); // Enable global interrupt - usb_otg->GAHBCFG |= GAHBCFG_GINT; + core->GAHBCFG |= GAHBCFG_GINT; dcd_connect(rhport); } @@ -478,15 +478,15 @@ void dcd_remote_wakeup(uint8_t rhport) { (void) rhport; - dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_core_t * core = GLOBAL_BASE(rhport); dwc2_device_t * dev = DEVICE_BASE(rhport); // set remote wakeup dev->DCTL |= DCTL_RWUSIG; // enable SOF to detect bus resume - usb_otg->GINTSTS = GINTSTS_SOF; - usb_otg->GINTMSK |= GINTMSK_SOFM; + core->GINTSTS = GINTSTS_SOF; + core->GINTMSK |= GINTMSK_SOFM; // Per specs: remote wakeup signal bit must be clear within 1-15ms remote_wakeup_delay(); @@ -517,7 +517,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) { (void) rhport; - dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_core_t * core = GLOBAL_BASE(rhport); dwc2_device_t * dev = DEVICE_BASE(rhport); dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); dwc2_epin_t * in_ep = IN_EP_BASE(rhport); @@ -539,12 +539,12 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) uint16_t const sz = calc_rx_ff_size(4*fifo_size); // If size_rx needs to be extended check if possible and if so enlarge it - if (usb_otg->GRXFSIZ < sz) + if (core->GRXFSIZ < sz) { TU_ASSERT(sz + _allocated_fifo_words_tx <= EP_FIFO_SIZE/4); // Enlarge RX FIFO - usb_otg->GRXFSIZ = sz; + core->GRXFSIZ = sz; } out_ep[epnum].DOEPCTL |= (1 << DOEPCTL_USBAEP_Pos) | @@ -578,7 +578,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // - IN EP 1 gets FIFO 1, IN EP "n" gets FIFO "n". // Check if free space is available - TU_ASSERT(_allocated_fifo_words_tx + fifo_size + usb_otg->GRXFSIZ <= EP_FIFO_SIZE/4); + TU_ASSERT(_allocated_fifo_words_tx + fifo_size + core->GRXFSIZ <= EP_FIFO_SIZE/4); _allocated_fifo_words_tx += fifo_size; @@ -586,7 +586,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // DIEPTXF starts at FIFO #1. // Both TXFD and TXSA are in unit of 32-bit words. - usb_otg->DIEPTXF[epnum - 1] = (fifo_size << DIEPTXF_INEPTXFD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + core->DIEPTXF[epnum - 1] = (fifo_size << DIEPTXF_INEPTXFD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); in_ep[epnum].DIEPCTL |= (1 << DIEPCTL_USBAEP_Pos) | (epnum << DIEPCTL_TXFNUM_Pos) | @@ -605,7 +605,7 @@ void dcd_edpt_close_all (uint8_t rhport) { (void) rhport; -// dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); +// dwc2_core_t * core = GLOBAL_BASE(rhport); dwc2_device_t * dev = DEVICE_BASE(rhport); dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); dwc2_epin_t * in_ep = IN_EP_BASE(rhport); @@ -693,7 +693,7 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) { (void) rhport; - dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_core_t * core = GLOBAL_BASE(rhport); dwc2_device_t * dev = DEVICE_BASE(rhport); dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); dwc2_epin_t * in_ep = IN_EP_BASE(rhport); @@ -717,9 +717,9 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) } // Flush the FIFO, and wait until we have confirmed it cleared. - usb_otg->GRSTCTL |= (epnum << GRSTCTL_TXFNUM_Pos); - usb_otg->GRSTCTL |= GRSTCTL_TXFFLSH; - while((usb_otg->GRSTCTL & GRSTCTL_TXFFLSH_Msk) != 0); + core->GRSTCTL |= (epnum << GRSTCTL_TXFNUM_Pos); + core->GRSTCTL |= GRSTCTL_TXFFLSH; + while((core->GRSTCTL & GRSTCTL_TXFFLSH_Msk) != 0); } else { // Only disable currently enabled non-control endpoint if ( (epnum == 0) || !(out_ep[epnum].DOEPCTL & DOEPCTL_EPENA) ){ @@ -730,7 +730,7 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) // anyway, and it can't be cleared by user code. If this while loop never // finishes, we have bigger problems than just the stack. dev->DCTL |= DCTL_SGONAK; - while((usb_otg->GINTSTS & GINTSTS_BOUTNAKEFF_Msk) == 0); + while((core->GINTSTS & GINTSTS_BOUTNAKEFF_Msk) == 0); // Ditto here- disable the endpoint. out_ep[epnum].DOEPCTL |= DOEPCTL_EPDIS | (stall ? DOEPCTL_STALL : 0); @@ -748,7 +748,7 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) */ void dcd_edpt_close (uint8_t rhport, uint8_t ep_addr) { - dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_core_t * core = GLOBAL_BASE(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const dir = tu_edpt_dir(ep_addr); @@ -760,8 +760,8 @@ void dcd_edpt_close (uint8_t rhport, uint8_t ep_addr) if (dir == TUSB_DIR_IN) { - uint16_t const fifo_size = (usb_otg->DIEPTXF[epnum - 1] & DIEPTXF_INEPTXFD_Msk) >> DIEPTXF_INEPTXFD_Pos; - uint16_t const fifo_start = (usb_otg->DIEPTXF[epnum - 1] & DIEPTXF_INEPTXSA_Msk) >> DIEPTXF_INEPTXSA_Pos; + uint16_t const fifo_size = (core->DIEPTXF[epnum - 1] & DIEPTXF_INEPTXFD_Msk) >> DIEPTXF_INEPTXFD_Pos; + uint16_t const fifo_start = (core->DIEPTXF[epnum - 1] & DIEPTXF_INEPTXSA_Msk) >> DIEPTXF_INEPTXSA_Pos; // For now only the last opened endpoint can be closed without fuss. TU_ASSERT(fifo_start == EP_FIFO_SIZE/4 - _allocated_fifo_words_tx,); _allocated_fifo_words_tx -= fifo_size; @@ -861,11 +861,11 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, u } static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { - dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_core_t * core = GLOBAL_BASE(rhport); usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); // Pop control word off FIFO - uint32_t ctl_word = usb_otg->GRXSTSP; + uint32_t ctl_word = core->GRXSTSP; uint8_t pktsts = (ctl_word & GRXSTSP_PKTSTS_Msk) >> GRXSTSP_PKTSTS_Pos; uint8_t epnum = (ctl_word & GRXSTSP_EPNUM_Msk) >> GRXSTSP_EPNUM_Pos; uint16_t bcnt = (ctl_word & GRXSTSP_BCNT_Msk) >> GRXSTSP_BCNT_Pos; @@ -1025,17 +1025,17 @@ static void handle_epin_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epin_t * void dcd_int_handler(uint8_t rhport) { - dwc2_core_t * usb_otg = GLOBAL_BASE(rhport); + dwc2_core_t * core = GLOBAL_BASE(rhport); dwc2_device_t * dev = DEVICE_BASE(rhport); dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); dwc2_epin_t * in_ep = IN_EP_BASE(rhport); - uint32_t const int_status = usb_otg->GINTSTS & usb_otg->GINTMSK; + uint32_t const int_status = core->GINTSTS & core->GINTMSK; if(int_status & GINTSTS_USBRST) { // USBRST is start of reset. - usb_otg->GINTSTS = GINTSTS_USBRST; + core->GINTSTS = GINTSTS_USBRST; bus_reset(rhport); } @@ -1043,23 +1043,23 @@ void dcd_int_handler(uint8_t rhport) { // ENUMDNE is the end of reset where speed of the link is detected - usb_otg->GINTSTS = GINTSTS_ENUMDNE; + core->GINTSTS = GINTSTS_ENUMDNE; tusb_speed_t const speed = get_speed(rhport); - set_turnaround(usb_otg, speed); + set_turnaround(core, speed); dcd_event_bus_reset(rhport, speed, true); } if(int_status & GINTSTS_USBSUSP) { - usb_otg->GINTSTS = GINTSTS_USBSUSP; + core->GINTSTS = GINTSTS_USBSUSP; dcd_event_bus_signal(rhport, DCD_EVENT_SUSPEND, true); } if(int_status & GINTSTS_WKUINT) { - usb_otg->GINTSTS = GINTSTS_WKUINT; + core->GINTSTS = GINTSTS_WKUINT; dcd_event_bus_signal(rhport, DCD_EVENT_RESUME, true); } @@ -1069,22 +1069,22 @@ void dcd_int_handler(uint8_t rhport) if(int_status & GINTSTS_OTGINT) { // OTG INT bit is read-only - uint32_t const otg_int = usb_otg->GOTGINT; + uint32_t const otg_int = core->GOTGINT; if (otg_int & GOTGINT_SEDET) { dcd_event_bus_signal(rhport, DCD_EVENT_UNPLUGGED, true); } - usb_otg->GOTGINT = otg_int; + core->GOTGINT = otg_int; } if(int_status & GINTSTS_SOF) { - usb_otg->GINTSTS = GINTSTS_SOF; + core->GINTSTS = GINTSTS_SOF; // Disable SOF interrupt since currently only used for remote wakeup detection - usb_otg->GINTMSK &= ~GINTMSK_SOFM; + core->GINTMSK &= ~GINTMSK_SOFM; dcd_event_bus_signal(rhport, DCD_EVENT_SOF, true); } @@ -1095,13 +1095,13 @@ void dcd_int_handler(uint8_t rhport) // RXFLVL bit is read-only // Mask out RXFLVL while reading data from FIFO - usb_otg->GINTMSK &= ~GINTMSK_RXFLVLM; + core->GINTMSK &= ~GINTMSK_RXFLVLM; // Loop until all available packets were handled do { handle_rxflvl_ints(rhport, out_ep); - } while(usb_otg->GINTSTS & GINTSTS_RXFLVL); + } while(core->GINTSTS & GINTSTS_RXFLVL); // Manage RX FIFO size if (_out_ep_closed) @@ -1112,7 +1112,7 @@ void dcd_int_handler(uint8_t rhport) _out_ep_closed = false; } - usb_otg->GINTMSK |= GINTMSK_RXFLVLM; + core->GINTMSK |= GINTMSK_RXFLVLM; } // OUT endpoint interrupt handling. From 4ab931a36167f579f556bd3fed4946cf78865646 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 25 Oct 2021 00:16:11 +0700 Subject: [PATCH 13/51] more clean up --- src/portable/synopsys/dwc2/dcd_dwc2.c | 102 +++++++++++++------------- 1 file changed, 49 insertions(+), 53 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 0be587cb2..aae6e7004 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -44,18 +44,14 @@ #include "device/dcd.h" -// Since TinyUSB doesn't use SOF for now, and this interrupt too often (1ms interval) -// We disable SOF for now until needed later on -#define USE_SOF 0 - //--------------------------------------------------------------------+ // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ -#define GLOBAL_BASE(_port) ((dwc2_core_t*) DWC2_REG_BASE) -#define DEVICE_BASE(_port) ((dwc2_device_t*) (DWC2_REG_BASE + DWC2_DEVICE_BASE)) -#define IN_EP_BASE(_port) ((dwc2_epin_t*) (DWC2_REG_BASE + DWC2_IN_ENDPOINT_BASE)) -#define OUT_EP_BASE(_port) ((dwc2_epout_t*) (DWC2_REG_BASE + DWC2_OUT_ENDPOINT_BASE)) +#define CORE_REG(_port) ((dwc2_core_t*) DWC2_REG_BASE) +#define DEVICE_REG(_port) ((dwc2_device_t*) (DWC2_REG_BASE + DWC2_DEVICE_BASE)) +#define EPIN_REG(_port) ((dwc2_epin_t*) (DWC2_REG_BASE + DWC2_IN_ENDPOINT_BASE)) +#define EPOUT_REG(_port) ((dwc2_epout_t*) (DWC2_REG_BASE + DWC2_OUT_ENDPOINT_BASE)) #define FIFO_BASE(_port, _x) ((volatile uint32_t*) (DWC2_REG_BASE + DWC2_FIFO_BASE + (_x) * DWC2_FIFO_SIZE)) enum @@ -97,7 +93,7 @@ static void update_grxfsiz(uint8_t rhport) { (void) rhport; - dwc2_core_t * core = GLOBAL_BASE(rhport); + dwc2_core_t * core = CORE_REG(rhport); // Determine largest EP size for RX FIFO uint16_t max_epsize = 0; @@ -115,10 +111,10 @@ static void bus_reset(uint8_t rhport) { (void) rhport; - dwc2_core_t * core = GLOBAL_BASE(rhport); - dwc2_device_t * dev = DEVICE_BASE(rhport); - dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); - dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + dwc2_core_t * core = CORE_REG(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_epout_t * out_ep = EPOUT_REG(rhport); + dwc2_epin_t * in_ep = EPIN_REG(rhport); tu_memclr(xfer_status, sizeof(xfer_status)); _out_ep_closed = false; @@ -133,8 +129,8 @@ static void bus_reset(uint8_t rhport) // 2. Un-mask interrupt bits dev->DAINTMSK = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); - dev->DOEPMSK = DOEPMSK_STUPM | DOEPMSK_XFRCM; - dev->DIEPMSK = DIEPMSK_TOM | DIEPMSK_XFRCM; + dev->DOEPMSK = DOEPMSK_STUPM | DOEPMSK_XFRCM; + dev->DIEPMSK = DIEPMSK_TOM | DIEPMSK_XFRCM; // "USB Data FIFOs" section in reference manual // Peripheral FIFO architecture @@ -247,7 +243,7 @@ static void set_turnaround(dwc2_core_t * core, tusb_speed_t speed) static tusb_speed_t get_speed(uint8_t rhport) { (void) rhport; - dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); uint32_t const enum_spd = (dev->DSTS & DSTS_ENUMSPD_Msk) >> DSTS_ENUMSPD_Pos; return (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL; } @@ -265,7 +261,7 @@ static void set_speed(uint8_t rhport, tusb_speed_t speed) bitvalue = DCD_FULL_SPEED; } - dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); // Clear and set speed bits dev->DCFG &= ~(3 << DCFG_DSPD_Pos); @@ -317,9 +313,9 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c { (void) rhport; - dwc2_device_t * dev = DEVICE_BASE(rhport); - dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); - dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_epout_t * out_ep = EPOUT_REG(rhport); + dwc2_epin_t * in_ep = EPIN_REG(rhport); // EP0 is limited to one packet each xfer // We use multiple transaction of xfer->max_size length to get a whole transfer done @@ -336,6 +332,7 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c ((total_bytes << DIEPTSIZ_XFRSIZ_Pos) & DIEPTSIZ_XFRSIZ_Msk); in_ep[epnum].DIEPCTL |= DIEPCTL_EPENA | DIEPCTL_CNAK; + // For ISO endpoint set correct odd/even bit for next frame. if ((in_ep[epnum].DIEPCTL & DIEPCTL_EPTYP) == DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) { @@ -370,7 +367,7 @@ void dcd_init (uint8_t rhport) { // Programming model begins in the last section of the chapter on the USB // peripheral in each Reference Manual. - dwc2_core_t * core = GLOBAL_BASE(rhport); + dwc2_core_t * core = CORE_REG(rhport); // No HNP/SRP (no OTG support), program timeout later. if ( rhport == 1 ) @@ -422,7 +419,7 @@ void dcd_init (uint8_t rhport) // the core to stop working/require reset. core->GINTMSK |= GINTMSK_OTGINT | GINTMSK_MMISM; - dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); // If USB host misbehaves during status portion of control xfer // (non zero-length packet), send STALL back and discard. @@ -433,9 +430,8 @@ void dcd_init (uint8_t rhport) // Enable internal USB transceiver, unless using HS core (port 1) with external PHY. if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) core->GCCFG |= GCCFG_PWRDWN; - core->GINTMSK |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | - GINTMSK_USBSUSPM | GINTMSK_WUIM | - GINTMSK_RXFLVLM | (USE_SOF ? GINTMSK_SOFM : 0); + core->GINTMSK |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_USBSUSPM | + GINTMSK_WUIM | GINTMSK_RXFLVLM; // Enable global interrupt core->GAHBCFG |= GAHBCFG_GINT; @@ -457,7 +453,7 @@ void dcd_int_disable (uint8_t rhport) void dcd_set_address (uint8_t rhport, uint8_t dev_addr) { - dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); dev->DCFG = (dev->DCFG & ~DCFG_DAD_Msk) | (dev_addr << DCFG_DAD_Pos); // Response with status after changing device address @@ -478,8 +474,8 @@ void dcd_remote_wakeup(uint8_t rhport) { (void) rhport; - dwc2_core_t * core = GLOBAL_BASE(rhport); - dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_core_t * core = CORE_REG(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); // set remote wakeup dev->DCTL |= DCTL_RWUSIG; @@ -497,14 +493,14 @@ void dcd_remote_wakeup(uint8_t rhport) void dcd_connect(uint8_t rhport) { (void) rhport; - dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); dev->DCTL &= ~DCTL_SDIS; } void dcd_disconnect(uint8_t rhport) { (void) rhport; - dwc2_device_t * dev = DEVICE_BASE(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); dev->DCTL |= DCTL_SDIS; } @@ -517,10 +513,10 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) { (void) rhport; - dwc2_core_t * core = GLOBAL_BASE(rhport); - dwc2_device_t * dev = DEVICE_BASE(rhport); - dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); - dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + dwc2_core_t * core = CORE_REG(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_epout_t * out_ep = EPOUT_REG(rhport); + dwc2_epin_t * in_ep = EPIN_REG(rhport); uint8_t const epnum = tu_edpt_number(desc_edpt->bEndpointAddress); uint8_t const dir = tu_edpt_dir(desc_edpt->bEndpointAddress); @@ -605,10 +601,10 @@ void dcd_edpt_close_all (uint8_t rhport) { (void) rhport; -// dwc2_core_t * core = GLOBAL_BASE(rhport); - dwc2_device_t * dev = DEVICE_BASE(rhport); - dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); - dwc2_epin_t * in_ep = IN_EP_BASE(rhport); +// dwc2_core_t * core = CORE_REG(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_epout_t * out_ep = EPOUT_REG(rhport); + dwc2_epin_t * in_ep = EPIN_REG(rhport); // Disable non-control interrupt dev->DAINTMSK = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); @@ -693,10 +689,10 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) { (void) rhport; - dwc2_core_t * core = GLOBAL_BASE(rhport); - dwc2_device_t * dev = DEVICE_BASE(rhport); - dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); - dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + dwc2_core_t * core = CORE_REG(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_epout_t * out_ep = EPOUT_REG(rhport); + dwc2_epin_t * in_ep = EPIN_REG(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const dir = tu_edpt_dir(ep_addr); @@ -748,7 +744,7 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) */ void dcd_edpt_close (uint8_t rhport, uint8_t ep_addr) { - dwc2_core_t * core = GLOBAL_BASE(rhport); + dwc2_core_t * core = CORE_REG(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const dir = tu_edpt_dir(ep_addr); @@ -781,8 +777,8 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) { (void) rhport; - dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); - dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + dwc2_epout_t * out_ep = EPOUT_REG(rhport); + dwc2_epin_t * in_ep = EPIN_REG(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const dir = tu_edpt_dir(ep_addr); @@ -861,14 +857,14 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, u } static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { - dwc2_core_t * core = GLOBAL_BASE(rhport); + dwc2_core_t * core = CORE_REG(rhport); usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); // Pop control word off FIFO uint32_t ctl_word = core->GRXSTSP; - uint8_t pktsts = (ctl_word & GRXSTSP_PKTSTS_Msk) >> GRXSTSP_PKTSTS_Pos; - uint8_t epnum = (ctl_word & GRXSTSP_EPNUM_Msk) >> GRXSTSP_EPNUM_Pos; - uint16_t bcnt = (ctl_word & GRXSTSP_BCNT_Msk) >> GRXSTSP_BCNT_Pos; + uint8_t pktsts = (ctl_word & GRXSTSP_PKTSTS_Msk) >> GRXSTSP_PKTSTS_Pos; + uint8_t epnum = (ctl_word & GRXSTSP_EPNUM_Msk) >> GRXSTSP_EPNUM_Pos; + uint16_t bcnt = (ctl_word & GRXSTSP_BCNT_Msk) >> GRXSTSP_BCNT_Pos; switch(pktsts) { case 0x01: // Global OUT NAK (Interrupt) @@ -1025,10 +1021,10 @@ static void handle_epin_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epin_t * void dcd_int_handler(uint8_t rhport) { - dwc2_core_t * core = GLOBAL_BASE(rhport); - dwc2_device_t * dev = DEVICE_BASE(rhport); - dwc2_epout_t * out_ep = OUT_EP_BASE(rhport); - dwc2_epin_t * in_ep = IN_EP_BASE(rhport); + dwc2_core_t * core = CORE_REG(rhport); + dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_epout_t * out_ep = EPOUT_REG(rhport); + dwc2_epin_t * in_ep = EPIN_REG(rhport); uint32_t const int_status = core->GINTSTS & core->GINTMSK; From 61c80840c30db790560076fef9808cccc3fdf361 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 25 Oct 2021 00:39:37 +0700 Subject: [PATCH 14/51] update dwc int enable/disable --- src/portable/synopsys/dwc2/dcd_dwc2.c | 17 +++++++---------- src/portable/synopsys/dwc2/dwc2_gd32.h | 22 +++++++++++++++++----- src/portable/synopsys/dwc2/dwc2_stm32.h | 14 ++++++++++++++ 3 files changed, 38 insertions(+), 15 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index aae6e7004..367fc7b56 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -32,6 +32,7 @@ #if TUSB_OPT_DEVICE_ENABLED && (defined(DCD_ATTR_DWC2_STM32) || TU_CHECK_MCU(GD32VF103)) +#include "device/dcd.h" #include "dwc2_type.h" #if defined(DCD_ATTR_DWC2_STM32) @@ -42,17 +43,15 @@ #error "Unsupported MCUs" #endif -#include "device/dcd.h" - //--------------------------------------------------------------------+ // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ -#define CORE_REG(_port) ((dwc2_core_t*) DWC2_REG_BASE) +#define CORE_REG(_port) ((dwc2_core_t*) DWC2_REG_BASE) #define DEVICE_REG(_port) ((dwc2_device_t*) (DWC2_REG_BASE + DWC2_DEVICE_BASE)) -#define EPIN_REG(_port) ((dwc2_epin_t*) (DWC2_REG_BASE + DWC2_IN_ENDPOINT_BASE)) -#define EPOUT_REG(_port) ((dwc2_epout_t*) (DWC2_REG_BASE + DWC2_OUT_ENDPOINT_BASE)) -#define FIFO_BASE(_port, _x) ((volatile uint32_t*) (DWC2_REG_BASE + DWC2_FIFO_BASE + (_x) * DWC2_FIFO_SIZE)) +#define EPIN_REG(_port) ((dwc2_epin_t*) (DWC2_REG_BASE + DWC2_IN_ENDPOINT_BASE)) +#define EPOUT_REG(_port) ((dwc2_epout_t*) (DWC2_REG_BASE + DWC2_OUT_ENDPOINT_BASE)) +#define FIFO_BASE(_port, _x) ((volatile uint32_t*) (DWC2_REG_BASE + DWC2_FIFO_BASE + (_x) * DWC2_FIFO_SIZE)) enum { @@ -441,14 +440,12 @@ void dcd_init (uint8_t rhport) void dcd_int_enable (uint8_t rhport) { - (void) rhport; - NVIC_EnableIRQ(RHPORT_IRQn); + dcd_dwc2_int_enable(rhport); } void dcd_int_disable (uint8_t rhport) { - (void) rhport; - NVIC_DisableIRQ(RHPORT_IRQn); + dcd_dwc2_int_disable(rhport); } void dcd_set_address (uint8_t rhport, uint8_t dev_addr) diff --git a/src/portable/synopsys/dwc2/dwc2_gd32.h b/src/portable/synopsys/dwc2/dwc2_gd32.h index 3ace4d484..8fe390fd8 100644 --- a/src/portable/synopsys/dwc2/dwc2_gd32.h +++ b/src/portable/synopsys/dwc2/dwc2_gd32.h @@ -32,26 +32,38 @@ #define __NOP() __asm volatile ("nop") // These numbers are the same for the whole GD32VF103 family. -#define RHPORT_IRQn 86 +#define DWC2_REG_BASE 0x50000000UL #define EP_MAX 4 #define EP_FIFO_SIZE 1280 -#define DWC2_REG_BASE 0x50000000UL +#define RHPORT_IRQn 86 // The GD32VF103 is a RISC-V MCU, which implements the ECLIC Core-Local // Interrupt Controller by Nuclei. It is nearly API compatible to the // NVIC used by ARM MCUs. #define ECLIC_INTERRUPT_ENABLE_BASE 0xD2001001UL -#define NVIC_EnableIRQ __eclic_enable_interrupt -#define NVIC_DisableIRQ __eclic_disable_interrupt - +TU_ATTR_ALWAYS_INLINE static inline void __eclic_enable_interrupt (uint32_t irq) { *(volatile uint8_t*)(ECLIC_INTERRUPT_ENABLE_BASE + (irq * 4)) = 1; } +TU_ATTR_ALWAYS_INLINE static inline void __eclic_disable_interrupt (uint32_t irq){ *(volatile uint8_t*)(ECLIC_INTERRUPT_ENABLE_BASE + (irq * 4)) = 0; } +TU_ATTR_ALWAYS_INLINE +static inline void dcd_dwc2_int_enable(uint8_t rhport) +{ + (void) rhport; + __eclic_enable_interrupt(RHPORT_IRQn); +} + +TU_ATTR_ALWAYS_INLINE +static inline void dcd_dwc2_int_disable (uint8_t rhport) +{ + (void) rhport; + __eclic_disable_interrupt(RHPORT_IRQn); +} #endif /* DWC2_GD32_H_ */ diff --git a/src/portable/synopsys/dwc2/dwc2_stm32.h b/src/portable/synopsys/dwc2/dwc2_stm32.h index 3a5e1a9ac..d99e5502a 100644 --- a/src/portable/synopsys/dwc2/dwc2_stm32.h +++ b/src/portable/synopsys/dwc2/dwc2_stm32.h @@ -84,4 +84,18 @@ #endif +TU_ATTR_ALWAYS_INLINE +static inline void dcd_dwc2_int_enable(uint8_t rhport) +{ + (void) rhport; + NVIC_EnableIRQ(RHPORT_IRQn); +} + +TU_ATTR_ALWAYS_INLINE +static inline void dcd_dwc2_int_disable (uint8_t rhport) +{ + (void) rhport; + NVIC_DisableIRQ(RHPORT_IRQn); +} + #endif /* DWC2_STM32_H_ */ From a0202df920889b57f79560760f6a38632e52c364 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 25 Oct 2021 13:49:59 +0700 Subject: [PATCH 15/51] add TU_ARGS_APPLY(), TU_CHECK_MCU() now could check list of mcus --- src/common/tusb_common.h | 31 ----------------------------- src/common/tusb_compiler.h | 40 ++++++++++++++++++++++++++++++++++++++ src/tusb_option.h | 9 ++++++++- 3 files changed, 48 insertions(+), 32 deletions(-) diff --git a/src/common/tusb_common.h b/src/common/tusb_common.h index fc92654b7..bf9641622 100644 --- a/src/common/tusb_common.h +++ b/src/common/tusb_common.h @@ -235,37 +235,6 @@ TU_ATTR_ALWAYS_INLINE static inline void tu_unaligned_write16 (void* mem, ui #endif -/*------------------------------------------------------------------*/ -/* Count number of arguments of __VA_ARGS__ - * - reference https://groups.google.com/forum/#!topic/comp.std.c/d-6Mj5Lko_s - * - _GET_NTH_ARG() takes args >= N (64) but only expand to Nth one (64th) - * - _RSEQ_N() is reverse sequential to N to add padding to have - * Nth position is the same as the number of arguments - * - ##__VA_ARGS__ is used to deal with 0 paramerter (swallows comma) - *------------------------------------------------------------------*/ -#ifndef TU_ARGS_NUM - -#define TU_ARGS_NUM(...) _TU_NARG(_0, ##__VA_ARGS__,_RSEQ_N()) - -#define _TU_NARG(...) _GET_NTH_ARG(__VA_ARGS__) -#define _GET_NTH_ARG( \ - _1, _2, _3, _4, _5, _6, _7, _8, _9,_10, \ - _11,_12,_13,_14,_15,_16,_17,_18,_19,_20, \ - _21,_22,_23,_24,_25,_26,_27,_28,_29,_30, \ - _31,_32,_33,_34,_35,_36,_37,_38,_39,_40, \ - _41,_42,_43,_44,_45,_46,_47,_48,_49,_50, \ - _51,_52,_53,_54,_55,_56,_57,_58,_59,_60, \ - _61,_62,_63,N,...) N -#define _RSEQ_N() \ - 62,61,60, \ - 59,58,57,56,55,54,53,52,51,50, \ - 49,48,47,46,45,44,43,42,41,40, \ - 39,38,37,36,35,34,33,32,31,30, \ - 29,28,27,26,25,24,23,22,21,20, \ - 19,18,17,16,15,14,13,12,11,10, \ - 9,8,7,6,5,4,3,2,1,0 -#endif - // To be removed //------------- Binary constant -------------// #if defined(__GNUC__) && !defined(__CC_ARM) diff --git a/src/common/tusb_compiler.h b/src/common/tusb_compiler.h index 3e85939b0..b0999b5d9 100644 --- a/src/common/tusb_compiler.h +++ b/src/common/tusb_compiler.h @@ -67,6 +67,46 @@ #define TU_LITTLE_ENDIAN (0x12u) #define TU_BIG_ENDIAN (0x21u) +/*------------------------------------------------------------------*/ +/* Count number of arguments of __VA_ARGS__ + * - reference https://groups.google.com/forum/#!topic/comp.std.c/d-6Mj5Lko_s + * - _GET_NTH_ARG() takes args >= N (64) but only expand to Nth one (64th) + * - _RSEQ_N() is reverse sequential to N to add padding to have + * Nth position is the same as the number of arguments + * - ##__VA_ARGS__ is used to deal with 0 paramerter (swallows comma) + *------------------------------------------------------------------*/ +#define TU_ARGS_NUM(...) _TU_NARG(_0, ##__VA_ARGS__,_RSEQ_N()) + +#define _TU_NARG(...) _GET_NTH_ARG(__VA_ARGS__) +#define _GET_NTH_ARG( \ + _1, _2, _3, _4, _5, _6, _7, _8, _9,_10, \ + _11,_12,_13,_14,_15,_16,_17,_18,_19,_20, \ + _21,_22,_23,_24,_25,_26,_27,_28,_29,_30, \ + _31,_32,_33,_34,_35,_36,_37,_38,_39,_40, \ + _41,_42,_43,_44,_45,_46,_47,_48,_49,_50, \ + _51,_52,_53,_54,_55,_56,_57,_58,_59,_60, \ + _61,_62,_63,N,...) N +#define _RSEQ_N() \ + 62,61,60, \ + 59,58,57,56,55,54,53,52,51,50, \ + 49,48,47,46,45,44,43,42,41,40, \ + 39,38,37,36,35,34,33,32,31,30, \ + 29,28,27,26,25,24,23,22,21,20, \ + 19,18,17,16,15,14,13,12,11,10, \ + 9,8,7,6,5,4,3,2,1,0 + +// Apply an macro X to each of the arguments with an separated of choice +#define TU_ARGS_APPLY(_X, _s, ...) TU_XSTRCAT(_TU_ARGS_APPLY_, TU_ARGS_NUM(__VA_ARGS__))(_X, _s, __VA_ARGS__) + +#define _TU_ARGS_APPLY_1(_X, _s, _a1) _X(_a1) +#define _TU_ARGS_APPLY_2(_X, _s, _a1, _a2) _X(_a1) _s _X(_a2) +#define _TU_ARGS_APPLY_3(_X, _s, _a1, _a2, _a3) _X(_a1) _s _TU_ARGS_APPLY_2(_X, _s, _a2, _a3) +#define _TU_ARGS_APPLY_4(_X, _s, _a1, _a2, _a3, _a4) _X(_a1) _s _TU_ARGS_APPLY_3(_X, _s, _a2, _a3, _a4) +#define _TU_ARGS_APPLY_5(_X, _s, _a1, _a2, _a3, _a4, _a5) _X(_a1) _s _TU_ARGS_APPLY_4(_X, _s, _a2, _a3, _a4, _a5) +#define _TU_ARGS_APPLY_6(_X, _s, _a1, _a2, _a3, _a4, _a5, _a6) _X(_a1) _s _TU_ARGS_APPLY_5(_X, _s, _a2, _a3, _a4, _a5, _a6) +#define _TU_ARGS_APPLY_7(_X, _s, _a1, _a2, _a3, _a4, _a5, _a6, _a7) _X(_a1) _s _TU_ARGS_APPLY_6(_X, _s, _a2, _a3, _a4, _a5, _a6, _a7) +#define _TU_ARGS_APPLY_8(_X, _s, _a1, _a2, _a3, _a4, _a5, _a6, _a7, _a8) _X(_a1) _s _TU_ARGS_APPLY_7(_X, _s, _a2, _a3, _a4, _a5, _a6, _a7, _a8) + //--------------------------------------------------------------------+ // Compiler porting with Attribute and Endian //--------------------------------------------------------------------+ diff --git a/src/tusb_option.h b/src/tusb_option.h index e49fc0119..89d83472b 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -27,6 +27,8 @@ #ifndef _TUSB_OPTION_H_ #define _TUSB_OPTION_H_ +#include "common/tusb_compiler.h" + #define TUSB_VERSION_MAJOR 0 #define TUSB_VERSION_MINOR 12 #define TUSB_VERSION_REVISION 0 @@ -36,7 +38,6 @@ // Supported MCUs // CFG_TUSB_MCU must be defined to one of following value //--------------------------------------------------------------------+ -#define TU_CHECK_MCU(_m) (CFG_TUSB_MCU == OPT_MCU_##_m) #define OPT_MCU_NONE 0 @@ -126,6 +127,12 @@ // GigaDevice #define OPT_MCU_GD32VF103 1600 ///< GigaDevice GD32VF103 + +// Helper to check if configured MCU is one of listed +// Apply _TU_CHECK_MCU with || as separator to list of input +#define _TU_CHECK_MCU(_m) (CFG_TUSB_MCU == OPT_MCU_##_m) +#define TU_CHECK_MCU(...) TU_ARGS_APPLY(_TU_CHECK_MCU, ||, __VA_ARGS__) + //--------------------------------------------------------------------+ // Supported OS //--------------------------------------------------------------------+ From 4ccf60954d184c0530daf800090bd7103aacee86 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 25 Oct 2021 15:51:41 +0700 Subject: [PATCH 16/51] moving esp32s2 to dwc2, abstract dwc2_set_turnaround() --- .../cdc_msc_freertos/src/CMakeLists.txt | 2 +- hw/bsp/gd32vf103/family.mk | 3 +- src/device/dcd_attr.h | 16 +-- src/portable/synopsys/dwc2/dcd_dwc2.c | 98 +++++-------------- src/portable/synopsys/dwc2/dwc2_esp32.h | 82 ++++++++++++++++ src/portable/synopsys/dwc2/dwc2_gd32.h | 37 +++++-- src/portable/synopsys/dwc2/dwc2_stm32.h | 83 +++++++++++++--- src/tusb_option.h | 2 +- 8 files changed, 222 insertions(+), 101 deletions(-) create mode 100644 src/portable/synopsys/dwc2/dwc2_esp32.h diff --git a/examples/device/cdc_msc_freertos/src/CMakeLists.txt b/examples/device/cdc_msc_freertos/src/CMakeLists.txt index 07fc4df89..93ae0686a 100644 --- a/examples/device/cdc_msc_freertos/src/CMakeLists.txt +++ b/examples/device/cdc_msc_freertos/src/CMakeLists.txt @@ -27,5 +27,5 @@ target_sources(${COMPONENT_TARGET} PUBLIC "${TOP}/src/class/net/ncm_device.c" "${TOP}/src/class/usbtmc/usbtmc_device.c" "${TOP}/src/class/vendor/vendor_device.c" - "${TOP}/src/portable/espressif/esp32sx/dcd_esp32sx.c" + "${TOP}/src/portable/synopsys/dwc2/dcd_dwc2.c" ) diff --git a/hw/bsp/gd32vf103/family.mk b/hw/bsp/gd32vf103/family.mk index 4de23ac17..49bacdf1b 100644 --- a/hw/bsp/gd32vf103/family.mk +++ b/hw/bsp/gd32vf103/family.mk @@ -28,8 +28,7 @@ CFLAGS += \ -mstrict-align \ -nostdlib -nostartfiles \ -DCFG_TUSB_MCU=OPT_MCU_GD32VF103 \ - -DDOWNLOAD_MODE=DOWNLOAD_MODE_FLASHXIP \ - -DGD32VF103 + -DDOWNLOAD_MODE=DOWNLOAD_MODE_FLASHXIP # mcu driver cause following warnings CFLAGS += -Wno-error=unused-parameter diff --git a/src/device/dcd_attr.h b/src/device/dcd_attr.h index 3690985c6..ddec481a8 100644 --- a/src/device/dcd_attr.h +++ b/src/device/dcd_attr.h @@ -36,13 +36,13 @@ // - PORT_HIGHSPEED: mask to indicate which port support highspeed mode, bit0 for port0 and so on. //------------- NXP -------------// -#if TU_CHECK_MCU(LPC11UXX) || TU_CHECK_MCU(LPC13XX) || TU_CHECK_MCU(LPC15XX) +#if TU_CHECK_MCU(LPC11UXX, LPC13XX, LPC15XX) #define DCD_ATTR_ENDPOINT_MAX 5 -#elif TU_CHECK_MCU(LPC175X_6X) || TU_CHECK_MCU(LPC177X_8X) || TU_CHECK_MCU(LPC40XX) +#elif TU_CHECK_MCU(LPC175X_6X, LPC177X_8X, LPC40XX) #define DCD_ATTR_ENDPOINT_MAX 16 -#elif TU_CHECK_MCU(LPC18XX) || TU_CHECK_MCU(LPC43XX) +#elif TU_CHECK_MCU(LPC18XX, LPC43XX) // TODO USB0 has 6, USB1 has 4 #define DCD_ATTR_ENDPOINT_MAX 6 @@ -60,7 +60,7 @@ #elif TU_CHECK_MCU(MIMXRT10XX) #define DCD_ATTR_ENDPOINT_MAX 8 -#elif TU_CHECK_MCU(MKL25ZXX) || TU_CHECK_MCU(K32L2BXX) +#elif TU_CHECK_MCU(MKL25ZXX, K32L2BXX) #define DCD_ATTR_ENDPOINT_MAX 16 #elif TU_CHECK_MCU(MM32F327X) @@ -72,8 +72,8 @@ #define DCD_ATTR_ENDPOINT_MAX 9 //------------- Microchip -------------// -#elif TU_CHECK_MCU(SAMD21) || TU_CHECK_MCU(SAMD51) || TU_CHECK_MCU(SAME5X) || \ - TU_CHECK_MCU(SAMD11) || TU_CHECK_MCU(SAML21) || TU_CHECK_MCU(SAML22) +#elif TU_CHECK_MCU(SAMD21, SAMD51, SAME5X) || \ + TU_CHECK_MCU(SAMD11, SAML21, SAML22) #define DCD_ATTR_ENDPOINT_MAX 8 #elif TU_CHECK_MCU(SAMG) @@ -119,7 +119,7 @@ #define DCD_ATTR_ENDPOINT_MAX 9 #define DCD_ATTR_DWC2_STM32 -#elif TU_CHECK_MCU(STM32L0) || TU_CHECK_MCU(STM32L1) +#elif TU_CHECK_MCU(STM32L0, STM32L1) #define DCD_ATTR_ENDPOINT_MAX 8 #elif TU_CHECK_MCU(STM32L4) @@ -157,7 +157,7 @@ #define DCD_ATTR_ENDPOINT_MAX 12 //------------- Espressif -------------// -#elif TU_CHECK_MCU(ESP32S2) || TU_CHECK_MCU(ESP32S3) +#elif TU_CHECK_MCU(ESP32S2, ESP32S3) #define DCD_ATTR_ENDPOINT_MAX 6 //------------- Dialog -------------// diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 367fc7b56..c3773fb8b 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -30,13 +30,16 @@ #include "tusb_option.h" #include "device/dcd_attr.h" -#if TUSB_OPT_DEVICE_ENABLED && (defined(DCD_ATTR_DWC2_STM32) || TU_CHECK_MCU(GD32VF103)) +#if TUSB_OPT_DEVICE_ENABLED && \ + ( defined(DCD_ATTR_DWC2_STM32) || TU_CHECK_MCU(ESP32S2, ESP32S3, GD32VF103) ) #include "device/dcd.h" #include "dwc2_type.h" #if defined(DCD_ATTR_DWC2_STM32) #include "dwc2_stm32.h" +#elif TU_CHECK_MCU(ESP32S2, ESP32S3) + #include "dwc2_esp32.h" #elif TU_CHECK_MCU(GD32VF103) #include "dwc2_gd32.h" #else @@ -72,7 +75,7 @@ typedef struct { typedef volatile uint32_t * usb_fifo_t; -xfer_ctl_t xfer_status[EP_MAX][2]; +xfer_ctl_t xfer_status[DWC2_EP_MAX][2]; #define XFER_CTL_BASE(_ep, _dir) &xfer_status[_ep][_dir] // EP0 transfers are limited to 1 packet - larger sizes has to be split @@ -85,7 +88,7 @@ static bool _out_ep_closed; // Flag to check if RX FIFO si // Calculate the RX FIFO size according to recommendations from reference manual static inline uint16_t calc_rx_ff_size(uint16_t ep_size) { - return 15 + 2*(ep_size/4) + 2*EP_MAX; + return 15 + 2*(ep_size/4) + 2*DWC2_EP_MAX; } static void update_grxfsiz(uint8_t rhport) @@ -96,7 +99,7 @@ static void update_grxfsiz(uint8_t rhport) // Determine largest EP size for RX FIFO uint16_t max_epsize = 0; - for (uint8_t epnum = 0; epnum < EP_MAX; epnum++) + for (uint8_t epnum = 0; epnum < DWC2_EP_MAX; epnum++) { max_epsize = tu_max16(max_epsize, xfer_status[epnum][TUSB_DIR_OUT].max_size); } @@ -122,7 +125,7 @@ static void bus_reset(uint8_t rhport) dev->DCFG &= ~DCFG_DAD_Msk; // 1. NAK for all OUT endpoints - for(uint8_t n = 0; n < EP_MAX; n++) { + for(uint8_t n = 0; n < DWC2_EP_MAX; n++) { out_ep[n].DOEPCTL |= DOEPCTL_SNAK; } @@ -171,11 +174,11 @@ static void bus_reset(uint8_t rhport) // - 2 for each used OUT endpoint // // Therefore GRXFSIZ = 13 + 1 + 1 + 2 x (Largest-EPsize/4) + 2 x EPOUTnum - // - FullSpeed (64 Bytes ): GRXFSIZ = 15 + 2 x 16 + 2 x EP_MAX = 47 + 2 x EP_MAX - // - Highspeed (512 bytes): GRXFSIZ = 15 + 2 x 128 + 2 x EP_MAX = 271 + 2 x EP_MAX + // - FullSpeed (64 Bytes ): GRXFSIZ = 15 + 2 x 16 + 2 x DWC2_EP_MAX = 47 + 2 x DWC2_EP_MAX + // - Highspeed (512 bytes): GRXFSIZ = 15 + 2 x 128 + 2 x DWC2_EP_MAX = 271 + 2 x DWC2_EP_MAX // // NOTE: Largest-EPsize & EPOUTnum is actual used endpoints in configuration. Since DCD has no knowledge - // of the overall picture yet. We will use the worst scenario: largest possible + EP_MAX + // of the overall picture yet. We will use the worst scenario: largest possible + DWC2_EP_MAX // // For Isochronous, largest EP size can be 1023/1024 for FS/HS respectively. In addition if multiple ISO // are enabled at least "2 x (Largest-EPsize/4) + 1" are recommended. Maybe provide a macro for application to @@ -186,7 +189,7 @@ static void bus_reset(uint8_t rhport) _allocated_fifo_words_tx = 16; // Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) - core->DIEPTXF0_HNPTXFSIZ = (16 << TX0FD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + core->DIEPTXF0_HNPTXFSIZ = (16 << TX0FD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); // Fixed control EP0 size to 64 bytes in_ep[0].DIEPCTL &= ~(0x03 << DIEPCTL_MPSIZ_Pos); @@ -197,47 +200,6 @@ static void bus_reset(uint8_t rhport) core->GINTMSK |= GINTMSK_OEPINT | GINTMSK_IEPINT; } -// Set turn-around timeout according to link speed -extern uint32_t SystemCoreClock; -static void set_turnaround(dwc2_core_t * core, tusb_speed_t speed) -{ - core->GUSBCFG &= ~GUSBCFG_TRDT; - - if ( speed == TUSB_SPEED_HIGH ) - { - // Use fixed 0x09 for Highspeed - core->GUSBCFG |= (0x09 << GUSBCFG_TRDT_Pos); - } - else - { - // Turnaround timeout depends on the MCU clock - uint32_t turnaround; - - if ( SystemCoreClock >= 32000000U ) - turnaround = 0x6U; - else if ( SystemCoreClock >= 27500000U ) - turnaround = 0x7U; - else if ( SystemCoreClock >= 24000000U ) - turnaround = 0x8U; - else if ( SystemCoreClock >= 21800000U ) - turnaround = 0x9U; - else if ( SystemCoreClock >= 20000000U ) - turnaround = 0xAU; - else if ( SystemCoreClock >= 18500000U ) - turnaround = 0xBU; - else if ( SystemCoreClock >= 17200000U ) - turnaround = 0xCU; - else if ( SystemCoreClock >= 16000000U ) - turnaround = 0xDU; - else if ( SystemCoreClock >= 15000000U ) - turnaround = 0xEU; - else - turnaround = 0xFU; - - // Fullspeed depends on MCU clocks, but we will use 0x06 for 32+ Mhz - core->GUSBCFG |= (turnaround << GUSBCFG_TRDT_Pos); - } -} static tusb_speed_t get_speed(uint8_t rhport) { @@ -368,6 +330,8 @@ void dcd_init (uint8_t rhport) // peripheral in each Reference Manual. dwc2_core_t * core = CORE_REG(rhport); + // check GSNPSID + // No HNP/SRP (no OTG support), program timeout later. if ( rhport == 1 ) { @@ -422,7 +386,7 @@ void dcd_init (uint8_t rhport) // If USB host misbehaves during status portion of control xfer // (non zero-length packet), send STALL back and discard. - dev->DCFG |= DCFG_NZLSOHSK; + dev->DCFG |= DCFG_NZLSOHSK; set_speed(rhport, TUD_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL); @@ -457,16 +421,6 @@ void dcd_set_address (uint8_t rhport, uint8_t dev_addr) dcd_edpt_xfer(rhport, tu_edpt_addr(0, TUSB_DIR_IN), NULL, 0); } -static void remote_wakeup_delay(void) -{ - // try to delay for 1 ms - uint32_t count = SystemCoreClock / 1000; - while ( count-- ) - { - __NOP(); - } -} - void dcd_remote_wakeup(uint8_t rhport) { (void) rhport; @@ -482,7 +436,7 @@ void dcd_remote_wakeup(uint8_t rhport) core->GINTMSK |= GINTMSK_SOFM; // Per specs: remote wakeup signal bit must be clear within 1-15ms - remote_wakeup_delay(); + dwc2_remote_wakeup_delay(); dev->DCTL &= ~DCTL_RWUSIG; } @@ -518,7 +472,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) uint8_t const epnum = tu_edpt_number(desc_edpt->bEndpointAddress); uint8_t const dir = tu_edpt_dir(desc_edpt->bEndpointAddress); - TU_ASSERT(epnum < EP_MAX); + TU_ASSERT(epnum < DWC2_EP_MAX); xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); xfer->max_size = tu_edpt_packet_size(desc_edpt); @@ -534,7 +488,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // If size_rx needs to be extended check if possible and if so enlarge it if (core->GRXFSIZ < sz) { - TU_ASSERT(sz + _allocated_fifo_words_tx <= EP_FIFO_SIZE/4); + TU_ASSERT(sz + _allocated_fifo_words_tx <= DWC2_EP_FIFO_SIZE/4); // Enlarge RX FIFO core->GRXFSIZ = sz; @@ -571,15 +525,15 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // - IN EP 1 gets FIFO 1, IN EP "n" gets FIFO "n". // Check if free space is available - TU_ASSERT(_allocated_fifo_words_tx + fifo_size + core->GRXFSIZ <= EP_FIFO_SIZE/4); + TU_ASSERT(_allocated_fifo_words_tx + fifo_size + core->GRXFSIZ <= DWC2_EP_FIFO_SIZE/4); _allocated_fifo_words_tx += fifo_size; - TU_LOG(2, " Allocated %u bytes at offset %u", fifo_size*4, EP_FIFO_SIZE-_allocated_fifo_words_tx*4); + TU_LOG(2, " Allocated %u bytes at offset %u", fifo_size*4, DWC2_EP_FIFO_SIZE-_allocated_fifo_words_tx*4); // DIEPTXF starts at FIFO #1. // Both TXFD and TXSA are in unit of 32-bit words. - core->DIEPTXF[epnum - 1] = (fifo_size << DIEPTXF_INEPTXFD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + core->DIEPTXF[epnum - 1] = (fifo_size << DIEPTXF_INEPTXFD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); in_ep[epnum].DIEPCTL |= (1 << DIEPCTL_USBAEP_Pos) | (epnum << DIEPCTL_TXFNUM_Pos) | @@ -606,7 +560,7 @@ void dcd_edpt_close_all (uint8_t rhport) // Disable non-control interrupt dev->DAINTMSK = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); - for(uint8_t n = 1; n < EP_MAX; n++) + for(uint8_t n = 1; n < DWC2_EP_MAX; n++) { // disable OUT endpoint out_ep[n].DOEPCTL = 0; @@ -756,7 +710,7 @@ void dcd_edpt_close (uint8_t rhport, uint8_t ep_addr) uint16_t const fifo_size = (core->DIEPTXF[epnum - 1] & DIEPTXF_INEPTXFD_Msk) >> DIEPTXF_INEPTXFD_Pos; uint16_t const fifo_start = (core->DIEPTXF[epnum - 1] & DIEPTXF_INEPTXSA_Msk) >> DIEPTXF_INEPTXSA_Pos; // For now only the last opened endpoint can be closed without fuss. - TU_ASSERT(fifo_start == EP_FIFO_SIZE/4 - _allocated_fifo_words_tx,); + TU_ASSERT(fifo_start == DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx,); _allocated_fifo_words_tx -= fifo_size; } else @@ -920,7 +874,7 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { static void handle_epout_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epout_t * out_ep) { // DAINT for a given EP clears when DOEPINTx is cleared. // OEPINT will be cleared when DAINT's out bits are cleared. - for(uint8_t n = 0; n < EP_MAX; n++) { + for(uint8_t n = 0; n < DWC2_EP_MAX; n++) { xfer_ctl_t * xfer = XFER_CTL_BASE(n, TUSB_DIR_OUT); if(dev->DAINT & (1 << (DAINT_OEPINT_Pos + n))) { @@ -949,7 +903,7 @@ static void handle_epout_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epout_t static void handle_epin_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epin_t * in_ep) { // DAINT for a given EP clears when DIEPINTx is cleared. // IEPINT will be cleared when DAINT's out bits are cleared. - for ( uint8_t n = 0; n < EP_MAX; n++ ) + for ( uint8_t n = 0; n < DWC2_EP_MAX; n++ ) { xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_IN); @@ -1040,7 +994,7 @@ void dcd_int_handler(uint8_t rhport) tusb_speed_t const speed = get_speed(rhport); - set_turnaround(core, speed); + dwc2_set_turnaround(core, speed); dcd_event_bus_reset(rhport, speed, true); } diff --git a/src/portable/synopsys/dwc2/dwc2_esp32.h b/src/portable/synopsys/dwc2/dwc2_esp32.h new file mode 100644 index 000000000..5e544673d --- /dev/null +++ b/src/portable/synopsys/dwc2/dwc2_esp32.h @@ -0,0 +1,82 @@ +/* + * 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 _DWC2_ESP32_H_ +#define _DWC2_ESP32_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#include "esp_intr_alloc.h" +#include "soc/periph_defs.h" +//#include "soc/usb_periph.h" + +#define DWC2_REG_BASE 0x60080000UL +#define DWC2_EP_MAX 5 // USB_OUT_EP_NUM +#define DWC2_EP_FIFO_SIZE 1024 + +// #define EP_FIFO_NUM 5 + +static intr_handle_t usb_ih; + +static void dcd_int_handler_wrap(void* arg) +{ + (void) arg; + dcd_int_handler(0); +} + +static inline void dcd_dwc2_int_enable (uint8_t rhport) +{ + (void) rhport; + esp_intr_alloc(ETS_USB_INTR_SOURCE, ESP_INTR_FLAG_LOWMED, dcd_int_handler_wrap, NULL, &usb_ih); +} + +static inline void dcd_dwc2_int_disable (uint8_t rhport) +{ + (void) rhport; + esp_intr_free(usb_ih); +} + +static inline void dwc2_remote_wakeup_delay(void) +{ + vTaskDelay(pdMS_TO_TICKS(1)); +} + +static inline void dwc2_set_turnaround(dwc2_core_t * core, tusb_speed_t speed) +{ + (void) core; + (void) speed; + + // keep the reset value +} + +#ifdef __cplusplus +} +#endif + +#endif /* _DWC2_ESP32_H_ */ diff --git a/src/portable/synopsys/dwc2/dwc2_gd32.h b/src/portable/synopsys/dwc2/dwc2_gd32.h index 8fe390fd8..1ad066720 100644 --- a/src/portable/synopsys/dwc2/dwc2_gd32.h +++ b/src/portable/synopsys/dwc2/dwc2_gd32.h @@ -28,14 +28,18 @@ #ifndef DWC2_GD32_H_ #define DWC2_GD32_H_ -// for remote wakeup delay -#define __NOP() __asm volatile ("nop") +#ifdef __cplusplus + extern "C" { +#endif + // These numbers are the same for the whole GD32VF103 family. -#define DWC2_REG_BASE 0x50000000UL -#define EP_MAX 4 -#define EP_FIFO_SIZE 1280 -#define RHPORT_IRQn 86 +#define DWC2_REG_BASE 0x50000000UL +#define DWC2_EP_MAX 4 +#define DWC2_EP_FIFO_SIZE 1280 +#define RHPORT_IRQn 86 + +extern uint32_t SystemCoreClock; // The GD32VF103 is a RISC-V MCU, which implements the ECLIC Core-Local // Interrupt Controller by Nuclei. It is nearly API compatible to the @@ -66,4 +70,25 @@ static inline void dcd_dwc2_int_disable (uint8_t rhport) __eclic_disable_interrupt(RHPORT_IRQn); } +TU_ATTR_ALWAYS_INLINE +static inline void dwc2_remote_wakeup_delay(void) +{ + // try to delay for 1 ms + uint32_t count = SystemCoreClock / 1000; + while ( count-- ) __asm volatile ("nop"); +} + +static inline void dwc2_set_turnaround(dwc2_core_t * core, tusb_speed_t speed) +{ + (void) core; + (void) speed; + + // keep the reset value +} + + +#ifdef __cplusplus +} +#endif + #endif /* DWC2_GD32_H_ */ diff --git a/src/portable/synopsys/dwc2/dwc2_stm32.h b/src/portable/synopsys/dwc2/dwc2_stm32.h index d99e5502a..2a6d58e9a 100644 --- a/src/portable/synopsys/dwc2/dwc2_stm32.h +++ b/src/portable/synopsys/dwc2/dwc2_stm32.h @@ -24,8 +24,12 @@ * This file is part of the TinyUSB stack. */ -#ifndef _TUSB_DWC2_STM32_H_ -#define _TUSB_DWC2_STM32_H_ +#ifndef _DWC2_STM32_H_ +#define _DWC2_STM32_H_ + +#ifdef __cplusplus + extern "C" { +#endif // EP_MAX : Max number of bi-directional endpoints including EP0 // EP_FIFO_SIZE : Size of dedicated USB SRAM @@ -71,19 +75,21 @@ // On STM32 we associate Port0 to OTG_FS, and Port1 to OTG_HS #if TUD_OPT_RHPORT == 0 - #define EP_MAX EP_MAX_FS - #define EP_FIFO_SIZE EP_FIFO_SIZE_FS - #define DWC2_REG_BASE USB_OTG_FS_PERIPH_BASE - #define RHPORT_IRQn OTG_FS_IRQn + #define DWC2_REG_BASE USB_OTG_FS_PERIPH_BASE + #define DWC2_EP_MAX EP_MAX_FS + #define DWC2_EP_FIFO_SIZE EP_FIFO_SIZE_FS + #define RHPORT_IRQn OTG_FS_IRQn #else - #define EP_MAX EP_MAX_HS - #define EP_FIFO_SIZE EP_FIFO_SIZE_HS - #define DWC2_REG_BASE USB_OTG_HS_PERIPH_BASE - #define RHPORT_IRQn OTG_HS_IRQn + #define DWC2_REG_BASE USB_OTG_HS_PERIPH_BASE + #define DWC2_EP_MAX EP_MAX_HS + #define DWC2_EP_FIFO_SIZE EP_FIFO_SIZE_HS + #define RHPORT_IRQn OTG_HS_IRQn #endif +extern uint32_t SystemCoreClock; + TU_ATTR_ALWAYS_INLINE static inline void dcd_dwc2_int_enable(uint8_t rhport) { @@ -98,4 +104,59 @@ static inline void dcd_dwc2_int_disable (uint8_t rhport) NVIC_DisableIRQ(RHPORT_IRQn); } -#endif /* DWC2_STM32_H_ */ +TU_ATTR_ALWAYS_INLINE +static inline void dwc2_remote_wakeup_delay(void) +{ + // try to delay for 1 ms + uint32_t count = SystemCoreClock / 1000; + while ( count-- ) __NOP(); +} + +// Set turn-around timeout according to link speed +static inline void dwc2_set_turnaround(dwc2_core_t * core, tusb_speed_t speed) +{ + core->GUSBCFG &= ~GUSBCFG_TRDT; + + if ( speed == TUSB_SPEED_HIGH ) + { + // Use fixed 0x09 for Highspeed + core->GUSBCFG |= (0x09 << GUSBCFG_TRDT_Pos); + } + else + { + // Turnaround timeout depends on the MCU clock + uint32_t turnaround; + + if ( SystemCoreClock >= 32000000U ) + turnaround = 0x6U; + else if ( SystemCoreClock >= 27500000U ) + turnaround = 0x7U; + else if ( SystemCoreClock >= 24000000U ) + turnaround = 0x8U; + else if ( SystemCoreClock >= 21800000U ) + turnaround = 0x9U; + else if ( SystemCoreClock >= 20000000U ) + turnaround = 0xAU; + else if ( SystemCoreClock >= 18500000U ) + turnaround = 0xBU; + else if ( SystemCoreClock >= 17200000U ) + turnaround = 0xCU; + else if ( SystemCoreClock >= 16000000U ) + turnaround = 0xDU; + else if ( SystemCoreClock >= 15000000U ) + turnaround = 0xEU; + else + turnaround = 0xFU; + + // Fullspeed depends on MCU clocks, but we will use 0x06 for 32+ Mhz + core->GUSBCFG |= (turnaround << GUSBCFG_TRDT_Pos); + } +} + + + +#ifdef __cplusplus +} +#endif + +#endif /* _DWC2_STM32_H_ */ diff --git a/src/tusb_option.h b/src/tusb_option.h index 89d83472b..d707c44c7 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -131,7 +131,7 @@ // Helper to check if configured MCU is one of listed // Apply _TU_CHECK_MCU with || as separator to list of input #define _TU_CHECK_MCU(_m) (CFG_TUSB_MCU == OPT_MCU_##_m) -#define TU_CHECK_MCU(...) TU_ARGS_APPLY(_TU_CHECK_MCU, ||, __VA_ARGS__) +#define TU_CHECK_MCU(...) (TU_ARGS_APPLY(_TU_CHECK_MCU, ||, __VA_ARGS__)) //--------------------------------------------------------------------+ // Supported OS From 85e18b9172b266f26ace35c825a9da0f3a32db0b Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 25 Oct 2021 15:58:12 +0700 Subject: [PATCH 17/51] house keeping --- src/portable/synopsys/dwc2/dcd_dwc2.c | 112 ++++++++++++++++---------- 1 file changed, 70 insertions(+), 42 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index c3773fb8b..fca5321f7 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -73,8 +73,6 @@ typedef struct { uint8_t interval; } xfer_ctl_t; -typedef volatile uint32_t * usb_fifo_t; - xfer_ctl_t xfer_status[DWC2_EP_MAX][2]; #define XFER_CTL_BASE(_ep, _dir) &xfer_status[_ep][_dir] @@ -586,7 +584,8 @@ bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t xfer->total_len = total_bytes; // EP0 can only handle one packet - if(epnum == 0) { + if(epnum == 0) + { ep0_pending[dir] = total_bytes; // Schedule the first transaction for EP0 transfer edpt_schedule_packets(rhport, epnum, dir, 1, ep0_pending[dir]); @@ -597,9 +596,7 @@ bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t uint16_t const short_packet_size = total_bytes % xfer->max_size; // Zero-size packet is special case. - if(short_packet_size > 0 || (total_bytes == 0)) { - num_packets++; - } + if ( short_packet_size > 0 || (total_bytes == 0) ) num_packets++; // Schedule packets to be sent within interrupt edpt_schedule_packets(rhport, epnum, dir, num_packets, total_bytes); @@ -628,7 +625,7 @@ bool dcd_edpt_xfer_fifo (uint8_t rhport, uint8_t ep_addr, tu_fifo_t * ff, uint16 uint16_t const short_packet_size = total_bytes % xfer->max_size; // Zero-size packet is special case. - if(short_packet_size > 0 || (total_bytes == 0)) num_packets++; + if ( short_packet_size > 0 || (total_bytes == 0) ) num_packets++; // Schedule packets to be sent within interrupt edpt_schedule_packets(rhport, epnum, dir, num_packets, total_bytes); @@ -648,40 +645,51 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const dir = tu_edpt_dir(ep_addr); - if(dir == TUSB_DIR_IN) { + if ( dir == TUSB_DIR_IN ) + { // Only disable currently enabled non-control endpoint - if ( (epnum == 0) || !(in_ep[epnum].DIEPCTL & DIEPCTL_EPENA) ){ + if ( (epnum == 0) || !(in_ep[epnum].DIEPCTL & DIEPCTL_EPENA) ) + { in_ep[epnum].DIEPCTL |= DIEPCTL_SNAK | (stall ? DIEPCTL_STALL : 0); - } else { + } + else + { // Stop transmitting packets and NAK IN xfers. in_ep[epnum].DIEPCTL |= DIEPCTL_SNAK; - while((in_ep[epnum].DIEPINT & DIEPINT_INEPNE) == 0); + while ( (in_ep[epnum].DIEPINT & DIEPINT_INEPNE) == 0 ) {} // Disable the endpoint. in_ep[epnum].DIEPCTL |= DIEPCTL_EPDIS | (stall ? DIEPCTL_STALL : 0); - while((in_ep[epnum].DIEPINT & DIEPINT_EPDISD_Msk) == 0); + while ( (in_ep[epnum].DIEPINT & DIEPINT_EPDISD_Msk) == 0 ) {} + in_ep[epnum].DIEPINT = DIEPINT_EPDISD; } // Flush the FIFO, and wait until we have confirmed it cleared. core->GRSTCTL |= (epnum << GRSTCTL_TXFNUM_Pos); core->GRSTCTL |= GRSTCTL_TXFFLSH; - while((core->GRSTCTL & GRSTCTL_TXFFLSH_Msk) != 0); - } else { + while ( (core->GRSTCTL & GRSTCTL_TXFFLSH_Msk) != 0 ) {} + } + else + { // Only disable currently enabled non-control endpoint - if ( (epnum == 0) || !(out_ep[epnum].DOEPCTL & DOEPCTL_EPENA) ){ + if ( (epnum == 0) || !(out_ep[epnum].DOEPCTL & DOEPCTL_EPENA) ) + { out_ep[epnum].DOEPCTL |= stall ? DOEPCTL_STALL : 0; - } else { + } + else + { // Asserting GONAK is required to STALL an OUT endpoint. // Simpler to use polling here, we don't use the "B"OUTNAKEFF interrupt // anyway, and it can't be cleared by user code. If this while loop never // finishes, we have bigger problems than just the stack. dev->DCTL |= DCTL_SGONAK; - while((core->GINTSTS & GINTSTS_BOUTNAKEFF_Msk) == 0); + while ( (core->GINTSTS & GINTSTS_BOUTNAKEFF_Msk) == 0 ) {} // Ditto here- disable the endpoint. out_ep[epnum].DOEPCTL |= DOEPCTL_EPDIS | (stall ? DOEPCTL_STALL : 0); - while((out_ep[epnum].DOEPINT & DOEPINT_EPDISD_Msk) == 0); + while ( (out_ep[epnum].DOEPINT & DOEPINT_EPDISD_Msk) == 0 ) {} + out_ep[epnum].DOEPINT = DOEPINT_EPDISD; // Allow other OUT endpoints to keep receiving. @@ -735,10 +743,13 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) uint8_t const dir = tu_edpt_dir(ep_addr); // Clear stall and reset data toggle - if(dir == TUSB_DIR_IN) { + if ( dir == TUSB_DIR_IN ) + { in_ep[epnum].DIEPCTL &= ~DIEPCTL_STALL; in_ep[epnum].DIEPCTL |= DIEPCTL_SD0PID_SEVNFRM; - } else { + } + else + { out_ep[epnum].DOEPCTL &= ~DOEPCTL_STALL; out_ep[epnum].DOEPCTL |= DOEPCTL_SD0PID_SEVNFRM; } @@ -751,11 +762,12 @@ static void read_fifo_packet(uint8_t rhport, uint8_t * dst, uint16_t len) { (void) rhport; - usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); + volatile uint32_t * rx_fifo = FIFO_BASE(rhport, 0); // Reading full available 32 bit words from fifo uint16_t full_words = len >> 2; - for(uint16_t i = 0; i < full_words; i++) { + for ( uint16_t i = 0; i < full_words; i++ ) + { uint32_t tmp = *rx_fifo; dst[0] = tmp & 0x000000FF; dst[1] = (tmp & 0x0000FF00) >> 8; @@ -766,13 +778,16 @@ static void read_fifo_packet(uint8_t rhport, uint8_t * dst, uint16_t len) // Read the remaining 1-3 bytes from fifo uint8_t bytes_rem = len & 0x03; - if(bytes_rem != 0) { + if ( bytes_rem != 0 ) + { uint32_t tmp = *rx_fifo; dst[0] = tmp & 0x000000FF; - if(bytes_rem > 1) { + if ( bytes_rem > 1 ) + { dst[1] = (tmp & 0x0000FF00) >> 8; } - if(bytes_rem > 2) { + if ( bytes_rem > 2 ) + { dst[2] = (tmp & 0x00FF0000) >> 16; } } @@ -783,24 +798,28 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, u { (void) rhport; - usb_fifo_t tx_fifo = FIFO_BASE(rhport, fifo_num); + volatile uint32_t * tx_fifo = FIFO_BASE(rhport, fifo_num); // Pushing full available 32 bit words to fifo uint16_t full_words = len >> 2; - for(uint16_t i = 0; i < full_words; i++){ + for ( uint16_t i = 0; i < full_words; i++ ) + { *tx_fifo = (src[3] << 24) | (src[2] << 16) | (src[1] << 8) | src[0]; src += 4; } // Write the remaining 1-3 bytes into fifo uint8_t bytes_rem = len & 0x03; - if(bytes_rem){ + if ( bytes_rem ) + { uint32_t tmp_word = 0; tmp_word |= src[0]; - if(bytes_rem > 1){ + if ( bytes_rem > 1 ) + { tmp_word |= src[1] << 8; } - if(bytes_rem > 2){ + if ( bytes_rem > 2 ) + { tmp_word |= src[2] << 16; } *tx_fifo = tmp_word; @@ -809,7 +828,7 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, u static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { dwc2_core_t * core = CORE_REG(rhport); - usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); + volatile uint32_t * rx_fifo = FIFO_BASE(rhport, 0); // Pop control word off FIFO uint32_t ctl_word = core->GRXSTSP; @@ -817,7 +836,8 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { uint8_t epnum = (ctl_word & GRXSTSP_EPNUM_Msk) >> GRXSTSP_EPNUM_Pos; uint16_t bcnt = (ctl_word & GRXSTSP_BCNT_Msk) >> GRXSTSP_BCNT_Pos; - switch(pktsts) { + switch(pktsts) + { case 0x01: // Global OUT NAK (Interrupt) break; @@ -871,28 +891,36 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { } } -static void handle_epout_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epout_t * out_ep) { +static void handle_epout_ints (uint8_t rhport, dwc2_device_t *dev, dwc2_epout_t *out_ep) +{ // DAINT for a given EP clears when DOEPINTx is cleared. // OEPINT will be cleared when DAINT's out bits are cleared. - for(uint8_t n = 0; n < DWC2_EP_MAX; n++) { - xfer_ctl_t * xfer = XFER_CTL_BASE(n, TUSB_DIR_OUT); + for ( uint8_t n = 0; n < DWC2_EP_MAX; n++ ) + { + xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_OUT); - if(dev->DAINT & (1 << (DAINT_OEPINT_Pos + n))) { + if ( dev->DAINT & (1 << (DAINT_OEPINT_Pos + n)) ) + { // SETUP packet Setup Phase done. - if(out_ep[n].DOEPINT & DOEPINT_STUP) { - out_ep[n].DOEPINT = DOEPINT_STUP; + if ( out_ep[n].DOEPINT & DOEPINT_STUP ) + { + out_ep[n].DOEPINT = DOEPINT_STUP; dcd_event_setup_received(rhport, (uint8_t*) &_setup_packet[0], true); } // OUT XFER complete - if(out_ep[n].DOEPINT & DOEPINT_XFRC) { + if ( out_ep[n].DOEPINT & DOEPINT_XFRC ) + { out_ep[n].DOEPINT = DOEPINT_XFRC; // EP0 can only handle one packet - if((n == 0) && ep0_pending[TUSB_DIR_OUT]) { + if ( (n == 0) && ep0_pending[TUSB_DIR_OUT] ) + { // Schedule another packet to be received. edpt_schedule_packets(rhport, n, TUSB_DIR_OUT, 1, ep0_pending[TUSB_DIR_OUT]); - } else { + } + else + { dcd_event_xfer_complete(rhport, n, xfer->total_len, XFER_RESULT_SUCCESS, true); } } @@ -948,7 +976,7 @@ static void handle_epin_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epin_t * // Push packet to Tx-FIFO if (xfer->ff) { - usb_fifo_t tx_fifo = FIFO_BASE(rhport, n); + volatile uint32_t * tx_fifo = FIFO_BASE(rhport, n); tu_fifo_read_n_const_addr_full_words(xfer->ff, (void *)(uintptr_t) tx_fifo, packet_size); } else From dbd31895bc234ff6d76d3fe736dc613890ab7acb Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 25 Oct 2021 17:04:03 +0700 Subject: [PATCH 18/51] change usage of TU_CHECK_MCU() to prevent macro conflict --- .../audio_4_channel_mic/src/usb_descriptors.c | 12 +-- .../device/audio_test/src/usb_descriptors.c | 2 +- examples/device/cdc_msc_freertos/src/main.c | 6 +- .../device/cdc_msc_freertos/src/tusb_config.h | 2 +- .../device/hid_composite_freertos/src/main.c | 6 +- .../hid_composite_freertos/src/tusb_config.h | 2 +- .../video_capture/src/usb_descriptors.c | 4 +- src/class/msc/msc_device.c | 2 +- src/common/tusb_compiler.h | 2 +- src/device/dcd_attr.h | 73 +++++++++---------- src/host/hcd_attr.h | 46 ++++++------ src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c | 11 +-- src/portable/synopsys/dwc2/dcd_dwc2.c | 6 +- src/tusb_option.h | 2 +- 14 files changed, 85 insertions(+), 91 deletions(-) diff --git a/examples/device/audio_4_channel_mic/src/usb_descriptors.c b/examples/device/audio_4_channel_mic/src/usb_descriptors.c index b6a5bd5c2..93ae2ea47 100644 --- a/examples/device/audio_4_channel_mic/src/usb_descriptors.c +++ b/examples/device/audio_4_channel_mic/src/usb_descriptors.c @@ -81,12 +81,12 @@ enum #define CONFIG_TOTAL_LEN (TUD_CONFIG_DESC_LEN + CFG_TUD_AUDIO * TUD_AUDIO_MIC_FOUR_CH_DESC_LEN) -#if TU_CHECK_MCU(LPC175X_6X) || TU_CHECK_MCU(LPC177X_8X) || TU_CHECK_MCU(LPC40XX) +#if TU_CHECK_MCU(OPT_MCU_LPC175X_6X, OPT_MCU_LPC177X_8X, OPT_MCU_LPC40XX) // LPC 17xx and 40xx endpoint type (bulk/interrupt/iso) are fixed by its number // 0 control, 1 In, 2 Bulk, 3 Iso, 4 In etc ... #define EPNUM_AUDIO 0x03 -#elif TU_CHECK_MCU(NRF5X) +#elif TU_CHECK_MCU(OPT_MCU_NRF5X) // nRF5x ISO can only be endpoint 8 #define EPNUM_AUDIO 0x08 @@ -96,11 +96,11 @@ enum uint8_t const desc_configuration[] = { - // Interface count, string index, total length, attribute, power in mA - TUD_CONFIG_DESCRIPTOR(1, ITF_NUM_TOTAL, 0, CONFIG_TOTAL_LEN, 0x00, 100), + // Interface count, string index, total length, attribute, power in mA + TUD_CONFIG_DESCRIPTOR(1, ITF_NUM_TOTAL, 0, CONFIG_TOTAL_LEN, 0x00, 100), - // Interface number, string index, EP Out & EP In address, EP size - TUD_AUDIO_MIC_FOUR_CH_DESCRIPTOR(/*_itfnum*/ ITF_NUM_AUDIO_CONTROL, /*_stridx*/ 0, /*_nBytesPerSample*/ CFG_TUD_AUDIO_FUNC_1_N_BYTES_PER_SAMPLE_TX, /*_nBitsUsedPerSample*/ CFG_TUD_AUDIO_FUNC_1_N_BYTES_PER_SAMPLE_TX*8, /*_epin*/ 0x80 | EPNUM_AUDIO, /*_epsize*/ CFG_TUD_AUDIO_EP_SZ_IN) + // Interface number, string index, EP Out & EP In address, EP size + TUD_AUDIO_MIC_FOUR_CH_DESCRIPTOR(/*_itfnum*/ ITF_NUM_AUDIO_CONTROL, /*_stridx*/ 0, /*_nBytesPerSample*/ CFG_TUD_AUDIO_FUNC_1_N_BYTES_PER_SAMPLE_TX, /*_nBitsUsedPerSample*/ CFG_TUD_AUDIO_FUNC_1_N_BYTES_PER_SAMPLE_TX*8, /*_epin*/ 0x80 | EPNUM_AUDIO, /*_epsize*/ CFG_TUD_AUDIO_EP_SZ_IN) }; // Invoked when received GET CONFIGURATION DESCRIPTOR diff --git a/examples/device/audio_test/src/usb_descriptors.c b/examples/device/audio_test/src/usb_descriptors.c index 348f5eede..09b2a2d45 100644 --- a/examples/device/audio_test/src/usb_descriptors.c +++ b/examples/device/audio_test/src/usb_descriptors.c @@ -86,7 +86,7 @@ enum // 0 control, 1 In, 2 Bulk, 3 Iso, 4 In etc ... #define EPNUM_AUDIO 0x03 -#elif TU_CHECK_MCU(NRF5X) +#elif TU_CHECK_MCU(OPT_MCU_NRF5X) // nRF5x ISO can only be endpoint 8 #define EPNUM_AUDIO 0x08 diff --git a/examples/device/cdc_msc_freertos/src/main.c b/examples/device/cdc_msc_freertos/src/main.c index 65b7fda3b..2d3426f1d 100644 --- a/examples/device/cdc_msc_freertos/src/main.c +++ b/examples/device/cdc_msc_freertos/src/main.c @@ -30,7 +30,7 @@ #include "bsp/board.h" #include "tusb.h" -#if TU_CHECK_MCU(ESP32S2) || TU_CHECK_MCU(ESP32S3) +#if TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3) // ESP-IDF need "freertos/" prefix in include path. // CFG_TUSB_OS_INC_PATH should be defined accordingly. #include "freertos/FreeRTOS.h" @@ -105,14 +105,14 @@ int main(void) (void) xTaskCreateStatic( cdc_task, "cdc", CDC_STACK_SZIE, NULL, configMAX_PRIORITIES-2, cdc_stack, &cdc_taskdef); // skip starting scheduler (and return) for ESP32-S2 or ESP32-S3 -#if !( TU_CHECK_MCU(ESP32S2) || TU_CHECK_MCU(ESP32S3) ) +#if !TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3) vTaskStartScheduler(); #endif return 0; } -#if CFG_TUSB_MCU == OPT_MCU_ESP32S2 || CFG_TUSB_MCU == OPT_MCU_ESP32S3 +#if TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3) void app_main(void) { main(); diff --git a/examples/device/cdc_msc_freertos/src/tusb_config.h b/examples/device/cdc_msc_freertos/src/tusb_config.h index d4bbdee48..55e84c62d 100644 --- a/examples/device/cdc_msc_freertos/src/tusb_config.h +++ b/examples/device/cdc_msc_freertos/src/tusb_config.h @@ -68,7 +68,7 @@ #define CFG_TUSB_OS OPT_OS_FREERTOS // Espressif IDF requires "freertos/" prefix in include path -#if TU_CHECK_MCU(ESP32S2) || TU_CHECK_MCU(ESP32S3) +#if TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3) #define CFG_TUSB_OS_INC_PATH freertos/ #endif diff --git a/examples/device/hid_composite_freertos/src/main.c b/examples/device/hid_composite_freertos/src/main.c index b25c71f64..336f5d426 100644 --- a/examples/device/hid_composite_freertos/src/main.c +++ b/examples/device/hid_composite_freertos/src/main.c @@ -31,7 +31,7 @@ #include "tusb.h" #include "usb_descriptors.h" -#if TU_CHECK_MCU(ESP32S2) || TU_CHECK_MCU(ESP32S3) +#if TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3) // ESP-IDF need "freertos/" prefix in include path. // CFG_TUSB_OS_INC_PATH should be defined accordingly. #include "freertos/FreeRTOS.h" @@ -105,14 +105,14 @@ int main(void) (void) xTaskCreateStatic( hid_task, "hid", HID_STACK_SZIE, NULL, configMAX_PRIORITIES-2, hid_stack, &hid_taskdef); // skip starting scheduler (and return) for ESP32-S2 or ESP32-S3 -#if !( TU_CHECK_MCU(ESP32S2) || TU_CHECK_MCU(ESP32S3) ) +#if !TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3) vTaskStartScheduler(); #endif return 0; } -#if CFG_TUSB_MCU == OPT_MCU_ESP32S2 || CFG_TUSB_MCU == OPT_MCU_ESP32S3 +#if TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3) void app_main(void) { main(); diff --git a/examples/device/hid_composite_freertos/src/tusb_config.h b/examples/device/hid_composite_freertos/src/tusb_config.h index b061dce3f..062f32ac3 100644 --- a/examples/device/hid_composite_freertos/src/tusb_config.h +++ b/examples/device/hid_composite_freertos/src/tusb_config.h @@ -68,7 +68,7 @@ #define CFG_TUSB_OS OPT_OS_FREERTOS // Espressif IDF requires "freertos/" prefix in include path -#if TU_CHECK_MCU(ESP32S2) || TU_CHECK_MCU(ESP32S3) +#if TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3) #define CFG_TUSB_OS_INC_PATH freertos/ #endif diff --git a/examples/device/video_capture/src/usb_descriptors.c b/examples/device/video_capture/src/usb_descriptors.c index 404ffe070..da8ec8e89 100644 --- a/examples/device/video_capture/src/usb_descriptors.c +++ b/examples/device/video_capture/src/usb_descriptors.c @@ -77,12 +77,12 @@ uint8_t const * tud_descriptor_device_cb(void) #define CONFIG_TOTAL_LEN (TUD_CONFIG_DESC_LEN + TUD_VIDEO_CAPTURE_DESC_LEN) -#if TU_CHECK_MCU(LPC175X_6X) || TU_CHECK_MCU(LPC177X_8X) || TU_CHECK_MCU(LPC40XX) +#if TU_CHECK_MCU(OPT_MCU_LPC175X_6X, OPT_MCU_LPC177X_8X, OPT_MCU_LPC40XX) // LPC 17xx and 40xx endpoint type (bulk/interrupt/iso) are fixed by its number // 0 control, 1 In, 2 Bulk, 3 Iso, 4 In, 5 Bulk etc ... #define EPNUM_VIDEO_IN 0x83 -#elif TU_CHECK_MCU(NRF5X) +#elif TU_CHECK_MCU(OPT_MCU_NRF5X) // nRF5x ISO can only be endpoint 8 #define EPNUM_VIDEO_IN 0x88 diff --git a/src/class/msc/msc_device.c b/src/class/msc/msc_device.c index 81522be46..dd490dd68 100644 --- a/src/class/msc/msc_device.c +++ b/src/class/msc/msc_device.c @@ -617,7 +617,7 @@ bool mscd_xfer_cb(uint8_t rhport, uint8_t ep_addr, xfer_result_t event, uint32_t } } - #if TU_CHECK_MCU(CXD56) + #if TU_CHECK_MCU(OPT_MCU_CXD56) // WORKAROUND: cxd56 has its own nuttx usb stack which does not forward Set/ClearFeature(Endpoint) to DCD. // There is no way for us to know when EP is un-stall, therefore we will unconditionally un-stall here and // hope everything will work diff --git a/src/common/tusb_compiler.h b/src/common/tusb_compiler.h index b0999b5d9..d3284c62a 100644 --- a/src/common/tusb_compiler.h +++ b/src/common/tusb_compiler.h @@ -69,7 +69,7 @@ /*------------------------------------------------------------------*/ /* Count number of arguments of __VA_ARGS__ - * - reference https://groups.google.com/forum/#!topic/comp.std.c/d-6Mj5Lko_s + * - reference https://stackoverflow.com/questions/2124339/c-preprocessor-va-args-number-of-arguments * - _GET_NTH_ARG() takes args >= N (64) but only expand to Nth one (64th) * - _RSEQ_N() is reverse sequential to N to add padding to have * Nth position is the same as the number of arguments diff --git a/src/device/dcd_attr.h b/src/device/dcd_attr.h index ddec481a8..54627eaa0 100644 --- a/src/device/dcd_attr.h +++ b/src/device/dcd_attr.h @@ -36,59 +36,59 @@ // - PORT_HIGHSPEED: mask to indicate which port support highspeed mode, bit0 for port0 and so on. //------------- NXP -------------// -#if TU_CHECK_MCU(LPC11UXX, LPC13XX, LPC15XX) +#if TU_CHECK_MCU(OPT_MCU_LPC11UXX, OPT_MCU_LPC13XX, OPT_MCU_LPC15XX) #define DCD_ATTR_ENDPOINT_MAX 5 -#elif TU_CHECK_MCU(LPC175X_6X, LPC177X_8X, LPC40XX) +#elif TU_CHECK_MCU(OPT_MCU_LPC175X_6X, OPT_MCU_LPC177X_8X, OPT_MCU_LPC40XX) #define DCD_ATTR_ENDPOINT_MAX 16 -#elif TU_CHECK_MCU(LPC18XX, LPC43XX) +#elif TU_CHECK_MCU(OPT_MCU_LPC18XX, OPT_MCU_LPC43XX) // TODO USB0 has 6, USB1 has 4 #define DCD_ATTR_ENDPOINT_MAX 6 -#elif TU_CHECK_MCU(LPC51UXX) +#elif TU_CHECK_MCU(OPT_MCU_LPC51UXX) #define DCD_ATTR_ENDPOINT_MAX 5 -#elif TU_CHECK_MCU(LPC54XXX) +#elif TU_CHECK_MCU(OPT_MCU_LPC54XXX) // TODO USB0 has 5, USB1 has 6 #define DCD_ATTR_ENDPOINT_MAX 6 -#elif TU_CHECK_MCU(LPC55XX) +#elif TU_CHECK_MCU(OPT_MCU_LPC55XX) // TODO USB0 has 5, USB1 has 6 #define DCD_ATTR_ENDPOINT_MAX 6 -#elif TU_CHECK_MCU(MIMXRT10XX) +#elif TU_CHECK_MCU(OPT_MCU_MIMXRT10XX) #define DCD_ATTR_ENDPOINT_MAX 8 -#elif TU_CHECK_MCU(MKL25ZXX, K32L2BXX) +#elif TU_CHECK_MCU(OPT_MCU_MKL25ZXX, OPT_MCU_K32L2BXX) #define DCD_ATTR_ENDPOINT_MAX 16 -#elif TU_CHECK_MCU(MM32F327X) +#elif TU_CHECK_MCU(OPT_MCU_MM32F327X) #define DCD_ATTR_ENDPOINT_MAX 16 //------------- Nordic -------------// -#elif TU_CHECK_MCU(NRF5X) +#elif TU_CHECK_MCU(OPT_MCU_NRF5X) // 8 CBI + 1 ISO #define DCD_ATTR_ENDPOINT_MAX 9 //------------- Microchip -------------// -#elif TU_CHECK_MCU(SAMD21, SAMD51, SAME5X) || \ - TU_CHECK_MCU(SAMD11, SAML21, SAML22) +#elif TU_CHECK_MCU(OPT_MCU_SAMD21, OPT_MCU_SAMD51, OPT_MCU_SAME5X) || \ + TU_CHECK_MCU(OPT_MCU_SAMD11, OPT_MCU_SAML21, OPT_MCU_SAML22) #define DCD_ATTR_ENDPOINT_MAX 8 -#elif TU_CHECK_MCU(SAMG) +#elif TU_CHECK_MCU(OPT_MCU_SAMG) #define DCD_ATTR_ENDPOINT_MAX 6 #define DCD_ATTR_ENDPOINT_EXCLUSIVE_NUMBER -#elif TU_CHECK_MCU(SAMX7X) +#elif TU_CHECK_MCU(OPT_MCU_SAMX7X) #define DCD_ATTR_ENDPOINT_MAX 10 #define DCD_ATTR_ENDPOINT_EXCLUSIVE_NUMBER //------------- ST -------------// -#elif TU_CHECK_MCU(STM32F0) +#elif TU_CHECK_MCU(OPT_MCU_STM32F0) #define DCD_ATTR_ENDPOINT_MAX 8 -#elif TU_CHECK_MCU(STM32F1) +#elif TU_CHECK_MCU(OPT_MCU_STM32F1) #if defined (STM32F105x8) || defined (STM32F105xB) || defined (STM32F105xC) || \ defined (STM32F107xB) || defined (STM32F107xC) #define DCD_ATTR_ENDPOINT_MAX 4 @@ -97,32 +97,32 @@ #define DCD_ATTR_ENDPOINT_MAX 8 #endif -#elif TU_CHECK_MCU(STM32F2) +#elif TU_CHECK_MCU(OPT_MCU_STM32F2) // FS has 4 ep, HS has 5 ep #define DCD_ATTR_ENDPOINT_MAX 6 #define DCD_ATTR_DWC2_STM32 -#elif TU_CHECK_MCU(STM32F3) +#elif TU_CHECK_MCU(OPT_MCU_STM32F3) #define DCD_ATTR_ENDPOINT_MAX 8 -#elif TU_CHECK_MCU(STM32F4) +#elif TU_CHECK_MCU(OPT_MCU_STM32F4) // For most mcu, FS has 4, HS has 6. TODO 446/469/479 HS has 9 #define DCD_ATTR_ENDPOINT_MAX 6 #define DCD_ATTR_DWC2_STM32 -#elif TU_CHECK_MCU(STM32F7) +#elif TU_CHECK_MCU(OPT_MCU_STM32F7) // FS has 6, HS has 9 #define DCD_ATTR_ENDPOINT_MAX 9 #define DCD_ATTR_DWC2_STM32 -#elif TU_CHECK_MCU(STM32H7) +#elif TU_CHECK_MCU(OPT_MCU_STM32H7) #define DCD_ATTR_ENDPOINT_MAX 9 #define DCD_ATTR_DWC2_STM32 -#elif TU_CHECK_MCU(STM32L0, STM32L1) +#elif TU_CHECK_MCU(OPT_MCU_STM32L0, OPT_MCU_STM32L1) #define DCD_ATTR_ENDPOINT_MAX 8 -#elif TU_CHECK_MCU(STM32L4) +#elif TU_CHECK_MCU(OPT_MCU_STM32L4) #if defined (STM32L475xx) || defined (STM32L476xx) || \ defined (STM32L485xx) || defined (STM32L486xx) || defined (STM32L496xx) || \ defined (STM32L4R5xx) || defined (STM32L4R7xx) || defined (STM32L4R9xx) || \ @@ -134,53 +134,50 @@ #endif //------------- Sony -------------// -#elif TU_CHECK_MCU(CXD56) +#elif TU_CHECK_MCU(OPT_MCU_CXD56) #define DCD_ATTR_ENDPOINT_MAX 7 #define DCD_ATTR_ENDPOINT_EXCLUSIVE_NUMBER //------------- TI -------------// -#elif TU_CHECK_MCU(MSP430x5xx) +#elif TU_CHECK_MCU(OPT_MCU_MSP430x5xx) #define DCD_ATTR_ENDPOINT_MAX 8 //------------- ValentyUSB -------------// -#elif TU_CHECK_MCU(VALENTYUSB_EPTRI) +#elif TU_CHECK_MCU(OPT_MCU_VALENTYUSB_EPTRI) #define DCD_ATTR_ENDPOINT_MAX 16 //------------- Nuvoton -------------// -#elif TU_CHECK_MCU(NUC121) || TU_CHECK_MCU(NUC126) +#elif TU_CHECK_MCU(OPT_MCU_NUC121, OPT_MCU_NUC126) #define DCD_ATTR_ENDPOINT_MAX 8 -#elif TU_CHECK_MCU(NUC120) +#elif TU_CHECK_MCU(OPT_MCU_NUC120) #define DCD_ATTR_ENDPOINT_MAX 6 -#elif TU_CHECK_MCU(NUC505) +#elif TU_CHECK_MCU(OPT_MCU_NUC505) #define DCD_ATTR_ENDPOINT_MAX 12 //------------- Espressif -------------// -#elif TU_CHECK_MCU(ESP32S2, ESP32S3) +#elif TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3) #define DCD_ATTR_ENDPOINT_MAX 6 //------------- Dialog -------------// -#elif TU_CHECK_MCU(DA1469X) +#elif TU_CHECK_MCU(OPT_MCU_DA1469X) #define DCD_ATTR_ENDPOINT_MAX 4 //------------- Raspberry Pi -------------// -#elif TU_CHECK_MCU(RP2040) +#elif TU_CHECK_MCU(OPT_MCU_RP2040) #define DCD_ATTR_ENDPOINT_MAX 16 //------------- Silabs -------------// -#elif TU_CHECK_MCU(EFM32GG) || TU_CHECK_MCU(EFM32GG11) || TU_CHECK_MCU(EFM32GG12) +#elif TU_CHECK_MCU(OPT_MCU_EFM32GG, OPT_MCU_EFM32GG11, OPT_MCU_EFM32GG12) #define DCD_ATTR_ENDPOINT_MAX 7 //------------- Renesas -------------// -#elif TU_CHECK_MCU(RX63X) || TU_CHECK_MCU(RX65X) || TU_CHECK_MCU(RX72N) +#elif TU_CHECK_MCU(OPT_MCU_RX63X, OPT_MCU_RX65X, OPT_MCU_RX72N) #define DCD_ATTR_ENDPOINT_MAX 10 -//#elif TU_CHECK_MCU(MM32F327X) -// #define DCD_ATTR_ENDPOINT_MAX not known yet - //------------- GigaDevice -------------// -#elif TU_CHECK_MCU(GD32VF103) +#elif TU_CHECK_MCU(OPT_MCU_GD32VF103) #define DCD_ATTR_ENDPOINT_MAX 4 #else diff --git a/src/host/hcd_attr.h b/src/host/hcd_attr.h index 729fc407b..a9bc242d7 100644 --- a/src/host/hcd_attr.h +++ b/src/host/hcd_attr.h @@ -34,64 +34,64 @@ // - PORT_HIGHSPEED: mask to indicate which port support highspeed mode, bit0 for port0 and so on. //------------- NXP -------------// -#if TU_CHECK_MCU(LPC175X_6X) || TU_CHECK_MCU(LPC177X_8X) || TU_CHECK_MCU(LPC40XX) +#if TU_CHECK_MCU(OPT_MCU_LPC175X_6X, OPT_MCU_LPC177X_8X, OPT_MCU_LPC40XX) #define HCD_ATTR_OHCI -#elif TU_CHECK_MCU(LPC18XX) || TU_CHECK_MCU(LPC43XX) +#elif TU_CHECK_MCU(OPT_MCU_LPC18XX, OPT_MCU_LPC43XX) #define HCD_ATTR_EHCI_TRANSDIMENSION -#elif TU_CHECK_MCU(LPC54XXX) +#elif TU_CHECK_MCU(OPT_MCU_LPC54XXX) // #define HCD_ATTR_EHCI_NXP_PTD -#elif TU_CHECK_MCU(LPC55XX) +#elif TU_CHECK_MCU(OPT_MCU_LPC55XX) // #define HCD_ATTR_EHCI_NXP_PTD -#elif TU_CHECK_MCU(MIMXRT10XX) +#elif TU_CHECK_MCU(OPT_MCU_MIMXRT10XX) #define HCD_ATTR_EHCI_TRANSDIMENSION -#elif TU_CHECK_MCU(MKL25ZXX) +#elif TU_CHECK_MCU(OPT_MCU_MKL25ZXX) //------------- Microchip -------------// -#elif TU_CHECK_MCU(SAMD21) || TU_CHECK_MCU(SAMD51) || TU_CHECK_MCU(SAME5X) || \ - TU_CHECK_MCU(SAMD11) || TU_CHECK_MCU(SAML21) || TU_CHECK_MCU(SAML22) +#elif TU_CHECK_MCU(OPT_MCU_SAMD21, OPT_MCU_SAMD51, OPT_MCU_SAME5X) || \ + TU_CHECK_MCU(OPT_MCU_SAMD11, OPT_MCU_SAML21, OPT_MCU_SAML22) -#elif TU_CHECK_MCU(SAMG) +#elif TU_CHECK_MCU(OPT_MCU_SAMG) -#elif TU_CHECK_MCU(SAMX7X) +#elif TU_CHECK_MCU(OPT_MCU_SAMX7X) //------------- ST -------------// -#elif TU_CHECK_MCU(STM32F0) || TU_CHECK_MCU(STM32F1) || TU_CHECK_MCU(STM32F3) || \ - TU_CHECK_MCU(STM32L0) || TU_CHECK_MCU(STM32L1) || TU_CHECK_MCU(STM32L4) +#elif TU_CHECK_MCU(OPT_MCU_STM32F0, OPT_MCU_STM32F1, OPT_MCU_STM32F3) || \ + TU_CHECK_MCU(OPT_MCU_STM32L0, OPT_MCU_STM32L1, OPT_MCU_STM32L4) -#elif TU_CHECK_MCU(STM32F2) || TU_CHECK_MCU(STM32F4) || TU_CHECK_MCU(STM32F3) +#elif TU_CHECK_MCU(OPT_MCU_STM32F2, OPT_MCU_STM32F3, OPT_MCU_STM32F4) -#elif TU_CHECK_MCU(STM32F7) +#elif TU_CHECK_MCU(OPT_MCU_STM32F7) -#elif TU_CHECK_MCU(STM32H7) +#elif TU_CHECK_MCU(OPT_MCU_STM32H7) //------------- Sony -------------// -#elif TU_CHECK_MCU(CXD56) +#elif TU_CHECK_MCU(OPT_MCU_CXD56) //------------- Nuvoton -------------// -#elif TU_CHECK_MCU(NUC505) +#elif TU_CHECK_MCU(OPT_MCU_NUC505) //------------- Espressif -------------// -#elif TU_CHECK_MCU(ESP32S2) || TU_CHECK_MCU(ESP32S3) +#elif TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3) //------------- Raspberry Pi -------------// -#elif TU_CHECK_MCU(RP2040) +#elif TU_CHECK_MCU(OPT_MCU_RP2040) //------------- Silabs -------------// -#elif TU_CHECK_MCU(EFM32GG) || TU_CHECK_MCU(EFM32GG11) || TU_CHECK_MCU(EFM32GG12) +#elif TU_CHECK_MCU(OPT_MCU_EFM32GG, OPT_MCU_EFM32GG11, OPT_MCU_EFM32GG12) //------------- Renesas -------------// -#elif TU_CHECK_MCU(RX63X) || TU_CHECK_MCU(RX65X) || TU_CHECK_MCU(RX72N) +#elif TU_CHECK_MCU(OPT_MCU_RX63X, OPT_MCU_RX65X, OPT_MCU_RX72N) -//#elif TU_CHECK_MCU(MM32F327X) +//#elif TU_CHECK_MCU(OPT_MCU_MM32F327X) // #define DCD_ATTR_ENDPOINT_MAX not known yet //------------- GigaDevice -------------// -#elif TU_CHECK_MCU(GD32VF103) +#elif TU_CHECK_MCU(OPT_MCU_GD32VF103) #else // #warning "DCD_ATTR_ENDPOINT_MAX is not defined for this MCU, default to 8" diff --git a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c index ca6564d46..933f352a2 100644 --- a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c +++ b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c @@ -109,13 +109,10 @@ #define STM32F1_FSDEV #endif -#if (TUSB_OPT_DEVICE_ENABLED) && ( \ - (CFG_TUSB_MCU == OPT_MCU_STM32F0 ) || \ - (CFG_TUSB_MCU == OPT_MCU_STM32F1 && defined(STM32F1_FSDEV)) || \ - (CFG_TUSB_MCU == OPT_MCU_STM32F3 ) || \ - (CFG_TUSB_MCU == OPT_MCU_STM32L0 ) || \ - (CFG_TUSB_MCU == OPT_MCU_STM32L1 ) \ - ) +#if TUSB_OPT_DEVICE_ENABLED && \ + ( TU_CHECK_MCU(OPT_MCU_STM32F0, OPT_MCU_STM32F3, OPT_MCU_STM32L0, OPT_MCU_STM32L1) || \ + (TU_CHECK_MCU(OPT_MCU_STM32F1) && defined(STM32F1_FSDEV)) \ + ) // In order to reduce the dependance on HAL, we undefine this. // Some definitions are copied to our private include file. diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index fca5321f7..7ae10652c 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -31,16 +31,16 @@ #include "device/dcd_attr.h" #if TUSB_OPT_DEVICE_ENABLED && \ - ( defined(DCD_ATTR_DWC2_STM32) || TU_CHECK_MCU(ESP32S2, ESP32S3, GD32VF103) ) + ( defined(DCD_ATTR_DWC2_STM32) || TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3, OPT_MCU_GD32VF103) ) #include "device/dcd.h" #include "dwc2_type.h" #if defined(DCD_ATTR_DWC2_STM32) #include "dwc2_stm32.h" -#elif TU_CHECK_MCU(ESP32S2, ESP32S3) +#elif TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3) #include "dwc2_esp32.h" -#elif TU_CHECK_MCU(GD32VF103) +#elif TU_CHECK_MCU(OPT_MCU_GD32VF103) #include "dwc2_gd32.h" #else #error "Unsupported MCUs" diff --git a/src/tusb_option.h b/src/tusb_option.h index d707c44c7..509ff4a3c 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -130,7 +130,7 @@ // Helper to check if configured MCU is one of listed // Apply _TU_CHECK_MCU with || as separator to list of input -#define _TU_CHECK_MCU(_m) (CFG_TUSB_MCU == OPT_MCU_##_m) +#define _TU_CHECK_MCU(_m) (CFG_TUSB_MCU == _m) #define TU_CHECK_MCU(...) (TU_ARGS_APPLY(_TU_CHECK_MCU, ||, __VA_ARGS__)) //--------------------------------------------------------------------+ From 460052c8a0b21d715a8206149f8106de0c5c38aa Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 25 Oct 2021 21:20:58 +0700 Subject: [PATCH 19/51] spacing --- src/portable/synopsys/dwc2/dwc2_gd32.h | 2 - src/portable/synopsys/dwc2/dwc2_type.h | 1979 ++++++++++++------------ 2 files changed, 983 insertions(+), 998 deletions(-) diff --git a/src/portable/synopsys/dwc2/dwc2_gd32.h b/src/portable/synopsys/dwc2/dwc2_gd32.h index 1ad066720..db1fb89fd 100644 --- a/src/portable/synopsys/dwc2/dwc2_gd32.h +++ b/src/portable/synopsys/dwc2/dwc2_gd32.h @@ -32,8 +32,6 @@ extern "C" { #endif - -// These numbers are the same for the whole GD32VF103 family. #define DWC2_REG_BASE 0x50000000UL #define DWC2_EP_MAX 4 #define DWC2_EP_FIFO_SIZE 1280 diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 5f3b4a420..8d12e21ce 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -23,136 +23,124 @@ extern "C" { #endif -#ifdef __cplusplus - #define __I volatile -#else - #define __I volatile const -#endif -#define __O volatile -#define __IO volatile -#define __IM volatile const -#define __OM volatile -#define __IOM volatile - #if 0 // HS PHY typedef struct { - -__IO uint32_t HS_PHYC_PLL; /*!< This register is used to control the PLL of the HS PHY. 000h */ -__IO uint32_t Reserved04; /*!< Reserved 004h */ -__IO uint32_t Reserved08; /*!< Reserved 008h */ -__IO uint32_t HS_PHYC_TUNE; /*!< This register is used to control the tuning interface of the High Speed PHY. 00Ch */ -__IO uint32_t Reserved10; /*!< Reserved 010h */ -__IO uint32_t Reserved14; /*!< Reserved 014h */ -__IO uint32_t HS_PHYC_LDO; /*!< This register is used to control the regulator (LDO). 018h */ + volatile uint32_t HS_PHYC_PLL; /*!< This register is used to control the PLL of the HS PHY. 000h */ + volatile uint32_t Reserved04; /*!< Reserved 004h */ + volatile uint32_t Reserved08; /*!< Reserved 008h */ + volatile uint32_t HS_PHYC_TUNE; /*!< This register is used to control the tuning interface of the High Speed PHY. 00Ch */ + volatile uint32_t Reserved10; /*!< Reserved 010h */ + volatile uint32_t Reserved14; /*!< Reserved 014h */ + volatile uint32_t HS_PHYC_LDO; /*!< This register is used to control the regulator (LDO). 018h */ } HS_PHYC_GlobalTypeDef; #endif // Core typedef struct { - __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ - __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ - __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ - __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ - __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h */ - __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ - __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ - __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ - __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ - __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ - __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ - __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ - uint32_t Reserved30[2]; /*!< Reserved 030h */ - __IO uint32_t GCCFG; /*!< General Purpose IO Register 038h */ - __IO uint32_t CID; /*!< User ID Register 03Ch */ - __IO uint32_t GSNPSID; /* USB_OTG core ID 040h*/ - __IO uint32_t GHWCFG1; /* User HW config1 044h*/ - __IO uint32_t GHWCFG2; /* User HW config2 048h*/ - __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ - uint32_t Reserved6; /*!< Reserved 050h */ - __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ - __IO uint32_t GPWRDN; /*!< Power Down Register 058h */ - __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ - __IO uint32_t GADPCTL; /*!< ADP Timer, Control and Status Register 60Ch */ - uint32_t Reserved43[39]; /*!< Reserved 058h-0FFh */ - __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ - __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO 104h-13Ch */ + volatile uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ + volatile uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ + volatile uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ + volatile uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ + volatile uint32_t GRSTCTL; /*!< Core Reset Register 010h */ + volatile uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ + volatile uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ + volatile uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ + volatile uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ + volatile uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ + volatile uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ + volatile uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ + uint32_t Reserved30[2]; /*!< Reserved 030h */ + volatile uint32_t GCCFG; /*!< General Purpose IO Register 038h */ + volatile uint32_t CID; /*!< User ID Register 03Ch */ + volatile uint32_t GSNPSID; /* USB_OTG core ID 040h*/ + volatile uint32_t GHWCFG1; /* User HW config1 044h*/ + volatile uint32_t GHWCFG2; /* User HW config2 048h*/ + volatile uint32_t GHWCFG3; /*!< User HW config3 04Ch */ + uint32_t Reserved6; /*!< Reserved 050h */ + volatile uint32_t GLPMCFG; /*!< LPM Register 054h */ + volatile uint32_t GPWRDN; /*!< Power Down Register 058h */ + volatile uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ + volatile uint32_t GADPCTL; /*!< ADP Timer, Control and Status Register 60Ch */ + uint32_t Reserved43[39]; /*!< Reserved 058h-0FFh */ + volatile uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ + volatile uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO 104h-13Ch */ } dwc2_core_t; // Host typedef struct { - __IO uint32_t HCFG; /*!< Host Configuration Register 400h */ - __IO uint32_t HFIR; /*!< Host Frame Interval Register 404h */ - __IO uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ - uint32_t Reserved40C; /*!< Reserved 40Ch */ - __IO uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ - __IO uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ - __IO uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ + volatile uint32_t HCFG; /*!< Host Configuration Register 400h */ + volatile uint32_t HFIR; /*!< Host Frame Interval Register 404h */ + volatile uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ + uint32_t Reserved40C; /*!< Reserved 40Ch */ + volatile uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ + volatile uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ + volatile uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ } dwc2_host_t; // Host Channel typedef struct { - __IO uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ - __IO uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ - __IO uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ - __IO uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ - __IO uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ - __IO uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ - uint32_t Reserved[2]; /*!< Reserved */ + volatile uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ + volatile uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ + volatile uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ + volatile uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ + volatile uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ + volatile uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ + uint32_t Reserved[2]; /*!< Reserved */ } dwc2_channel_t; // Device typedef struct { - __IO uint32_t DCFG; /*!< dev Configuration Register 800h */ - __IO uint32_t DCTL; /*!< dev Control Register 804h */ - __IO uint32_t DSTS; /*!< dev Status Register (RO) 808h */ - uint32_t Reserved0C; /*!< Reserved 80Ch */ - __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ - __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ - __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ - __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ - uint32_t Reserved20; /*!< Reserved 820h */ - uint32_t Reserved9; /*!< Reserved 824h */ - __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ - __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ - __IO uint32_t DTHRCTL; /*!< dev threshold 830h */ - __IO uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ - __IO uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ - __IO uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ - uint32_t Reserved40; /*!< dedicated EP mask 840h */ - __IO uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ - uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ - __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ + volatile uint32_t DCFG; /*!< dev Configuration Register 800h */ + volatile uint32_t DCTL; /*!< dev Control Register 804h */ + volatile uint32_t DSTS; /*!< dev Status Register (RO) 808h */ + uint32_t Reserved0C; /*!< Reserved 80Ch */ + volatile uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ + volatile uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ + volatile uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ + volatile uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ + uint32_t Reserved20; /*!< Reserved 820h */ + uint32_t Reserved9; /*!< Reserved 824h */ + volatile uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ + volatile uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ + volatile uint32_t DTHRCTL; /*!< dev threshold 830h */ + volatile uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ + volatile uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ + volatile uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ + uint32_t Reserved40; /*!< dedicated EP mask 840h */ + volatile uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ + uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ + volatile uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ } dwc2_device_t; // Endpoint IN typedef struct { - __IO uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ - __IO uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - __IO uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - __IO uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ + volatile uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ + uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ + volatile uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ + uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ + volatile uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ + volatile uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ + volatile uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ + uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ } dwc2_epin_t; // Endpoint OUT typedef struct { - __IO uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ - __IO uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ - __IO uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ - uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ + volatile uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ + uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ + volatile uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ + uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ + volatile uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ + volatile uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ + uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ } dwc2_epout_t; @@ -179,1411 +167,1410 @@ typedef struct /******************** Bit definition for GOTGCTL register ********************/ #define GOTGCTL_SRQSCS_Pos (0U) -#define GOTGCTL_SRQSCS_Msk (0x1UL << GOTGCTL_SRQSCS_Pos) /*!< 0x00000001 */ -#define GOTGCTL_SRQSCS GOTGCTL_SRQSCS_Msk /*!< Session request success */ +#define GOTGCTL_SRQSCS_Msk (0x1UL << GOTGCTL_SRQSCS_Pos) /*!< 0x00000001 */ +#define GOTGCTL_SRQSCS GOTGCTL_SRQSCS_Msk /*!< Session request success */ #define GOTGCTL_SRQ_Pos (1U) -#define GOTGCTL_SRQ_Msk (0x1UL << GOTGCTL_SRQ_Pos) /*!< 0x00000002 */ -#define GOTGCTL_SRQ GOTGCTL_SRQ_Msk /*!< Session request */ +#define GOTGCTL_SRQ_Msk (0x1UL << GOTGCTL_SRQ_Pos) /*!< 0x00000002 */ +#define GOTGCTL_SRQ GOTGCTL_SRQ_Msk /*!< Session request */ #define GOTGCTL_VBVALOEN_Pos (2U) -#define GOTGCTL_VBVALOEN_Msk (0x1UL << GOTGCTL_VBVALOEN_Pos) /*!< 0x00000004 */ -#define GOTGCTL_VBVALOEN GOTGCTL_VBVALOEN_Msk /*!< VBUS valid override enable */ +#define GOTGCTL_VBVALOEN_Msk (0x1UL << GOTGCTL_VBVALOEN_Pos) /*!< 0x00000004 */ +#define GOTGCTL_VBVALOEN GOTGCTL_VBVALOEN_Msk /*!< VBUS valid override enable */ #define GOTGCTL_VBVALOVAL_Pos (3U) -#define GOTGCTL_VBVALOVAL_Msk (0x1UL << GOTGCTL_VBVALOVAL_Pos) /*!< 0x00000008 */ -#define GOTGCTL_VBVALOVAL GOTGCTL_VBVALOVAL_Msk /*!< VBUS valid override value */ +#define GOTGCTL_VBVALOVAL_Msk (0x1UL << GOTGCTL_VBVALOVAL_Pos) /*!< 0x00000008 */ +#define GOTGCTL_VBVALOVAL GOTGCTL_VBVALOVAL_Msk /*!< VBUS valid override value */ #define GOTGCTL_AVALOEN_Pos (4U) -#define GOTGCTL_AVALOEN_Msk (0x1UL << GOTGCTL_AVALOEN_Pos) /*!< 0x00000010 */ -#define GOTGCTL_AVALOEN GOTGCTL_AVALOEN_Msk /*!< A-peripheral session valid override enable */ +#define GOTGCTL_AVALOEN_Msk (0x1UL << GOTGCTL_AVALOEN_Pos) /*!< 0x00000010 */ +#define GOTGCTL_AVALOEN GOTGCTL_AVALOEN_Msk /*!< A-peripheral session valid override enable */ #define GOTGCTL_AVALOVAL_Pos (5U) -#define GOTGCTL_AVALOVAL_Msk (0x1UL << GOTGCTL_AVALOVAL_Pos) /*!< 0x00000020 */ -#define GOTGCTL_AVALOVAL GOTGCTL_AVALOVAL_Msk /*!< A-peripheral session valid override value */ +#define GOTGCTL_AVALOVAL_Msk (0x1UL << GOTGCTL_AVALOVAL_Pos) /*!< 0x00000020 */ +#define GOTGCTL_AVALOVAL GOTGCTL_AVALOVAL_Msk /*!< A-peripheral session valid override value */ #define GOTGCTL_BVALOEN_Pos (6U) -#define GOTGCTL_BVALOEN_Msk (0x1UL << GOTGCTL_BVALOEN_Pos) /*!< 0x00000040 */ -#define GOTGCTL_BVALOEN GOTGCTL_BVALOEN_Msk /*!< B-peripheral session valid override enable */ +#define GOTGCTL_BVALOEN_Msk (0x1UL << GOTGCTL_BVALOEN_Pos) /*!< 0x00000040 */ +#define GOTGCTL_BVALOEN GOTGCTL_BVALOEN_Msk /*!< B-peripheral session valid override enable */ #define GOTGCTL_BVALOVAL_Pos (7U) -#define GOTGCTL_BVALOVAL_Msk (0x1UL << GOTGCTL_BVALOVAL_Pos) /*!< 0x00000080 */ -#define GOTGCTL_BVALOVAL GOTGCTL_BVALOVAL_Msk /*!< B-peripheral session valid override value */ +#define GOTGCTL_BVALOVAL_Msk (0x1UL << GOTGCTL_BVALOVAL_Pos) /*!< 0x00000080 */ +#define GOTGCTL_BVALOVAL GOTGCTL_BVALOVAL_Msk /*!< B-peripheral session valid override value */ #define GOTGCTL_HNGSCS_Pos (8U) -#define GOTGCTL_HNGSCS_Msk (0x1UL << GOTGCTL_HNGSCS_Pos) /*!< 0x00000100 */ -#define GOTGCTL_HNGSCS GOTGCTL_HNGSCS_Msk /*!< Host set HNP enable */ +#define GOTGCTL_HNGSCS_Msk (0x1UL << GOTGCTL_HNGSCS_Pos) /*!< 0x00000100 */ +#define GOTGCTL_HNGSCS GOTGCTL_HNGSCS_Msk /*!< Host set HNP enable */ #define GOTGCTL_HNPRQ_Pos (9U) -#define GOTGCTL_HNPRQ_Msk (0x1UL << GOTGCTL_HNPRQ_Pos) /*!< 0x00000200 */ -#define GOTGCTL_HNPRQ GOTGCTL_HNPRQ_Msk /*!< HNP request */ +#define GOTGCTL_HNPRQ_Msk (0x1UL << GOTGCTL_HNPRQ_Pos) /*!< 0x00000200 */ +#define GOTGCTL_HNPRQ GOTGCTL_HNPRQ_Msk /*!< HNP request */ #define GOTGCTL_HSHNPEN_Pos (10U) -#define GOTGCTL_HSHNPEN_Msk (0x1UL << GOTGCTL_HSHNPEN_Pos) /*!< 0x00000400 */ -#define GOTGCTL_HSHNPEN GOTGCTL_HSHNPEN_Msk /*!< Host set HNP enable */ +#define GOTGCTL_HSHNPEN_Msk (0x1UL << GOTGCTL_HSHNPEN_Pos) /*!< 0x00000400 */ +#define GOTGCTL_HSHNPEN GOTGCTL_HSHNPEN_Msk /*!< Host set HNP enable */ #define GOTGCTL_DHNPEN_Pos (11U) -#define GOTGCTL_DHNPEN_Msk (0x1UL << GOTGCTL_DHNPEN_Pos) /*!< 0x00000800 */ -#define GOTGCTL_DHNPEN GOTGCTL_DHNPEN_Msk /*!< Device HNP enabled */ +#define GOTGCTL_DHNPEN_Msk (0x1UL << GOTGCTL_DHNPEN_Pos) /*!< 0x00000800 */ +#define GOTGCTL_DHNPEN GOTGCTL_DHNPEN_Msk /*!< Device HNP enabled */ #define GOTGCTL_EHEN_Pos (12U) -#define GOTGCTL_EHEN_Msk (0x1UL << GOTGCTL_EHEN_Pos) /*!< 0x00001000 */ -#define GOTGCTL_EHEN GOTGCTL_EHEN_Msk /*!< Embedded host enable */ +#define GOTGCTL_EHEN_Msk (0x1UL << GOTGCTL_EHEN_Pos) /*!< 0x00001000 */ +#define GOTGCTL_EHEN GOTGCTL_EHEN_Msk /*!< Embedded host enable */ #define GOTGCTL_CIDSTS_Pos (16U) -#define GOTGCTL_CIDSTS_Msk (0x1UL << GOTGCTL_CIDSTS_Pos) /*!< 0x00010000 */ -#define GOTGCTL_CIDSTS GOTGCTL_CIDSTS_Msk /*!< Connector ID status */ +#define GOTGCTL_CIDSTS_Msk (0x1UL << GOTGCTL_CIDSTS_Pos) /*!< 0x00010000 */ +#define GOTGCTL_CIDSTS GOTGCTL_CIDSTS_Msk /*!< Connector ID status */ #define GOTGCTL_DBCT_Pos (17U) -#define GOTGCTL_DBCT_Msk (0x1UL << GOTGCTL_DBCT_Pos) /*!< 0x00020000 */ -#define GOTGCTL_DBCT GOTGCTL_DBCT_Msk /*!< Long/short debounce time */ +#define GOTGCTL_DBCT_Msk (0x1UL << GOTGCTL_DBCT_Pos) /*!< 0x00020000 */ +#define GOTGCTL_DBCT GOTGCTL_DBCT_Msk /*!< Long/short debounce time */ #define GOTGCTL_ASVLD_Pos (18U) -#define GOTGCTL_ASVLD_Msk (0x1UL << GOTGCTL_ASVLD_Pos) /*!< 0x00040000 */ -#define GOTGCTL_ASVLD GOTGCTL_ASVLD_Msk /*!< A-session valid */ +#define GOTGCTL_ASVLD_Msk (0x1UL << GOTGCTL_ASVLD_Pos) /*!< 0x00040000 */ +#define GOTGCTL_ASVLD GOTGCTL_ASVLD_Msk /*!< A-session valid */ #define GOTGCTL_BSESVLD_Pos (19U) -#define GOTGCTL_BSESVLD_Msk (0x1UL << GOTGCTL_BSESVLD_Pos) /*!< 0x00080000 */ -#define GOTGCTL_BSESVLD GOTGCTL_BSESVLD_Msk /*!< B-session valid */ +#define GOTGCTL_BSESVLD_Msk (0x1UL << GOTGCTL_BSESVLD_Pos) /*!< 0x00080000 */ +#define GOTGCTL_BSESVLD GOTGCTL_BSESVLD_Msk /*!< B-session valid */ #define GOTGCTL_OTGVER_Pos (20U) -#define GOTGCTL_OTGVER_Msk (0x1UL << GOTGCTL_OTGVER_Pos) /*!< 0x00100000 */ -#define GOTGCTL_OTGVER GOTGCTL_OTGVER_Msk /*!< OTG version */ +#define GOTGCTL_OTGVER_Msk (0x1UL << GOTGCTL_OTGVER_Pos) /*!< 0x00100000 */ +#define GOTGCTL_OTGVER GOTGCTL_OTGVER_Msk /*!< OTG version */ /******************** Bit definition for HCFG register ********************/ #define HCFG_FSLSPCS_Pos (0U) -#define HCFG_FSLSPCS_Msk (0x3UL << HCFG_FSLSPCS_Pos) /*!< 0x00000003 */ -#define HCFG_FSLSPCS HCFG_FSLSPCS_Msk /*!< FS/LS PHY clock select */ -#define HCFG_FSLSPCS_0 (0x1UL << HCFG_FSLSPCS_Pos) /*!< 0x00000001 */ -#define HCFG_FSLSPCS_1 (0x2UL << HCFG_FSLSPCS_Pos) /*!< 0x00000002 */ +#define HCFG_FSLSPCS_Msk (0x3UL << HCFG_FSLSPCS_Pos) /*!< 0x00000003 */ +#define HCFG_FSLSPCS HCFG_FSLSPCS_Msk /*!< FS/LS PHY clock select */ +#define HCFG_FSLSPCS_0 (0x1UL << HCFG_FSLSPCS_Pos) /*!< 0x00000001 */ +#define HCFG_FSLSPCS_1 (0x2UL << HCFG_FSLSPCS_Pos) /*!< 0x00000002 */ #define HCFG_FSLSS_Pos (2U) -#define HCFG_FSLSS_Msk (0x1UL << HCFG_FSLSS_Pos) /*!< 0x00000004 */ -#define HCFG_FSLSS HCFG_FSLSS_Msk /*!< FS- and LS-only support */ +#define HCFG_FSLSS_Msk (0x1UL << HCFG_FSLSS_Pos) /*!< 0x00000004 */ +#define HCFG_FSLSS HCFG_FSLSS_Msk /*!< FS- and LS-only support */ /******************** Bit definition for DCFG register ********************/ #define DCFG_DSPD_Pos (0U) -#define DCFG_DSPD_Msk (0x3UL << DCFG_DSPD_Pos) /*!< 0x00000003 */ -#define DCFG_DSPD DCFG_DSPD_Msk /*!< Device speed */ -#define DCFG_DSPD_0 (0x1UL << DCFG_DSPD_Pos) /*!< 0x00000001 */ -#define DCFG_DSPD_1 (0x2UL << DCFG_DSPD_Pos) /*!< 0x00000002 */ +#define DCFG_DSPD_Msk (0x3UL << DCFG_DSPD_Pos) /*!< 0x00000003 */ +#define DCFG_DSPD DCFG_DSPD_Msk /*!< Device speed */ +#define DCFG_DSPD_0 (0x1UL << DCFG_DSPD_Pos) /*!< 0x00000001 */ +#define DCFG_DSPD_1 (0x2UL << DCFG_DSPD_Pos) /*!< 0x00000002 */ #define DCFG_NZLSOHSK_Pos (2U) -#define DCFG_NZLSOHSK_Msk (0x1UL << DCFG_NZLSOHSK_Pos) /*!< 0x00000004 */ -#define DCFG_NZLSOHSK DCFG_NZLSOHSK_Msk /*!< Nonzero-length status OUT handshake */ +#define DCFG_NZLSOHSK_Msk (0x1UL << DCFG_NZLSOHSK_Pos) /*!< 0x00000004 */ +#define DCFG_NZLSOHSK DCFG_NZLSOHSK_Msk /*!< Nonzero-length status OUT handshake */ #define DCFG_DAD_Pos (4U) -#define DCFG_DAD_Msk (0x7FUL << DCFG_DAD_Pos) /*!< 0x000007F0 */ -#define DCFG_DAD DCFG_DAD_Msk /*!< Device address */ -#define DCFG_DAD_0 (0x01UL << DCFG_DAD_Pos) /*!< 0x00000010 */ -#define DCFG_DAD_1 (0x02UL << DCFG_DAD_Pos) /*!< 0x00000020 */ -#define DCFG_DAD_2 (0x04UL << DCFG_DAD_Pos) /*!< 0x00000040 */ -#define DCFG_DAD_3 (0x08UL << DCFG_DAD_Pos) /*!< 0x00000080 */ -#define DCFG_DAD_4 (0x10UL << DCFG_DAD_Pos) /*!< 0x00000100 */ -#define DCFG_DAD_5 (0x20UL << DCFG_DAD_Pos) /*!< 0x00000200 */ -#define DCFG_DAD_6 (0x40UL << DCFG_DAD_Pos) /*!< 0x00000400 */ +#define DCFG_DAD_Msk (0x7FUL << DCFG_DAD_Pos) /*!< 0x000007F0 */ +#define DCFG_DAD DCFG_DAD_Msk /*!< Device address */ +#define DCFG_DAD_0 (0x01UL << DCFG_DAD_Pos) /*!< 0x00000010 */ +#define DCFG_DAD_1 (0x02UL << DCFG_DAD_Pos) /*!< 0x00000020 */ +#define DCFG_DAD_2 (0x04UL << DCFG_DAD_Pos) /*!< 0x00000040 */ +#define DCFG_DAD_3 (0x08UL << DCFG_DAD_Pos) /*!< 0x00000080 */ +#define DCFG_DAD_4 (0x10UL << DCFG_DAD_Pos) /*!< 0x00000100 */ +#define DCFG_DAD_5 (0x20UL << DCFG_DAD_Pos) /*!< 0x00000200 */ +#define DCFG_DAD_6 (0x40UL << DCFG_DAD_Pos) /*!< 0x00000400 */ #define DCFG_PFIVL_Pos (11U) -#define DCFG_PFIVL_Msk (0x3UL << DCFG_PFIVL_Pos) /*!< 0x00001800 */ -#define DCFG_PFIVL DCFG_PFIVL_Msk /*!< Periodic (micro)frame interval */ -#define DCFG_PFIVL_0 (0x1UL << DCFG_PFIVL_Pos) /*!< 0x00000800 */ -#define DCFG_PFIVL_1 (0x2UL << DCFG_PFIVL_Pos) /*!< 0x00001000 */ +#define DCFG_PFIVL_Msk (0x3UL << DCFG_PFIVL_Pos) /*!< 0x00001800 */ +#define DCFG_PFIVL DCFG_PFIVL_Msk /*!< Periodic (micro)frame interval */ +#define DCFG_PFIVL_0 (0x1UL << DCFG_PFIVL_Pos) /*!< 0x00000800 */ +#define DCFG_PFIVL_1 (0x2UL << DCFG_PFIVL_Pos) /*!< 0x00001000 */ #define DCFG_PERSCHIVL_Pos (24U) -#define DCFG_PERSCHIVL_Msk (0x3UL << DCFG_PERSCHIVL_Pos) /*!< 0x03000000 */ -#define DCFG_PERSCHIVL DCFG_PERSCHIVL_Msk /*!< Periodic scheduling interval */ -#define DCFG_PERSCHIVL_0 (0x1UL << DCFG_PERSCHIVL_Pos) /*!< 0x01000000 */ -#define DCFG_PERSCHIVL_1 (0x2UL << DCFG_PERSCHIVL_Pos) /*!< 0x02000000 */ +#define DCFG_PERSCHIVL_Msk (0x3UL << DCFG_PERSCHIVL_Pos) /*!< 0x03000000 */ +#define DCFG_PERSCHIVL DCFG_PERSCHIVL_Msk /*!< Periodic scheduling interval */ +#define DCFG_PERSCHIVL_0 (0x1UL << DCFG_PERSCHIVL_Pos) /*!< 0x01000000 */ +#define DCFG_PERSCHIVL_1 (0x2UL << DCFG_PERSCHIVL_Pos) /*!< 0x02000000 */ /******************** Bit definition for PCGCR register ********************/ #define PCGCR_STPPCLK_Pos (0U) -#define PCGCR_STPPCLK_Msk (0x1UL << PCGCR_STPPCLK_Pos) /*!< 0x00000001 */ -#define PCGCR_STPPCLK PCGCR_STPPCLK_Msk /*!< Stop PHY clock */ +#define PCGCR_STPPCLK_Msk (0x1UL << PCGCR_STPPCLK_Pos) /*!< 0x00000001 */ +#define PCGCR_STPPCLK PCGCR_STPPCLK_Msk /*!< Stop PHY clock */ #define PCGCR_GATEHCLK_Pos (1U) -#define PCGCR_GATEHCLK_Msk (0x1UL << PCGCR_GATEHCLK_Pos) /*!< 0x00000002 */ -#define PCGCR_GATEHCLK PCGCR_GATEHCLK_Msk /*!< Gate HCLK */ +#define PCGCR_GATEHCLK_Msk (0x1UL << PCGCR_GATEHCLK_Pos) /*!< 0x00000002 */ +#define PCGCR_GATEHCLK PCGCR_GATEHCLK_Msk /*!< Gate HCLK */ #define PCGCR_PHYSUSP_Pos (4U) -#define PCGCR_PHYSUSP_Msk (0x1UL << PCGCR_PHYSUSP_Pos) /*!< 0x00000010 */ -#define PCGCR_PHYSUSP PCGCR_PHYSUSP_Msk /*!< PHY suspended */ +#define PCGCR_PHYSUSP_Msk (0x1UL << PCGCR_PHYSUSP_Pos) /*!< 0x00000010 */ +#define PCGCR_PHYSUSP PCGCR_PHYSUSP_Msk /*!< PHY suspended */ /******************** Bit definition for GOTGINT register ********************/ #define GOTGINT_SEDET_Pos (2U) -#define GOTGINT_SEDET_Msk (0x1UL << GOTGINT_SEDET_Pos) /*!< 0x00000004 */ -#define GOTGINT_SEDET GOTGINT_SEDET_Msk /*!< Session end detected */ +#define GOTGINT_SEDET_Msk (0x1UL << GOTGINT_SEDET_Pos) /*!< 0x00000004 */ +#define GOTGINT_SEDET GOTGINT_SEDET_Msk /*!< Session end detected */ #define GOTGINT_SRSSCHG_Pos (8U) -#define GOTGINT_SRSSCHG_Msk (0x1UL << GOTGINT_SRSSCHG_Pos) /*!< 0x00000100 */ -#define GOTGINT_SRSSCHG GOTGINT_SRSSCHG_Msk /*!< Session request success status change */ +#define GOTGINT_SRSSCHG_Msk (0x1UL << GOTGINT_SRSSCHG_Pos) /*!< 0x00000100 */ +#define GOTGINT_SRSSCHG GOTGINT_SRSSCHG_Msk /*!< Session request success status change */ #define GOTGINT_HNSSCHG_Pos (9U) -#define GOTGINT_HNSSCHG_Msk (0x1UL << GOTGINT_HNSSCHG_Pos) /*!< 0x00000200 */ -#define GOTGINT_HNSSCHG GOTGINT_HNSSCHG_Msk /*!< Host negotiation success status change */ +#define GOTGINT_HNSSCHG_Msk (0x1UL << GOTGINT_HNSSCHG_Pos) /*!< 0x00000200 */ +#define GOTGINT_HNSSCHG GOTGINT_HNSSCHG_Msk /*!< Host negotiation success status change */ #define GOTGINT_HNGDET_Pos (17U) -#define GOTGINT_HNGDET_Msk (0x1UL << GOTGINT_HNGDET_Pos) /*!< 0x00020000 */ -#define GOTGINT_HNGDET GOTGINT_HNGDET_Msk /*!< Host negotiation detected */ +#define GOTGINT_HNGDET_Msk (0x1UL << GOTGINT_HNGDET_Pos) /*!< 0x00020000 */ +#define GOTGINT_HNGDET GOTGINT_HNGDET_Msk /*!< Host negotiation detected */ #define GOTGINT_ADTOCHG_Pos (18U) -#define GOTGINT_ADTOCHG_Msk (0x1UL << GOTGINT_ADTOCHG_Pos) /*!< 0x00040000 */ -#define GOTGINT_ADTOCHG GOTGINT_ADTOCHG_Msk /*!< A-device timeout change */ +#define GOTGINT_ADTOCHG_Msk (0x1UL << GOTGINT_ADTOCHG_Pos) /*!< 0x00040000 */ +#define GOTGINT_ADTOCHG GOTGINT_ADTOCHG_Msk /*!< A-device timeout change */ #define GOTGINT_DBCDNE_Pos (19U) -#define GOTGINT_DBCDNE_Msk (0x1UL << GOTGINT_DBCDNE_Pos) /*!< 0x00080000 */ -#define GOTGINT_DBCDNE GOTGINT_DBCDNE_Msk /*!< Debounce done */ +#define GOTGINT_DBCDNE_Msk (0x1UL << GOTGINT_DBCDNE_Pos) /*!< 0x00080000 */ +#define GOTGINT_DBCDNE GOTGINT_DBCDNE_Msk /*!< Debounce done */ #define GOTGINT_IDCHNG_Pos (20U) -#define GOTGINT_IDCHNG_Msk (0x1UL << GOTGINT_IDCHNG_Pos) /*!< 0x00100000 */ -#define GOTGINT_IDCHNG GOTGINT_IDCHNG_Msk /*!< Change in ID pin input value */ +#define GOTGINT_IDCHNG_Msk (0x1UL << GOTGINT_IDCHNG_Pos) /*!< 0x00100000 */ +#define GOTGINT_IDCHNG GOTGINT_IDCHNG_Msk /*!< Change in ID pin input value */ /******************** Bit definition for DCTL register ********************/ #define DCTL_RWUSIG_Pos (0U) -#define DCTL_RWUSIG_Msk (0x1UL << DCTL_RWUSIG_Pos) /*!< 0x00000001 */ -#define DCTL_RWUSIG DCTL_RWUSIG_Msk /*!< Remote wakeup signaling */ +#define DCTL_RWUSIG_Msk (0x1UL << DCTL_RWUSIG_Pos) /*!< 0x00000001 */ +#define DCTL_RWUSIG DCTL_RWUSIG_Msk /*!< Remote wakeup signaling */ #define DCTL_SDIS_Pos (1U) -#define DCTL_SDIS_Msk (0x1UL << DCTL_SDIS_Pos) /*!< 0x00000002 */ -#define DCTL_SDIS DCTL_SDIS_Msk /*!< Soft disconnect */ +#define DCTL_SDIS_Msk (0x1UL << DCTL_SDIS_Pos) /*!< 0x00000002 */ +#define DCTL_SDIS DCTL_SDIS_Msk /*!< Soft disconnect */ #define DCTL_GINSTS_Pos (2U) -#define DCTL_GINSTS_Msk (0x1UL << DCTL_GINSTS_Pos) /*!< 0x00000004 */ -#define DCTL_GINSTS DCTL_GINSTS_Msk /*!< Global IN NAK status */ +#define DCTL_GINSTS_Msk (0x1UL << DCTL_GINSTS_Pos) /*!< 0x00000004 */ +#define DCTL_GINSTS DCTL_GINSTS_Msk /*!< Global IN NAK status */ #define DCTL_GONSTS_Pos (3U) -#define DCTL_GONSTS_Msk (0x1UL << DCTL_GONSTS_Pos) /*!< 0x00000008 */ -#define DCTL_GONSTS DCTL_GONSTS_Msk /*!< Global OUT NAK status */ +#define DCTL_GONSTS_Msk (0x1UL << DCTL_GONSTS_Pos) /*!< 0x00000008 */ +#define DCTL_GONSTS DCTL_GONSTS_Msk /*!< Global OUT NAK status */ #define DCTL_TCTL_Pos (4U) -#define DCTL_TCTL_Msk (0x7UL << DCTL_TCTL_Pos) /*!< 0x00000070 */ -#define DCTL_TCTL DCTL_TCTL_Msk /*!< Test control */ -#define DCTL_TCTL_0 (0x1UL << DCTL_TCTL_Pos) /*!< 0x00000010 */ -#define DCTL_TCTL_1 (0x2UL << DCTL_TCTL_Pos) /*!< 0x00000020 */ -#define DCTL_TCTL_2 (0x4UL << DCTL_TCTL_Pos) /*!< 0x00000040 */ +#define DCTL_TCTL_Msk (0x7UL << DCTL_TCTL_Pos) /*!< 0x00000070 */ +#define DCTL_TCTL DCTL_TCTL_Msk /*!< Test control */ +#define DCTL_TCTL_0 (0x1UL << DCTL_TCTL_Pos) /*!< 0x00000010 */ +#define DCTL_TCTL_1 (0x2UL << DCTL_TCTL_Pos) /*!< 0x00000020 */ +#define DCTL_TCTL_2 (0x4UL << DCTL_TCTL_Pos) /*!< 0x00000040 */ #define DCTL_SGINAK_Pos (7U) -#define DCTL_SGINAK_Msk (0x1UL << DCTL_SGINAK_Pos) /*!< 0x00000080 */ -#define DCTL_SGINAK DCTL_SGINAK_Msk /*!< Set global IN NAK */ +#define DCTL_SGINAK_Msk (0x1UL << DCTL_SGINAK_Pos) /*!< 0x00000080 */ +#define DCTL_SGINAK DCTL_SGINAK_Msk /*!< Set global IN NAK */ #define DCTL_CGINAK_Pos (8U) -#define DCTL_CGINAK_Msk (0x1UL << DCTL_CGINAK_Pos) /*!< 0x00000100 */ -#define DCTL_CGINAK DCTL_CGINAK_Msk /*!< Clear global IN NAK */ +#define DCTL_CGINAK_Msk (0x1UL << DCTL_CGINAK_Pos) /*!< 0x00000100 */ +#define DCTL_CGINAK DCTL_CGINAK_Msk /*!< Clear global IN NAK */ #define DCTL_SGONAK_Pos (9U) -#define DCTL_SGONAK_Msk (0x1UL << DCTL_SGONAK_Pos) /*!< 0x00000200 */ -#define DCTL_SGONAK DCTL_SGONAK_Msk /*!< Set global OUT NAK */ +#define DCTL_SGONAK_Msk (0x1UL << DCTL_SGONAK_Pos) /*!< 0x00000200 */ +#define DCTL_SGONAK DCTL_SGONAK_Msk /*!< Set global OUT NAK */ #define DCTL_CGONAK_Pos (10U) -#define DCTL_CGONAK_Msk (0x1UL << DCTL_CGONAK_Pos) /*!< 0x00000400 */ -#define DCTL_CGONAK DCTL_CGONAK_Msk /*!< Clear global OUT NAK */ +#define DCTL_CGONAK_Msk (0x1UL << DCTL_CGONAK_Pos) /*!< 0x00000400 */ +#define DCTL_CGONAK DCTL_CGONAK_Msk /*!< Clear global OUT NAK */ #define DCTL_POPRGDNE_Pos (11U) -#define DCTL_POPRGDNE_Msk (0x1UL << DCTL_POPRGDNE_Pos) /*!< 0x00000800 */ -#define DCTL_POPRGDNE DCTL_POPRGDNE_Msk /*!< Power-on programming done */ +#define DCTL_POPRGDNE_Msk (0x1UL << DCTL_POPRGDNE_Pos) /*!< 0x00000800 */ +#define DCTL_POPRGDNE DCTL_POPRGDNE_Msk /*!< Power-on programming done */ /******************** Bit definition for HFIR register ********************/ #define HFIR_FRIVL_Pos (0U) -#define HFIR_FRIVL_Msk (0xFFFFUL << HFIR_FRIVL_Pos) /*!< 0x0000FFFF */ -#define HFIR_FRIVL HFIR_FRIVL_Msk /*!< Frame interval */ +#define HFIR_FRIVL_Msk (0xFFFFUL << HFIR_FRIVL_Pos) /*!< 0x0000FFFF */ +#define HFIR_FRIVL HFIR_FRIVL_Msk /*!< Frame interval */ /******************** Bit definition for HFNUM register ********************/ #define HFNUM_FRNUM_Pos (0U) -#define HFNUM_FRNUM_Msk (0xFFFFUL << HFNUM_FRNUM_Pos) /*!< 0x0000FFFF */ -#define HFNUM_FRNUM HFNUM_FRNUM_Msk /*!< Frame number */ +#define HFNUM_FRNUM_Msk (0xFFFFUL << HFNUM_FRNUM_Pos) /*!< 0x0000FFFF */ +#define HFNUM_FRNUM HFNUM_FRNUM_Msk /*!< Frame number */ #define HFNUM_FTREM_Pos (16U) -#define HFNUM_FTREM_Msk (0xFFFFUL << HFNUM_FTREM_Pos) /*!< 0xFFFF0000 */ -#define HFNUM_FTREM HFNUM_FTREM_Msk /*!< Frame time remaining */ +#define HFNUM_FTREM_Msk (0xFFFFUL << HFNUM_FTREM_Pos) /*!< 0xFFFF0000 */ +#define HFNUM_FTREM HFNUM_FTREM_Msk /*!< Frame time remaining */ /******************** Bit definition for DSTS register ********************/ #define DSTS_SUSPSTS_Pos (0U) -#define DSTS_SUSPSTS_Msk (0x1UL << DSTS_SUSPSTS_Pos) /*!< 0x00000001 */ -#define DSTS_SUSPSTS DSTS_SUSPSTS_Msk /*!< Suspend status */ +#define DSTS_SUSPSTS_Msk (0x1UL << DSTS_SUSPSTS_Pos) /*!< 0x00000001 */ +#define DSTS_SUSPSTS DSTS_SUSPSTS_Msk /*!< Suspend status */ #define DSTS_ENUMSPD_Pos (1U) -#define DSTS_ENUMSPD_Msk (0x3UL << DSTS_ENUMSPD_Pos) /*!< 0x00000006 */ -#define DSTS_ENUMSPD DSTS_ENUMSPD_Msk /*!< Enumerated speed */ -#define DSTS_ENUMSPD_0 (0x1UL << DSTS_ENUMSPD_Pos) /*!< 0x00000002 */ -#define DSTS_ENUMSPD_1 (0x2UL << DSTS_ENUMSPD_Pos) /*!< 0x00000004 */ +#define DSTS_ENUMSPD_Msk (0x3UL << DSTS_ENUMSPD_Pos) /*!< 0x00000006 */ +#define DSTS_ENUMSPD DSTS_ENUMSPD_Msk /*!< Enumerated speed */ +#define DSTS_ENUMSPD_0 (0x1UL << DSTS_ENUMSPD_Pos) /*!< 0x00000002 */ +#define DSTS_ENUMSPD_1 (0x2UL << DSTS_ENUMSPD_Pos) /*!< 0x00000004 */ #define DSTS_EERR_Pos (3U) -#define DSTS_EERR_Msk (0x1UL << DSTS_EERR_Pos) /*!< 0x00000008 */ -#define DSTS_EERR DSTS_EERR_Msk /*!< Erratic error */ +#define DSTS_EERR_Msk (0x1UL << DSTS_EERR_Pos) /*!< 0x00000008 */ +#define DSTS_EERR DSTS_EERR_Msk /*!< Erratic error */ #define DSTS_FNSOF_Pos (8U) -#define DSTS_FNSOF_Msk (0x3FFFUL << DSTS_FNSOF_Pos) /*!< 0x003FFF00 */ -#define DSTS_FNSOF DSTS_FNSOF_Msk /*!< Frame number of the received SOF */ +#define DSTS_FNSOF_Msk (0x3FFFUL << DSTS_FNSOF_Pos) /*!< 0x003FFF00 */ +#define DSTS_FNSOF DSTS_FNSOF_Msk /*!< Frame number of the received SOF */ /******************** Bit definition for GAHBCFG register ********************/ #define GAHBCFG_GINT_Pos (0U) -#define GAHBCFG_GINT_Msk (0x1UL << GAHBCFG_GINT_Pos) /*!< 0x00000001 */ -#define GAHBCFG_GINT GAHBCFG_GINT_Msk /*!< Global interrupt mask */ +#define GAHBCFG_GINT_Msk (0x1UL << GAHBCFG_GINT_Pos) /*!< 0x00000001 */ +#define GAHBCFG_GINT GAHBCFG_GINT_Msk /*!< Global interrupt mask */ #define GAHBCFG_HBSTLEN_Pos (1U) -#define GAHBCFG_HBSTLEN_Msk (0xFUL << GAHBCFG_HBSTLEN_Pos) /*!< 0x0000001E */ -#define GAHBCFG_HBSTLEN GAHBCFG_HBSTLEN_Msk /*!< Burst length/type */ -#define GAHBCFG_HBSTLEN_0 (0x0UL << GAHBCFG_HBSTLEN_Pos) /*!< Single */ -#define GAHBCFG_HBSTLEN_1 (0x1UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR */ -#define GAHBCFG_HBSTLEN_2 (0x3UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR4 */ -#define GAHBCFG_HBSTLEN_3 (0x5UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR8 */ -#define GAHBCFG_HBSTLEN_4 (0x7UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR16 */ +#define GAHBCFG_HBSTLEN_Msk (0xFUL << GAHBCFG_HBSTLEN_Pos) /*!< 0x0000001E */ +#define GAHBCFG_HBSTLEN GAHBCFG_HBSTLEN_Msk /*!< Burst length/type */ +#define GAHBCFG_HBSTLEN_0 (0x0UL << GAHBCFG_HBSTLEN_Pos) /*!< Single */ +#define GAHBCFG_HBSTLEN_1 (0x1UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR */ +#define GAHBCFG_HBSTLEN_2 (0x3UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR4 */ +#define GAHBCFG_HBSTLEN_3 (0x5UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR8 */ +#define GAHBCFG_HBSTLEN_4 (0x7UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR16 */ #define GAHBCFG_DMAEN_Pos (5U) -#define GAHBCFG_DMAEN_Msk (0x1UL << GAHBCFG_DMAEN_Pos) /*!< 0x00000020 */ -#define GAHBCFG_DMAEN GAHBCFG_DMAEN_Msk /*!< DMA enable */ +#define GAHBCFG_DMAEN_Msk (0x1UL << GAHBCFG_DMAEN_Pos) /*!< 0x00000020 */ +#define GAHBCFG_DMAEN GAHBCFG_DMAEN_Msk /*!< DMA enable */ #define GAHBCFG_TXFELVL_Pos (7U) -#define GAHBCFG_TXFELVL_Msk (0x1UL << GAHBCFG_TXFELVL_Pos) /*!< 0x00000080 */ -#define GAHBCFG_TXFELVL GAHBCFG_TXFELVL_Msk /*!< TxFIFO empty level */ +#define GAHBCFG_TXFELVL_Msk (0x1UL << GAHBCFG_TXFELVL_Pos) /*!< 0x00000080 */ +#define GAHBCFG_TXFELVL GAHBCFG_TXFELVL_Msk /*!< TxFIFO empty level */ #define GAHBCFG_PTXFELVL_Pos (8U) -#define GAHBCFG_PTXFELVL_Msk (0x1UL << GAHBCFG_PTXFELVL_Pos) /*!< 0x00000100 */ -#define GAHBCFG_PTXFELVL GAHBCFG_PTXFELVL_Msk /*!< Periodic TxFIFO empty level */ +#define GAHBCFG_PTXFELVL_Msk (0x1UL << GAHBCFG_PTXFELVL_Pos) /*!< 0x00000100 */ +#define GAHBCFG_PTXFELVL GAHBCFG_PTXFELVL_Msk /*!< Periodic TxFIFO empty level */ /******************** Bit definition for GUSBCFG register ********************/ #define GUSBCFG_TOCAL_Pos (0U) -#define GUSBCFG_TOCAL_Msk (0x7UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000007 */ -#define GUSBCFG_TOCAL GUSBCFG_TOCAL_Msk /*!< FS timeout calibration */ -#define GUSBCFG_TOCAL_0 (0x1UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000001 */ -#define GUSBCFG_TOCAL_1 (0x2UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000002 */ -#define GUSBCFG_TOCAL_2 (0x4UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000004 */ +#define GUSBCFG_TOCAL_Msk (0x7UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000007 */ +#define GUSBCFG_TOCAL GUSBCFG_TOCAL_Msk /*!< FS timeout calibration */ +#define GUSBCFG_TOCAL_0 (0x1UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000001 */ +#define GUSBCFG_TOCAL_1 (0x2UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000002 */ +#define GUSBCFG_TOCAL_2 (0x4UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000004 */ #define GUSBCFG_PHYIF_Pos (3U) -#define GUSBCFG_PHYIF_Msk (0x1UL << GUSBCFG_PHYIF_Pos) /*!< 0x00000008 */ -#define GUSBCFG_PHYIF GUSBCFG_PHYIF_Msk /*!< PHY Interface (PHYIf) */ +#define GUSBCFG_PHYIF_Msk (0x1UL << GUSBCFG_PHYIF_Pos) /*!< 0x00000008 */ +#define GUSBCFG_PHYIF GUSBCFG_PHYIF_Msk /*!< PHY Interface (PHYIf) */ #define GUSBCFG_ULPI_UTMI_SEL_Pos (4U) -#define GUSBCFG_ULPI_UTMI_SEL_Msk (0x1UL << GUSBCFG_ULPI_UTMI_SEL_Pos) /*!< 0x00000010 */ -#define GUSBCFG_ULPI_UTMI_SEL GUSBCFG_ULPI_UTMI_SEL_Msk /*!< ULPI or UTMI+ Select (ULPI_UTMI_Sel) */ +#define GUSBCFG_ULPI_UTMI_SEL_Msk (0x1UL << GUSBCFG_ULPI_UTMI_SEL_Pos) /*!< 0x00000010 */ +#define GUSBCFG_ULPI_UTMI_SEL GUSBCFG_ULPI_UTMI_SEL_Msk /*!< ULPI or UTMI+ Select (ULPI_UTMI_Sel) */ #define GUSBCFG_PHYSEL_Pos (6U) -#define GUSBCFG_PHYSEL_Msk (0x1UL << GUSBCFG_PHYSEL_Pos) /*!< 0x00000040 */ -#define GUSBCFG_PHYSEL GUSBCFG_PHYSEL_Msk /*!< USB 2.0 high-speed ULPI PHY or USB 1.1 full-speed serial transceiver select */ +#define GUSBCFG_PHYSEL_Msk (0x1UL << GUSBCFG_PHYSEL_Pos) /*!< 0x00000040 */ +#define GUSBCFG_PHYSEL GUSBCFG_PHYSEL_Msk /*!< USB 2.0 high-speed ULPI PHY or USB 1.1 full-speed serial transceiver select */ #define GUSBCFG_SRPCAP_Pos (8U) -#define GUSBCFG_SRPCAP_Msk (0x1UL << GUSBCFG_SRPCAP_Pos) /*!< 0x00000100 */ -#define GUSBCFG_SRPCAP GUSBCFG_SRPCAP_Msk /*!< SRP-capable */ +#define GUSBCFG_SRPCAP_Msk (0x1UL << GUSBCFG_SRPCAP_Pos) /*!< 0x00000100 */ +#define GUSBCFG_SRPCAP GUSBCFG_SRPCAP_Msk /*!< SRP-capable */ #define GUSBCFG_HNPCAP_Pos (9U) -#define GUSBCFG_HNPCAP_Msk (0x1UL << GUSBCFG_HNPCAP_Pos) /*!< 0x00000200 */ -#define GUSBCFG_HNPCAP GUSBCFG_HNPCAP_Msk /*!< HNP-capable */ +#define GUSBCFG_HNPCAP_Msk (0x1UL << GUSBCFG_HNPCAP_Pos) /*!< 0x00000200 */ +#define GUSBCFG_HNPCAP GUSBCFG_HNPCAP_Msk /*!< HNP-capable */ #define GUSBCFG_TRDT_Pos (10U) -#define GUSBCFG_TRDT_Msk (0xFUL << GUSBCFG_TRDT_Pos) /*!< 0x00003C00 */ -#define GUSBCFG_TRDT GUSBCFG_TRDT_Msk /*!< USB turnaround time */ -#define GUSBCFG_TRDT_0 (0x1UL << GUSBCFG_TRDT_Pos) /*!< 0x00000400 */ -#define GUSBCFG_TRDT_1 (0x2UL << GUSBCFG_TRDT_Pos) /*!< 0x00000800 */ -#define GUSBCFG_TRDT_2 (0x4UL << GUSBCFG_TRDT_Pos) /*!< 0x00001000 */ -#define GUSBCFG_TRDT_3 (0x8UL << GUSBCFG_TRDT_Pos) /*!< 0x00002000 */ +#define GUSBCFG_TRDT_Msk (0xFUL << GUSBCFG_TRDT_Pos) /*!< 0x00003C00 */ +#define GUSBCFG_TRDT GUSBCFG_TRDT_Msk /*!< USB turnaround time */ +#define GUSBCFG_TRDT_0 (0x1UL << GUSBCFG_TRDT_Pos) /*!< 0x00000400 */ +#define GUSBCFG_TRDT_1 (0x2UL << GUSBCFG_TRDT_Pos) /*!< 0x00000800 */ +#define GUSBCFG_TRDT_2 (0x4UL << GUSBCFG_TRDT_Pos) /*!< 0x00001000 */ +#define GUSBCFG_TRDT_3 (0x8UL << GUSBCFG_TRDT_Pos) /*!< 0x00002000 */ #define GUSBCFG_PHYLPCS_Pos (15U) -#define GUSBCFG_PHYLPCS_Msk (0x1UL << GUSBCFG_PHYLPCS_Pos) /*!< 0x00008000 */ -#define GUSBCFG_PHYLPCS GUSBCFG_PHYLPCS_Msk /*!< PHY Low-power clock select */ +#define GUSBCFG_PHYLPCS_Msk (0x1UL << GUSBCFG_PHYLPCS_Pos) /*!< 0x00008000 */ +#define GUSBCFG_PHYLPCS GUSBCFG_PHYLPCS_Msk /*!< PHY Low-power clock select */ #define GUSBCFG_ULPIFSLS_Pos (17U) -#define GUSBCFG_ULPIFSLS_Msk (0x1UL << GUSBCFG_ULPIFSLS_Pos) /*!< 0x00020000 */ -#define GUSBCFG_ULPIFSLS GUSBCFG_ULPIFSLS_Msk /*!< ULPI FS/LS select */ +#define GUSBCFG_ULPIFSLS_Msk (0x1UL << GUSBCFG_ULPIFSLS_Pos) /*!< 0x00020000 */ +#define GUSBCFG_ULPIFSLS GUSBCFG_ULPIFSLS_Msk /*!< ULPI FS/LS select */ #define GUSBCFG_ULPIAR_Pos (18U) -#define GUSBCFG_ULPIAR_Msk (0x1UL << GUSBCFG_ULPIAR_Pos) /*!< 0x00040000 */ -#define GUSBCFG_ULPIAR GUSBCFG_ULPIAR_Msk /*!< ULPI Auto-resume */ +#define GUSBCFG_ULPIAR_Msk (0x1UL << GUSBCFG_ULPIAR_Pos) /*!< 0x00040000 */ +#define GUSBCFG_ULPIAR GUSBCFG_ULPIAR_Msk /*!< ULPI Auto-resume */ #define GUSBCFG_ULPICSM_Pos (19U) -#define GUSBCFG_ULPICSM_Msk (0x1UL << GUSBCFG_ULPICSM_Pos) /*!< 0x00080000 */ -#define GUSBCFG_ULPICSM GUSBCFG_ULPICSM_Msk /*!< ULPI Clock SuspendM */ +#define GUSBCFG_ULPICSM_Msk (0x1UL << GUSBCFG_ULPICSM_Pos) /*!< 0x00080000 */ +#define GUSBCFG_ULPICSM GUSBCFG_ULPICSM_Msk /*!< ULPI Clock SuspendM */ #define GUSBCFG_ULPIEVBUSD_Pos (20U) -#define GUSBCFG_ULPIEVBUSD_Msk (0x1UL << GUSBCFG_ULPIEVBUSD_Pos) /*!< 0x00100000 */ -#define GUSBCFG_ULPIEVBUSD GUSBCFG_ULPIEVBUSD_Msk /*!< ULPI External VBUS Drive */ +#define GUSBCFG_ULPIEVBUSD_Msk (0x1UL << GUSBCFG_ULPIEVBUSD_Pos) /*!< 0x00100000 */ +#define GUSBCFG_ULPIEVBUSD GUSBCFG_ULPIEVBUSD_Msk /*!< ULPI External VBUS Drive */ #define GUSBCFG_ULPIEVBUSI_Pos (21U) -#define GUSBCFG_ULPIEVBUSI_Msk (0x1UL << GUSBCFG_ULPIEVBUSI_Pos) /*!< 0x00200000 */ -#define GUSBCFG_ULPIEVBUSI GUSBCFG_ULPIEVBUSI_Msk /*!< ULPI external VBUS indicator */ +#define GUSBCFG_ULPIEVBUSI_Msk (0x1UL << GUSBCFG_ULPIEVBUSI_Pos) /*!< 0x00200000 */ +#define GUSBCFG_ULPIEVBUSI GUSBCFG_ULPIEVBUSI_Msk /*!< ULPI external VBUS indicator */ #define GUSBCFG_TSDPS_Pos (22U) -#define GUSBCFG_TSDPS_Msk (0x1UL << GUSBCFG_TSDPS_Pos) /*!< 0x00400000 */ -#define GUSBCFG_TSDPS GUSBCFG_TSDPS_Msk /*!< TermSel DLine pulsing selection */ +#define GUSBCFG_TSDPS_Msk (0x1UL << GUSBCFG_TSDPS_Pos) /*!< 0x00400000 */ +#define GUSBCFG_TSDPS GUSBCFG_TSDPS_Msk /*!< TermSel DLine pulsing selection */ #define GUSBCFG_PCCI_Pos (23U) -#define GUSBCFG_PCCI_Msk (0x1UL << GUSBCFG_PCCI_Pos) /*!< 0x00800000 */ -#define GUSBCFG_PCCI GUSBCFG_PCCI_Msk /*!< Indicator complement */ +#define GUSBCFG_PCCI_Msk (0x1UL << GUSBCFG_PCCI_Pos) /*!< 0x00800000 */ +#define GUSBCFG_PCCI GUSBCFG_PCCI_Msk /*!< Indicator complement */ #define GUSBCFG_PTCI_Pos (24U) -#define GUSBCFG_PTCI_Msk (0x1UL << GUSBCFG_PTCI_Pos) /*!< 0x01000000 */ -#define GUSBCFG_PTCI GUSBCFG_PTCI_Msk /*!< Indicator pass through */ +#define GUSBCFG_PTCI_Msk (0x1UL << GUSBCFG_PTCI_Pos) /*!< 0x01000000 */ +#define GUSBCFG_PTCI GUSBCFG_PTCI_Msk /*!< Indicator pass through */ #define GUSBCFG_ULPIIPD_Pos (25U) -#define GUSBCFG_ULPIIPD_Msk (0x1UL << GUSBCFG_ULPIIPD_Pos) /*!< 0x02000000 */ -#define GUSBCFG_ULPIIPD GUSBCFG_ULPIIPD_Msk /*!< ULPI interface protect disable */ +#define GUSBCFG_ULPIIPD_Msk (0x1UL << GUSBCFG_ULPIIPD_Pos) /*!< 0x02000000 */ +#define GUSBCFG_ULPIIPD GUSBCFG_ULPIIPD_Msk /*!< ULPI interface protect disable */ #define GUSBCFG_FHMOD_Pos (29U) -#define GUSBCFG_FHMOD_Msk (0x1UL << GUSBCFG_FHMOD_Pos) /*!< 0x20000000 */ -#define GUSBCFG_FHMOD GUSBCFG_FHMOD_Msk /*!< Forced host mode */ +#define GUSBCFG_FHMOD_Msk (0x1UL << GUSBCFG_FHMOD_Pos) /*!< 0x20000000 */ +#define GUSBCFG_FHMOD GUSBCFG_FHMOD_Msk /*!< Forced host mode */ #define GUSBCFG_FDMOD_Pos (30U) -#define GUSBCFG_FDMOD_Msk (0x1UL << GUSBCFG_FDMOD_Pos) /*!< 0x40000000 */ -#define GUSBCFG_FDMOD GUSBCFG_FDMOD_Msk /*!< Forced peripheral mode */ +#define GUSBCFG_FDMOD_Msk (0x1UL << GUSBCFG_FDMOD_Pos) /*!< 0x40000000 */ +#define GUSBCFG_FDMOD GUSBCFG_FDMOD_Msk /*!< Forced peripheral mode */ #define GUSBCFG_CTXPKT_Pos (31U) -#define GUSBCFG_CTXPKT_Msk (0x1UL << GUSBCFG_CTXPKT_Pos) /*!< 0x80000000 */ -#define GUSBCFG_CTXPKT GUSBCFG_CTXPKT_Msk /*!< Corrupt Tx packet */ +#define GUSBCFG_CTXPKT_Msk (0x1UL << GUSBCFG_CTXPKT_Pos) /*!< 0x80000000 */ +#define GUSBCFG_CTXPKT GUSBCFG_CTXPKT_Msk /*!< Corrupt Tx packet */ /******************** Bit definition for GRSTCTL register ********************/ #define GRSTCTL_CSRST_Pos (0U) -#define GRSTCTL_CSRST_Msk (0x1UL << GRSTCTL_CSRST_Pos) /*!< 0x00000001 */ -#define GRSTCTL_CSRST GRSTCTL_CSRST_Msk /*!< Core soft reset */ +#define GRSTCTL_CSRST_Msk (0x1UL << GRSTCTL_CSRST_Pos) /*!< 0x00000001 */ +#define GRSTCTL_CSRST GRSTCTL_CSRST_Msk /*!< Core soft reset */ #define GRSTCTL_HSRST_Pos (1U) -#define GRSTCTL_HSRST_Msk (0x1UL << GRSTCTL_HSRST_Pos) /*!< 0x00000002 */ -#define GRSTCTL_HSRST GRSTCTL_HSRST_Msk /*!< HCLK soft reset */ +#define GRSTCTL_HSRST_Msk (0x1UL << GRSTCTL_HSRST_Pos) /*!< 0x00000002 */ +#define GRSTCTL_HSRST GRSTCTL_HSRST_Msk /*!< HCLK soft reset */ #define GRSTCTL_FCRST_Pos (2U) -#define GRSTCTL_FCRST_Msk (0x1UL << GRSTCTL_FCRST_Pos) /*!< 0x00000004 */ -#define GRSTCTL_FCRST GRSTCTL_FCRST_Msk /*!< Host frame counter reset */ +#define GRSTCTL_FCRST_Msk (0x1UL << GRSTCTL_FCRST_Pos) /*!< 0x00000004 */ +#define GRSTCTL_FCRST GRSTCTL_FCRST_Msk /*!< Host frame counter reset */ #define GRSTCTL_RXFFLSH_Pos (4U) -#define GRSTCTL_RXFFLSH_Msk (0x1UL << GRSTCTL_RXFFLSH_Pos) /*!< 0x00000010 */ -#define GRSTCTL_RXFFLSH GRSTCTL_RXFFLSH_Msk /*!< RxFIFO flush */ +#define GRSTCTL_RXFFLSH_Msk (0x1UL << GRSTCTL_RXFFLSH_Pos) /*!< 0x00000010 */ +#define GRSTCTL_RXFFLSH GRSTCTL_RXFFLSH_Msk /*!< RxFIFO flush */ #define GRSTCTL_TXFFLSH_Pos (5U) -#define GRSTCTL_TXFFLSH_Msk (0x1UL << GRSTCTL_TXFFLSH_Pos) /*!< 0x00000020 */ -#define GRSTCTL_TXFFLSH GRSTCTL_TXFFLSH_Msk /*!< TxFIFO flush */ +#define GRSTCTL_TXFFLSH_Msk (0x1UL << GRSTCTL_TXFFLSH_Pos) /*!< 0x00000020 */ +#define GRSTCTL_TXFFLSH GRSTCTL_TXFFLSH_Msk /*!< TxFIFO flush */ #define GRSTCTL_TXFNUM_Pos (6U) -#define GRSTCTL_TXFNUM_Msk (0x1FUL << GRSTCTL_TXFNUM_Pos) /*!< 0x000007C0 */ -#define GRSTCTL_TXFNUM GRSTCTL_TXFNUM_Msk /*!< TxFIFO number */ -#define GRSTCTL_TXFNUM_0 (0x01UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000040 */ -#define GRSTCTL_TXFNUM_1 (0x02UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000080 */ -#define GRSTCTL_TXFNUM_2 (0x04UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000100 */ -#define GRSTCTL_TXFNUM_3 (0x08UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000200 */ -#define GRSTCTL_TXFNUM_4 (0x10UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000400 */ +#define GRSTCTL_TXFNUM_Msk (0x1FUL << GRSTCTL_TXFNUM_Pos) /*!< 0x000007C0 */ +#define GRSTCTL_TXFNUM GRSTCTL_TXFNUM_Msk /*!< TxFIFO number */ +#define GRSTCTL_TXFNUM_0 (0x01UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000040 */ +#define GRSTCTL_TXFNUM_1 (0x02UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000080 */ +#define GRSTCTL_TXFNUM_2 (0x04UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000100 */ +#define GRSTCTL_TXFNUM_3 (0x08UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000200 */ +#define GRSTCTL_TXFNUM_4 (0x10UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000400 */ #define GRSTCTL_DMAREQ_Pos (30U) -#define GRSTCTL_DMAREQ_Msk (0x1UL << GRSTCTL_DMAREQ_Pos) /*!< 0x40000000 */ -#define GRSTCTL_DMAREQ GRSTCTL_DMAREQ_Msk /*!< DMA request signal */ +#define GRSTCTL_DMAREQ_Msk (0x1UL << GRSTCTL_DMAREQ_Pos) /*!< 0x40000000 */ +#define GRSTCTL_DMAREQ GRSTCTL_DMAREQ_Msk /*!< DMA request signal */ #define GRSTCTL_AHBIDL_Pos (31U) -#define GRSTCTL_AHBIDL_Msk (0x1UL << GRSTCTL_AHBIDL_Pos) /*!< 0x80000000 */ -#define GRSTCTL_AHBIDL GRSTCTL_AHBIDL_Msk /*!< AHB master idle */ +#define GRSTCTL_AHBIDL_Msk (0x1UL << GRSTCTL_AHBIDL_Pos) /*!< 0x80000000 */ +#define GRSTCTL_AHBIDL GRSTCTL_AHBIDL_Msk /*!< AHB master idle */ /******************** Bit definition for DIEPMSK register ********************/ #define DIEPMSK_XFRCM_Pos (0U) -#define DIEPMSK_XFRCM_Msk (0x1UL << DIEPMSK_XFRCM_Pos) /*!< 0x00000001 */ -#define DIEPMSK_XFRCM DIEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define DIEPMSK_XFRCM_Msk (0x1UL << DIEPMSK_XFRCM_Pos) /*!< 0x00000001 */ +#define DIEPMSK_XFRCM DIEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ #define DIEPMSK_EPDM_Pos (1U) -#define DIEPMSK_EPDM_Msk (0x1UL << DIEPMSK_EPDM_Pos) /*!< 0x00000002 */ -#define DIEPMSK_EPDM DIEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define DIEPMSK_EPDM_Msk (0x1UL << DIEPMSK_EPDM_Pos) /*!< 0x00000002 */ +#define DIEPMSK_EPDM DIEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ #define DIEPMSK_TOM_Pos (3U) -#define DIEPMSK_TOM_Msk (0x1UL << DIEPMSK_TOM_Pos) /*!< 0x00000008 */ -#define DIEPMSK_TOM DIEPMSK_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ +#define DIEPMSK_TOM_Msk (0x1UL << DIEPMSK_TOM_Pos) /*!< 0x00000008 */ +#define DIEPMSK_TOM DIEPMSK_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ #define DIEPMSK_ITTXFEMSK_Pos (4U) -#define DIEPMSK_ITTXFEMSK_Msk (0x1UL << DIEPMSK_ITTXFEMSK_Pos) /*!< 0x00000010 */ -#define DIEPMSK_ITTXFEMSK DIEPMSK_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define DIEPMSK_ITTXFEMSK_Msk (0x1UL << DIEPMSK_ITTXFEMSK_Pos) /*!< 0x00000010 */ +#define DIEPMSK_ITTXFEMSK DIEPMSK_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ #define DIEPMSK_INEPNMM_Pos (5U) -#define DIEPMSK_INEPNMM_Msk (0x1UL << DIEPMSK_INEPNMM_Pos) /*!< 0x00000020 */ -#define DIEPMSK_INEPNMM DIEPMSK_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define DIEPMSK_INEPNMM_Msk (0x1UL << DIEPMSK_INEPNMM_Pos) /*!< 0x00000020 */ +#define DIEPMSK_INEPNMM DIEPMSK_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ #define DIEPMSK_INEPNEM_Pos (6U) -#define DIEPMSK_INEPNEM_Msk (0x1UL << DIEPMSK_INEPNEM_Pos) /*!< 0x00000040 */ -#define DIEPMSK_INEPNEM DIEPMSK_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define DIEPMSK_INEPNEM_Msk (0x1UL << DIEPMSK_INEPNEM_Pos) /*!< 0x00000040 */ +#define DIEPMSK_INEPNEM DIEPMSK_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ #define DIEPMSK_TXFURM_Pos (8U) -#define DIEPMSK_TXFURM_Msk (0x1UL << DIEPMSK_TXFURM_Pos) /*!< 0x00000100 */ -#define DIEPMSK_TXFURM DIEPMSK_TXFURM_Msk /*!< FIFO underrun mask */ +#define DIEPMSK_TXFURM_Msk (0x1UL << DIEPMSK_TXFURM_Pos) /*!< 0x00000100 */ +#define DIEPMSK_TXFURM DIEPMSK_TXFURM_Msk /*!< FIFO underrun mask */ #define DIEPMSK_BIM_Pos (9U) -#define DIEPMSK_BIM_Msk (0x1UL << DIEPMSK_BIM_Pos) /*!< 0x00000200 */ -#define DIEPMSK_BIM DIEPMSK_BIM_Msk /*!< BNA interrupt mask */ +#define DIEPMSK_BIM_Msk (0x1UL << DIEPMSK_BIM_Pos) /*!< 0x00000200 */ +#define DIEPMSK_BIM DIEPMSK_BIM_Msk /*!< BNA interrupt mask */ /******************** Bit definition for HPTXSTS register ********************/ #define HPTXSTS_PTXFSAVL_Pos (0U) -#define HPTXSTS_PTXFSAVL_Msk (0xFFFFUL << HPTXSTS_PTXFSAVL_Pos) /*!< 0x0000FFFF */ -#define HPTXSTS_PTXFSAVL HPTXSTS_PTXFSAVL_Msk /*!< Periodic transmit data FIFO space available */ +#define HPTXSTS_PTXFSAVL_Msk (0xFFFFUL << HPTXSTS_PTXFSAVL_Pos) /*!< 0x0000FFFF */ +#define HPTXSTS_PTXFSAVL HPTXSTS_PTXFSAVL_Msk /*!< Periodic transmit data FIFO space available */ #define HPTXSTS_PTXQSAV_Pos (16U) -#define HPTXSTS_PTXQSAV_Msk (0xFFUL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00FF0000 */ -#define HPTXSTS_PTXQSAV HPTXSTS_PTXQSAV_Msk /*!< Periodic transmit request queue space available */ -#define HPTXSTS_PTXQSAV_0 (0x01UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00010000 */ -#define HPTXSTS_PTXQSAV_1 (0x02UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00020000 */ -#define HPTXSTS_PTXQSAV_2 (0x04UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00040000 */ -#define HPTXSTS_PTXQSAV_3 (0x08UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00080000 */ -#define HPTXSTS_PTXQSAV_4 (0x10UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00100000 */ -#define HPTXSTS_PTXQSAV_5 (0x20UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00200000 */ -#define HPTXSTS_PTXQSAV_6 (0x40UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00400000 */ -#define HPTXSTS_PTXQSAV_7 (0x80UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00800000 */ +#define HPTXSTS_PTXQSAV_Msk (0xFFUL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00FF0000 */ +#define HPTXSTS_PTXQSAV HPTXSTS_PTXQSAV_Msk /*!< Periodic transmit request queue space available */ +#define HPTXSTS_PTXQSAV_0 (0x01UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00010000 */ +#define HPTXSTS_PTXQSAV_1 (0x02UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00020000 */ +#define HPTXSTS_PTXQSAV_2 (0x04UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00040000 */ +#define HPTXSTS_PTXQSAV_3 (0x08UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00080000 */ +#define HPTXSTS_PTXQSAV_4 (0x10UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00100000 */ +#define HPTXSTS_PTXQSAV_5 (0x20UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00200000 */ +#define HPTXSTS_PTXQSAV_6 (0x40UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00400000 */ +#define HPTXSTS_PTXQSAV_7 (0x80UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00800000 */ #define HPTXSTS_PTXQTOP_Pos (24U) -#define HPTXSTS_PTXQTOP_Msk (0xFFUL << HPTXSTS_PTXQTOP_Pos) /*!< 0xFF000000 */ -#define HPTXSTS_PTXQTOP HPTXSTS_PTXQTOP_Msk /*!< Top of the periodic transmit request queue */ -#define HPTXSTS_PTXQTOP_0 (0x01UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x01000000 */ -#define HPTXSTS_PTXQTOP_1 (0x02UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x02000000 */ -#define HPTXSTS_PTXQTOP_2 (0x04UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x04000000 */ -#define HPTXSTS_PTXQTOP_3 (0x08UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x08000000 */ -#define HPTXSTS_PTXQTOP_4 (0x10UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x10000000 */ -#define HPTXSTS_PTXQTOP_5 (0x20UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x20000000 */ -#define HPTXSTS_PTXQTOP_6 (0x40UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x40000000 */ -#define HPTXSTS_PTXQTOP_7 (0x80UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x80000000 */ +#define HPTXSTS_PTXQTOP_Msk (0xFFUL << HPTXSTS_PTXQTOP_Pos) /*!< 0xFF000000 */ +#define HPTXSTS_PTXQTOP HPTXSTS_PTXQTOP_Msk /*!< Top of the periodic transmit request queue */ +#define HPTXSTS_PTXQTOP_0 (0x01UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x01000000 */ +#define HPTXSTS_PTXQTOP_1 (0x02UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x02000000 */ +#define HPTXSTS_PTXQTOP_2 (0x04UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x04000000 */ +#define HPTXSTS_PTXQTOP_3 (0x08UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x08000000 */ +#define HPTXSTS_PTXQTOP_4 (0x10UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x10000000 */ +#define HPTXSTS_PTXQTOP_5 (0x20UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x20000000 */ +#define HPTXSTS_PTXQTOP_6 (0x40UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x40000000 */ +#define HPTXSTS_PTXQTOP_7 (0x80UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x80000000 */ /******************** Bit definition for HAINT register ********************/ #define HAINT_HAINT_Pos (0U) -#define HAINT_HAINT_Msk (0xFFFFUL << HAINT_HAINT_Pos) /*!< 0x0000FFFF */ -#define HAINT_HAINT HAINT_HAINT_Msk /*!< Channel interrupts */ +#define HAINT_HAINT_Msk (0xFFFFUL << HAINT_HAINT_Pos) /*!< 0x0000FFFF */ +#define HAINT_HAINT HAINT_HAINT_Msk /*!< Channel interrupts */ /******************** Bit definition for DOEPMSK register ********************/ #define DOEPMSK_XFRCM_Pos (0U) -#define DOEPMSK_XFRCM_Msk (0x1UL << DOEPMSK_XFRCM_Pos) /*!< 0x00000001 */ -#define DOEPMSK_XFRCM DOEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define DOEPMSK_XFRCM_Msk (0x1UL << DOEPMSK_XFRCM_Pos) /*!< 0x00000001 */ +#define DOEPMSK_XFRCM DOEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ #define DOEPMSK_EPDM_Pos (1U) -#define DOEPMSK_EPDM_Msk (0x1UL << DOEPMSK_EPDM_Pos) /*!< 0x00000002 */ -#define DOEPMSK_EPDM DOEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define DOEPMSK_EPDM_Msk (0x1UL << DOEPMSK_EPDM_Pos) /*!< 0x00000002 */ +#define DOEPMSK_EPDM DOEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ #define DOEPMSK_AHBERRM_Pos (2U) -#define DOEPMSK_AHBERRM_Msk (0x1UL << DOEPMSK_AHBERRM_Pos) /*!< 0x00000004 */ -#define DOEPMSK_AHBERRM DOEPMSK_AHBERRM_Msk /*!< OUT transaction AHB Error interrupt mask */ +#define DOEPMSK_AHBERRM_Msk (0x1UL << DOEPMSK_AHBERRM_Pos) /*!< 0x00000004 */ +#define DOEPMSK_AHBERRM DOEPMSK_AHBERRM_Msk /*!< OUT transaction AHB Error interrupt mask */ #define DOEPMSK_STUPM_Pos (3U) -#define DOEPMSK_STUPM_Msk (0x1UL << DOEPMSK_STUPM_Pos) /*!< 0x00000008 */ -#define DOEPMSK_STUPM DOEPMSK_STUPM_Msk /*!< SETUP phase done mask */ +#define DOEPMSK_STUPM_Msk (0x1UL << DOEPMSK_STUPM_Pos) /*!< 0x00000008 */ +#define DOEPMSK_STUPM DOEPMSK_STUPM_Msk /*!< SETUP phase done mask */ #define DOEPMSK_OTEPDM_Pos (4U) -#define DOEPMSK_OTEPDM_Msk (0x1UL << DOEPMSK_OTEPDM_Pos) /*!< 0x00000010 */ -#define DOEPMSK_OTEPDM DOEPMSK_OTEPDM_Msk /*!< OUT token received when endpoint disabled mask */ +#define DOEPMSK_OTEPDM_Msk (0x1UL << DOEPMSK_OTEPDM_Pos) /*!< 0x00000010 */ +#define DOEPMSK_OTEPDM DOEPMSK_OTEPDM_Msk /*!< OUT token received when endpoint disabled mask */ #define DOEPMSK_OTEPSPRM_Pos (5U) -#define DOEPMSK_OTEPSPRM_Msk (0x1UL << DOEPMSK_OTEPSPRM_Pos) /*!< 0x00000020 */ -#define DOEPMSK_OTEPSPRM DOEPMSK_OTEPSPRM_Msk /*!< Status Phase Received mask */ +#define DOEPMSK_OTEPSPRM_Msk (0x1UL << DOEPMSK_OTEPSPRM_Pos) /*!< 0x00000020 */ +#define DOEPMSK_OTEPSPRM DOEPMSK_OTEPSPRM_Msk /*!< Status Phase Received mask */ #define DOEPMSK_B2BSTUP_Pos (6U) -#define DOEPMSK_B2BSTUP_Msk (0x1UL << DOEPMSK_B2BSTUP_Pos) /*!< 0x00000040 */ -#define DOEPMSK_B2BSTUP DOEPMSK_B2BSTUP_Msk /*!< Back-to-back SETUP packets received mask */ +#define DOEPMSK_B2BSTUP_Msk (0x1UL << DOEPMSK_B2BSTUP_Pos) /*!< 0x00000040 */ +#define DOEPMSK_B2BSTUP DOEPMSK_B2BSTUP_Msk /*!< Back-to-back SETUP packets received mask */ #define DOEPMSK_OPEM_Pos (8U) -#define DOEPMSK_OPEM_Msk (0x1UL << DOEPMSK_OPEM_Pos) /*!< 0x00000100 */ -#define DOEPMSK_OPEM DOEPMSK_OPEM_Msk /*!< OUT packet error mask */ +#define DOEPMSK_OPEM_Msk (0x1UL << DOEPMSK_OPEM_Pos) /*!< 0x00000100 */ +#define DOEPMSK_OPEM DOEPMSK_OPEM_Msk /*!< OUT packet error mask */ #define DOEPMSK_BOIM_Pos (9U) -#define DOEPMSK_BOIM_Msk (0x1UL << DOEPMSK_BOIM_Pos) /*!< 0x00000200 */ -#define DOEPMSK_BOIM DOEPMSK_BOIM_Msk /*!< BNA interrupt mask */ +#define DOEPMSK_BOIM_Msk (0x1UL << DOEPMSK_BOIM_Pos) /*!< 0x00000200 */ +#define DOEPMSK_BOIM DOEPMSK_BOIM_Msk /*!< BNA interrupt mask */ #define DOEPMSK_BERRM_Pos (12U) -#define DOEPMSK_BERRM_Msk (0x1UL << DOEPMSK_BERRM_Pos) /*!< 0x00001000 */ -#define DOEPMSK_BERRM DOEPMSK_BERRM_Msk /*!< Babble error interrupt mask */ +#define DOEPMSK_BERRM_Msk (0x1UL << DOEPMSK_BERRM_Pos) /*!< 0x00001000 */ +#define DOEPMSK_BERRM DOEPMSK_BERRM_Msk /*!< Babble error interrupt mask */ #define DOEPMSK_NAKM_Pos (13U) -#define DOEPMSK_NAKM_Msk (0x1UL << DOEPMSK_NAKM_Pos) /*!< 0x00002000 */ -#define DOEPMSK_NAKM DOEPMSK_NAKM_Msk /*!< OUT Packet NAK interrupt mask */ +#define DOEPMSK_NAKM_Msk (0x1UL << DOEPMSK_NAKM_Pos) /*!< 0x00002000 */ +#define DOEPMSK_NAKM DOEPMSK_NAKM_Msk /*!< OUT Packet NAK interrupt mask */ #define DOEPMSK_NYETM_Pos (14U) -#define DOEPMSK_NYETM_Msk (0x1UL << DOEPMSK_NYETM_Pos) /*!< 0x00004000 */ -#define DOEPMSK_NYETM DOEPMSK_NYETM_Msk /*!< NYET interrupt mask */ +#define DOEPMSK_NYETM_Msk (0x1UL << DOEPMSK_NYETM_Pos) /*!< 0x00004000 */ +#define DOEPMSK_NYETM DOEPMSK_NYETM_Msk /*!< NYET interrupt mask */ /******************** Bit definition for GINTSTS register ********************/ #define GINTSTS_CMOD_Pos (0U) -#define GINTSTS_CMOD_Msk (0x1UL << GINTSTS_CMOD_Pos) /*!< 0x00000001 */ -#define GINTSTS_CMOD GINTSTS_CMOD_Msk /*!< Current mode of operation */ +#define GINTSTS_CMOD_Msk (0x1UL << GINTSTS_CMOD_Pos) /*!< 0x00000001 */ +#define GINTSTS_CMOD GINTSTS_CMOD_Msk /*!< Current mode of operation */ #define GINTSTS_MMIS_Pos (1U) -#define GINTSTS_MMIS_Msk (0x1UL << GINTSTS_MMIS_Pos) /*!< 0x00000002 */ -#define GINTSTS_MMIS GINTSTS_MMIS_Msk /*!< Mode mismatch interrupt */ +#define GINTSTS_MMIS_Msk (0x1UL << GINTSTS_MMIS_Pos) /*!< 0x00000002 */ +#define GINTSTS_MMIS GINTSTS_MMIS_Msk /*!< Mode mismatch interrupt */ #define GINTSTS_OTGINT_Pos (2U) -#define GINTSTS_OTGINT_Msk (0x1UL << GINTSTS_OTGINT_Pos) /*!< 0x00000004 */ -#define GINTSTS_OTGINT GINTSTS_OTGINT_Msk /*!< OTG interrupt */ +#define GINTSTS_OTGINT_Msk (0x1UL << GINTSTS_OTGINT_Pos) /*!< 0x00000004 */ +#define GINTSTS_OTGINT GINTSTS_OTGINT_Msk /*!< OTG interrupt */ #define GINTSTS_SOF_Pos (3U) -#define GINTSTS_SOF_Msk (0x1UL << GINTSTS_SOF_Pos) /*!< 0x00000008 */ -#define GINTSTS_SOF GINTSTS_SOF_Msk /*!< Start of frame */ +#define GINTSTS_SOF_Msk (0x1UL << GINTSTS_SOF_Pos) /*!< 0x00000008 */ +#define GINTSTS_SOF GINTSTS_SOF_Msk /*!< Start of frame */ #define GINTSTS_RXFLVL_Pos (4U) -#define GINTSTS_RXFLVL_Msk (0x1UL << GINTSTS_RXFLVL_Pos) /*!< 0x00000010 */ -#define GINTSTS_RXFLVL GINTSTS_RXFLVL_Msk /*!< RxFIFO nonempty */ +#define GINTSTS_RXFLVL_Msk (0x1UL << GINTSTS_RXFLVL_Pos) /*!< 0x00000010 */ +#define GINTSTS_RXFLVL GINTSTS_RXFLVL_Msk /*!< RxFIFO nonempty */ #define GINTSTS_NPTXFE_Pos (5U) -#define GINTSTS_NPTXFE_Msk (0x1UL << GINTSTS_NPTXFE_Pos) /*!< 0x00000020 */ -#define GINTSTS_NPTXFE GINTSTS_NPTXFE_Msk /*!< Nonperiodic TxFIFO empty */ +#define GINTSTS_NPTXFE_Msk (0x1UL << GINTSTS_NPTXFE_Pos) /*!< 0x00000020 */ +#define GINTSTS_NPTXFE GINTSTS_NPTXFE_Msk /*!< Nonperiodic TxFIFO empty */ #define GINTSTS_GINAKEFF_Pos (6U) -#define GINTSTS_GINAKEFF_Msk (0x1UL << GINTSTS_GINAKEFF_Pos) /*!< 0x00000040 */ -#define GINTSTS_GINAKEFF GINTSTS_GINAKEFF_Msk /*!< Global IN nonperiodic NAK effective */ +#define GINTSTS_GINAKEFF_Msk (0x1UL << GINTSTS_GINAKEFF_Pos) /*!< 0x00000040 */ +#define GINTSTS_GINAKEFF GINTSTS_GINAKEFF_Msk /*!< Global IN nonperiodic NAK effective */ #define GINTSTS_BOUTNAKEFF_Pos (7U) -#define GINTSTS_BOUTNAKEFF_Msk (0x1UL << GINTSTS_BOUTNAKEFF_Pos) /*!< 0x00000080 */ -#define GINTSTS_BOUTNAKEFF GINTSTS_BOUTNAKEFF_Msk /*!< Global OUT NAK effective */ +#define GINTSTS_BOUTNAKEFF_Msk (0x1UL << GINTSTS_BOUTNAKEFF_Pos) /*!< 0x00000080 */ +#define GINTSTS_BOUTNAKEFF GINTSTS_BOUTNAKEFF_Msk /*!< Global OUT NAK effective */ #define GINTSTS_ESUSP_Pos (10U) -#define GINTSTS_ESUSP_Msk (0x1UL << GINTSTS_ESUSP_Pos) /*!< 0x00000400 */ -#define GINTSTS_ESUSP GINTSTS_ESUSP_Msk /*!< Early suspend */ +#define GINTSTS_ESUSP_Msk (0x1UL << GINTSTS_ESUSP_Pos) /*!< 0x00000400 */ +#define GINTSTS_ESUSP GINTSTS_ESUSP_Msk /*!< Early suspend */ #define GINTSTS_USBSUSP_Pos (11U) -#define GINTSTS_USBSUSP_Msk (0x1UL << GINTSTS_USBSUSP_Pos) /*!< 0x00000800 */ -#define GINTSTS_USBSUSP GINTSTS_USBSUSP_Msk /*!< USB suspend */ +#define GINTSTS_USBSUSP_Msk (0x1UL << GINTSTS_USBSUSP_Pos) /*!< 0x00000800 */ +#define GINTSTS_USBSUSP GINTSTS_USBSUSP_Msk /*!< USB suspend */ #define GINTSTS_USBRST_Pos (12U) -#define GINTSTS_USBRST_Msk (0x1UL << GINTSTS_USBRST_Pos) /*!< 0x00001000 */ -#define GINTSTS_USBRST GINTSTS_USBRST_Msk /*!< USB reset */ +#define GINTSTS_USBRST_Msk (0x1UL << GINTSTS_USBRST_Pos) /*!< 0x00001000 */ +#define GINTSTS_USBRST GINTSTS_USBRST_Msk /*!< USB reset */ #define GINTSTS_ENUMDNE_Pos (13U) -#define GINTSTS_ENUMDNE_Msk (0x1UL << GINTSTS_ENUMDNE_Pos) /*!< 0x00002000 */ -#define GINTSTS_ENUMDNE GINTSTS_ENUMDNE_Msk /*!< Enumeration done */ +#define GINTSTS_ENUMDNE_Msk (0x1UL << GINTSTS_ENUMDNE_Pos) /*!< 0x00002000 */ +#define GINTSTS_ENUMDNE GINTSTS_ENUMDNE_Msk /*!< Enumeration done */ #define GINTSTS_ISOODRP_Pos (14U) -#define GINTSTS_ISOODRP_Msk (0x1UL << GINTSTS_ISOODRP_Pos) /*!< 0x00004000 */ -#define GINTSTS_ISOODRP GINTSTS_ISOODRP_Msk /*!< Isochronous OUT packet dropped interrupt */ +#define GINTSTS_ISOODRP_Msk (0x1UL << GINTSTS_ISOODRP_Pos) /*!< 0x00004000 */ +#define GINTSTS_ISOODRP GINTSTS_ISOODRP_Msk /*!< Isochronous OUT packet dropped interrupt */ #define GINTSTS_EOPF_Pos (15U) -#define GINTSTS_EOPF_Msk (0x1UL << GINTSTS_EOPF_Pos) /*!< 0x00008000 */ -#define GINTSTS_EOPF GINTSTS_EOPF_Msk /*!< End of periodic frame interrupt */ +#define GINTSTS_EOPF_Msk (0x1UL << GINTSTS_EOPF_Pos) /*!< 0x00008000 */ +#define GINTSTS_EOPF GINTSTS_EOPF_Msk /*!< End of periodic frame interrupt */ #define GINTSTS_IEPINT_Pos (18U) -#define GINTSTS_IEPINT_Msk (0x1UL << GINTSTS_IEPINT_Pos) /*!< 0x00040000 */ -#define GINTSTS_IEPINT GINTSTS_IEPINT_Msk /*!< IN endpoint interrupt */ +#define GINTSTS_IEPINT_Msk (0x1UL << GINTSTS_IEPINT_Pos) /*!< 0x00040000 */ +#define GINTSTS_IEPINT GINTSTS_IEPINT_Msk /*!< IN endpoint interrupt */ #define GINTSTS_OEPINT_Pos (19U) -#define GINTSTS_OEPINT_Msk (0x1UL << GINTSTS_OEPINT_Pos) /*!< 0x00080000 */ -#define GINTSTS_OEPINT GINTSTS_OEPINT_Msk /*!< OUT endpoint interrupt */ +#define GINTSTS_OEPINT_Msk (0x1UL << GINTSTS_OEPINT_Pos) /*!< 0x00080000 */ +#define GINTSTS_OEPINT GINTSTS_OEPINT_Msk /*!< OUT endpoint interrupt */ #define GINTSTS_IISOIXFR_Pos (20U) -#define GINTSTS_IISOIXFR_Msk (0x1UL << GINTSTS_IISOIXFR_Pos) /*!< 0x00100000 */ -#define GINTSTS_IISOIXFR GINTSTS_IISOIXFR_Msk /*!< Incomplete isochronous IN transfer */ +#define GINTSTS_IISOIXFR_Msk (0x1UL << GINTSTS_IISOIXFR_Pos) /*!< 0x00100000 */ +#define GINTSTS_IISOIXFR GINTSTS_IISOIXFR_Msk /*!< Incomplete isochronous IN transfer */ #define GINTSTS_PXFR_INCOMPISOOUT_Pos (21U) #define GINTSTS_PXFR_INCOMPISOOUT_Msk (0x1UL << GINTSTS_PXFR_INCOMPISOOUT_Pos) /*!< 0x00200000 */ -#define GINTSTS_PXFR_INCOMPISOOUT GINTSTS_PXFR_INCOMPISOOUT_Msk /*!< Incomplete periodic transfer */ +#define GINTSTS_PXFR_INCOMPISOOUT GINTSTS_PXFR_INCOMPISOOUT_Msk /*!< Incomplete periodic transfer */ #define GINTSTS_DATAFSUSP_Pos (22U) -#define GINTSTS_DATAFSUSP_Msk (0x1UL << GINTSTS_DATAFSUSP_Pos) /*!< 0x00400000 */ -#define GINTSTS_DATAFSUSP GINTSTS_DATAFSUSP_Msk /*!< Data fetch suspended */ +#define GINTSTS_DATAFSUSP_Msk (0x1UL << GINTSTS_DATAFSUSP_Pos) /*!< 0x00400000 */ +#define GINTSTS_DATAFSUSP GINTSTS_DATAFSUSP_Msk /*!< Data fetch suspended */ #define GINTSTS_RSTDET_Pos (23U) -#define GINTSTS_RSTDET_Msk (0x1UL << GINTSTS_RSTDET_Pos) /*!< 0x00800000 */ -#define GINTSTS_RSTDET GINTSTS_RSTDET_Msk /*!< Reset detected interrupt */ +#define GINTSTS_RSTDET_Msk (0x1UL << GINTSTS_RSTDET_Pos) /*!< 0x00800000 */ +#define GINTSTS_RSTDET GINTSTS_RSTDET_Msk /*!< Reset detected interrupt */ #define GINTSTS_HPRTINT_Pos (24U) -#define GINTSTS_HPRTINT_Msk (0x1UL << GINTSTS_HPRTINT_Pos) /*!< 0x01000000 */ -#define GINTSTS_HPRTINT GINTSTS_HPRTINT_Msk /*!< Host port interrupt */ +#define GINTSTS_HPRTINT_Msk (0x1UL << GINTSTS_HPRTINT_Pos) /*!< 0x01000000 */ +#define GINTSTS_HPRTINT GINTSTS_HPRTINT_Msk /*!< Host port interrupt */ #define GINTSTS_HCINT_Pos (25U) -#define GINTSTS_HCINT_Msk (0x1UL << GINTSTS_HCINT_Pos) /*!< 0x02000000 */ -#define GINTSTS_HCINT GINTSTS_HCINT_Msk /*!< Host channels interrupt */ +#define GINTSTS_HCINT_Msk (0x1UL << GINTSTS_HCINT_Pos) /*!< 0x02000000 */ +#define GINTSTS_HCINT GINTSTS_HCINT_Msk /*!< Host channels interrupt */ #define GINTSTS_PTXFE_Pos (26U) -#define GINTSTS_PTXFE_Msk (0x1UL << GINTSTS_PTXFE_Pos) /*!< 0x04000000 */ -#define GINTSTS_PTXFE GINTSTS_PTXFE_Msk /*!< Periodic TxFIFO empty */ +#define GINTSTS_PTXFE_Msk (0x1UL << GINTSTS_PTXFE_Pos) /*!< 0x04000000 */ +#define GINTSTS_PTXFE GINTSTS_PTXFE_Msk /*!< Periodic TxFIFO empty */ #define GINTSTS_LPMINT_Pos (27U) -#define GINTSTS_LPMINT_Msk (0x1UL << GINTSTS_LPMINT_Pos) /*!< 0x08000000 */ -#define GINTSTS_LPMINT GINTSTS_LPMINT_Msk /*!< LPM interrupt */ +#define GINTSTS_LPMINT_Msk (0x1UL << GINTSTS_LPMINT_Pos) /*!< 0x08000000 */ +#define GINTSTS_LPMINT GINTSTS_LPMINT_Msk /*!< LPM interrupt */ #define GINTSTS_CIDSCHG_Pos (28U) -#define GINTSTS_CIDSCHG_Msk (0x1UL << GINTSTS_CIDSCHG_Pos) /*!< 0x10000000 */ -#define GINTSTS_CIDSCHG GINTSTS_CIDSCHG_Msk /*!< Connector ID status change */ +#define GINTSTS_CIDSCHG_Msk (0x1UL << GINTSTS_CIDSCHG_Pos) /*!< 0x10000000 */ +#define GINTSTS_CIDSCHG GINTSTS_CIDSCHG_Msk /*!< Connector ID status change */ #define GINTSTS_DISCINT_Pos (29U) -#define GINTSTS_DISCINT_Msk (0x1UL << GINTSTS_DISCINT_Pos) /*!< 0x20000000 */ -#define GINTSTS_DISCINT GINTSTS_DISCINT_Msk /*!< Disconnect detected interrupt */ +#define GINTSTS_DISCINT_Msk (0x1UL << GINTSTS_DISCINT_Pos) /*!< 0x20000000 */ +#define GINTSTS_DISCINT GINTSTS_DISCINT_Msk /*!< Disconnect detected interrupt */ #define GINTSTS_SRQINT_Pos (30U) -#define GINTSTS_SRQINT_Msk (0x1UL << GINTSTS_SRQINT_Pos) /*!< 0x40000000 */ -#define GINTSTS_SRQINT GINTSTS_SRQINT_Msk /*!< Session request/new session detected interrupt */ +#define GINTSTS_SRQINT_Msk (0x1UL << GINTSTS_SRQINT_Pos) /*!< 0x40000000 */ +#define GINTSTS_SRQINT GINTSTS_SRQINT_Msk /*!< Session request/new session detected interrupt */ #define GINTSTS_WKUINT_Pos (31U) -#define GINTSTS_WKUINT_Msk (0x1UL << GINTSTS_WKUINT_Pos) /*!< 0x80000000 */ -#define GINTSTS_WKUINT GINTSTS_WKUINT_Msk /*!< Resume/remote wakeup detected interrupt */ +#define GINTSTS_WKUINT_Msk (0x1UL << GINTSTS_WKUINT_Pos) /*!< 0x80000000 */ +#define GINTSTS_WKUINT GINTSTS_WKUINT_Msk /*!< Resume/remote wakeup detected interrupt */ /******************** Bit definition for GINTMSK register ********************/ #define GINTMSK_MMISM_Pos (1U) -#define GINTMSK_MMISM_Msk (0x1UL << GINTMSK_MMISM_Pos) /*!< 0x00000002 */ -#define GINTMSK_MMISM GINTMSK_MMISM_Msk /*!< Mode mismatch interrupt mask */ +#define GINTMSK_MMISM_Msk (0x1UL << GINTMSK_MMISM_Pos) /*!< 0x00000002 */ +#define GINTMSK_MMISM GINTMSK_MMISM_Msk /*!< Mode mismatch interrupt mask */ #define GINTMSK_OTGINT_Pos (2U) -#define GINTMSK_OTGINT_Msk (0x1UL << GINTMSK_OTGINT_Pos) /*!< 0x00000004 */ -#define GINTMSK_OTGINT GINTMSK_OTGINT_Msk /*!< OTG interrupt mask */ +#define GINTMSK_OTGINT_Msk (0x1UL << GINTMSK_OTGINT_Pos) /*!< 0x00000004 */ +#define GINTMSK_OTGINT GINTMSK_OTGINT_Msk /*!< OTG interrupt mask */ #define GINTMSK_SOFM_Pos (3U) -#define GINTMSK_SOFM_Msk (0x1UL << GINTMSK_SOFM_Pos) /*!< 0x00000008 */ -#define GINTMSK_SOFM GINTMSK_SOFM_Msk /*!< Start of frame mask */ +#define GINTMSK_SOFM_Msk (0x1UL << GINTMSK_SOFM_Pos) /*!< 0x00000008 */ +#define GINTMSK_SOFM GINTMSK_SOFM_Msk /*!< Start of frame mask */ #define GINTMSK_RXFLVLM_Pos (4U) -#define GINTMSK_RXFLVLM_Msk (0x1UL << GINTMSK_RXFLVLM_Pos) /*!< 0x00000010 */ -#define GINTMSK_RXFLVLM GINTMSK_RXFLVLM_Msk /*!< Receive FIFO nonempty mask */ +#define GINTMSK_RXFLVLM_Msk (0x1UL << GINTMSK_RXFLVLM_Pos) /*!< 0x00000010 */ +#define GINTMSK_RXFLVLM GINTMSK_RXFLVLM_Msk /*!< Receive FIFO nonempty mask */ #define GINTMSK_NPTXFEM_Pos (5U) -#define GINTMSK_NPTXFEM_Msk (0x1UL << GINTMSK_NPTXFEM_Pos) /*!< 0x00000020 */ -#define GINTMSK_NPTXFEM GINTMSK_NPTXFEM_Msk /*!< Nonperiodic TxFIFO empty mask */ +#define GINTMSK_NPTXFEM_Msk (0x1UL << GINTMSK_NPTXFEM_Pos) /*!< 0x00000020 */ +#define GINTMSK_NPTXFEM GINTMSK_NPTXFEM_Msk /*!< Nonperiodic TxFIFO empty mask */ #define GINTMSK_GINAKEFFM_Pos (6U) -#define GINTMSK_GINAKEFFM_Msk (0x1UL << GINTMSK_GINAKEFFM_Pos) /*!< 0x00000040 */ -#define GINTMSK_GINAKEFFM GINTMSK_GINAKEFFM_Msk /*!< Global nonperiodic IN NAK effective mask */ +#define GINTMSK_GINAKEFFM_Msk (0x1UL << GINTMSK_GINAKEFFM_Pos) /*!< 0x00000040 */ +#define GINTMSK_GINAKEFFM GINTMSK_GINAKEFFM_Msk /*!< Global nonperiodic IN NAK effective mask */ #define GINTMSK_GONAKEFFM_Pos (7U) -#define GINTMSK_GONAKEFFM_Msk (0x1UL << GINTMSK_GONAKEFFM_Pos) /*!< 0x00000080 */ -#define GINTMSK_GONAKEFFM GINTMSK_GONAKEFFM_Msk /*!< Global OUT NAK effective mask */ +#define GINTMSK_GONAKEFFM_Msk (0x1UL << GINTMSK_GONAKEFFM_Pos) /*!< 0x00000080 */ +#define GINTMSK_GONAKEFFM GINTMSK_GONAKEFFM_Msk /*!< Global OUT NAK effective mask */ #define GINTMSK_ESUSPM_Pos (10U) -#define GINTMSK_ESUSPM_Msk (0x1UL << GINTMSK_ESUSPM_Pos) /*!< 0x00000400 */ -#define GINTMSK_ESUSPM GINTMSK_ESUSPM_Msk /*!< Early suspend mask */ +#define GINTMSK_ESUSPM_Msk (0x1UL << GINTMSK_ESUSPM_Pos) /*!< 0x00000400 */ +#define GINTMSK_ESUSPM GINTMSK_ESUSPM_Msk /*!< Early suspend mask */ #define GINTMSK_USBSUSPM_Pos (11U) -#define GINTMSK_USBSUSPM_Msk (0x1UL << GINTMSK_USBSUSPM_Pos) /*!< 0x00000800 */ -#define GINTMSK_USBSUSPM GINTMSK_USBSUSPM_Msk /*!< USB suspend mask */ +#define GINTMSK_USBSUSPM_Msk (0x1UL << GINTMSK_USBSUSPM_Pos) /*!< 0x00000800 */ +#define GINTMSK_USBSUSPM GINTMSK_USBSUSPM_Msk /*!< USB suspend mask */ #define GINTMSK_USBRST_Pos (12U) -#define GINTMSK_USBRST_Msk (0x1UL << GINTMSK_USBRST_Pos) /*!< 0x00001000 */ -#define GINTMSK_USBRST GINTMSK_USBRST_Msk /*!< USB reset mask */ +#define GINTMSK_USBRST_Msk (0x1UL << GINTMSK_USBRST_Pos) /*!< 0x00001000 */ +#define GINTMSK_USBRST GINTMSK_USBRST_Msk /*!< USB reset mask */ #define GINTMSK_ENUMDNEM_Pos (13U) -#define GINTMSK_ENUMDNEM_Msk (0x1UL << GINTMSK_ENUMDNEM_Pos) /*!< 0x00002000 */ -#define GINTMSK_ENUMDNEM GINTMSK_ENUMDNEM_Msk /*!< Enumeration done mask */ +#define GINTMSK_ENUMDNEM_Msk (0x1UL << GINTMSK_ENUMDNEM_Pos) /*!< 0x00002000 */ +#define GINTMSK_ENUMDNEM GINTMSK_ENUMDNEM_Msk /*!< Enumeration done mask */ #define GINTMSK_ISOODRPM_Pos (14U) -#define GINTMSK_ISOODRPM_Msk (0x1UL << GINTMSK_ISOODRPM_Pos) /*!< 0x00004000 */ -#define GINTMSK_ISOODRPM GINTMSK_ISOODRPM_Msk /*!< Isochronous OUT packet dropped interrupt mask */ +#define GINTMSK_ISOODRPM_Msk (0x1UL << GINTMSK_ISOODRPM_Pos) /*!< 0x00004000 */ +#define GINTMSK_ISOODRPM GINTMSK_ISOODRPM_Msk /*!< Isochronous OUT packet dropped interrupt mask */ #define GINTMSK_EOPFM_Pos (15U) -#define GINTMSK_EOPFM_Msk (0x1UL << GINTMSK_EOPFM_Pos) /*!< 0x00008000 */ -#define GINTMSK_EOPFM GINTMSK_EOPFM_Msk /*!< End of periodic frame interrupt mask */ +#define GINTMSK_EOPFM_Msk (0x1UL << GINTMSK_EOPFM_Pos) /*!< 0x00008000 */ +#define GINTMSK_EOPFM GINTMSK_EOPFM_Msk /*!< End of periodic frame interrupt mask */ #define GINTMSK_EPMISM_Pos (17U) -#define GINTMSK_EPMISM_Msk (0x1UL << GINTMSK_EPMISM_Pos) /*!< 0x00020000 */ -#define GINTMSK_EPMISM GINTMSK_EPMISM_Msk /*!< Endpoint mismatch interrupt mask */ +#define GINTMSK_EPMISM_Msk (0x1UL << GINTMSK_EPMISM_Pos) /*!< 0x00020000 */ +#define GINTMSK_EPMISM GINTMSK_EPMISM_Msk /*!< Endpoint mismatch interrupt mask */ #define GINTMSK_IEPINT_Pos (18U) -#define GINTMSK_IEPINT_Msk (0x1UL << GINTMSK_IEPINT_Pos) /*!< 0x00040000 */ -#define GINTMSK_IEPINT GINTMSK_IEPINT_Msk /*!< IN endpoints interrupt mask */ +#define GINTMSK_IEPINT_Msk (0x1UL << GINTMSK_IEPINT_Pos) /*!< 0x00040000 */ +#define GINTMSK_IEPINT GINTMSK_IEPINT_Msk /*!< IN endpoints interrupt mask */ #define GINTMSK_OEPINT_Pos (19U) -#define GINTMSK_OEPINT_Msk (0x1UL << GINTMSK_OEPINT_Pos) /*!< 0x00080000 */ -#define GINTMSK_OEPINT GINTMSK_OEPINT_Msk /*!< OUT endpoints interrupt mask */ +#define GINTMSK_OEPINT_Msk (0x1UL << GINTMSK_OEPINT_Pos) /*!< 0x00080000 */ +#define GINTMSK_OEPINT GINTMSK_OEPINT_Msk /*!< OUT endpoints interrupt mask */ #define GINTMSK_IISOIXFRM_Pos (20U) -#define GINTMSK_IISOIXFRM_Msk (0x1UL << GINTMSK_IISOIXFRM_Pos) /*!< 0x00100000 */ -#define GINTMSK_IISOIXFRM GINTMSK_IISOIXFRM_Msk /*!< Incomplete isochronous IN transfer mask */ +#define GINTMSK_IISOIXFRM_Msk (0x1UL << GINTMSK_IISOIXFRM_Pos) /*!< 0x00100000 */ +#define GINTMSK_IISOIXFRM GINTMSK_IISOIXFRM_Msk /*!< Incomplete isochronous IN transfer mask */ #define GINTMSK_PXFRM_IISOOXFRM_Pos (21U) -#define GINTMSK_PXFRM_IISOOXFRM_Msk (0x1UL << GINTMSK_PXFRM_IISOOXFRM_Pos) /*!< 0x00200000 */ -#define GINTMSK_PXFRM_IISOOXFRM GINTMSK_PXFRM_IISOOXFRM_Msk /*!< Incomplete periodic transfer mask */ +#define GINTMSK_PXFRM_IISOOXFRM_Msk (0x1UL << GINTMSK_PXFRM_IISOOXFRM_Pos) /*!< 0x00200000 */ +#define GINTMSK_PXFRM_IISOOXFRM GINTMSK_PXFRM_IISOOXFRM_Msk /*!< Incomplete periodic transfer mask */ #define GINTMSK_FSUSPM_Pos (22U) -#define GINTMSK_FSUSPM_Msk (0x1UL << GINTMSK_FSUSPM_Pos) /*!< 0x00400000 */ -#define GINTMSK_FSUSPM GINTMSK_FSUSPM_Msk /*!< Data fetch suspended mask */ +#define GINTMSK_FSUSPM_Msk (0x1UL << GINTMSK_FSUSPM_Pos) /*!< 0x00400000 */ +#define GINTMSK_FSUSPM GINTMSK_FSUSPM_Msk /*!< Data fetch suspended mask */ #define GINTMSK_RSTDEM_Pos (23U) -#define GINTMSK_RSTDEM_Msk (0x1UL << GINTMSK_RSTDEM_Pos) /*!< 0x00800000 */ -#define GINTMSK_RSTDEM GINTMSK_RSTDEM_Msk /*!< Reset detected interrupt mask */ +#define GINTMSK_RSTDEM_Msk (0x1UL << GINTMSK_RSTDEM_Pos) /*!< 0x00800000 */ +#define GINTMSK_RSTDEM GINTMSK_RSTDEM_Msk /*!< Reset detected interrupt mask */ #define GINTMSK_PRTIM_Pos (24U) -#define GINTMSK_PRTIM_Msk (0x1UL << GINTMSK_PRTIM_Pos) /*!< 0x01000000 */ -#define GINTMSK_PRTIM GINTMSK_PRTIM_Msk /*!< Host port interrupt mask */ +#define GINTMSK_PRTIM_Msk (0x1UL << GINTMSK_PRTIM_Pos) /*!< 0x01000000 */ +#define GINTMSK_PRTIM GINTMSK_PRTIM_Msk /*!< Host port interrupt mask */ #define GINTMSK_HCIM_Pos (25U) -#define GINTMSK_HCIM_Msk (0x1UL << GINTMSK_HCIM_Pos) /*!< 0x02000000 */ -#define GINTMSK_HCIM GINTMSK_HCIM_Msk /*!< Host channels interrupt mask */ +#define GINTMSK_HCIM_Msk (0x1UL << GINTMSK_HCIM_Pos) /*!< 0x02000000 */ +#define GINTMSK_HCIM GINTMSK_HCIM_Msk /*!< Host channels interrupt mask */ #define GINTMSK_PTXFEM_Pos (26U) -#define GINTMSK_PTXFEM_Msk (0x1UL << GINTMSK_PTXFEM_Pos) /*!< 0x04000000 */ -#define GINTMSK_PTXFEM GINTMSK_PTXFEM_Msk /*!< Periodic TxFIFO empty mask */ +#define GINTMSK_PTXFEM_Msk (0x1UL << GINTMSK_PTXFEM_Pos) /*!< 0x04000000 */ +#define GINTMSK_PTXFEM GINTMSK_PTXFEM_Msk /*!< Periodic TxFIFO empty mask */ #define GINTMSK_LPMINTM_Pos (27U) -#define GINTMSK_LPMINTM_Msk (0x1UL << GINTMSK_LPMINTM_Pos) /*!< 0x08000000 */ -#define GINTMSK_LPMINTM GINTMSK_LPMINTM_Msk /*!< LPM interrupt Mask */ +#define GINTMSK_LPMINTM_Msk (0x1UL << GINTMSK_LPMINTM_Pos) /*!< 0x08000000 */ +#define GINTMSK_LPMINTM GINTMSK_LPMINTM_Msk /*!< LPM interrupt Mask */ #define GINTMSK_CIDSCHGM_Pos (28U) -#define GINTMSK_CIDSCHGM_Msk (0x1UL << GINTMSK_CIDSCHGM_Pos) /*!< 0x10000000 */ -#define GINTMSK_CIDSCHGM GINTMSK_CIDSCHGM_Msk /*!< Connector ID status change mask */ +#define GINTMSK_CIDSCHGM_Msk (0x1UL << GINTMSK_CIDSCHGM_Pos) /*!< 0x10000000 */ +#define GINTMSK_CIDSCHGM GINTMSK_CIDSCHGM_Msk /*!< Connector ID status change mask */ #define GINTMSK_DISCINT_Pos (29U) -#define GINTMSK_DISCINT_Msk (0x1UL << GINTMSK_DISCINT_Pos) /*!< 0x20000000 */ -#define GINTMSK_DISCINT GINTMSK_DISCINT_Msk /*!< Disconnect detected interrupt mask */ +#define GINTMSK_DISCINT_Msk (0x1UL << GINTMSK_DISCINT_Pos) /*!< 0x20000000 */ +#define GINTMSK_DISCINT GINTMSK_DISCINT_Msk /*!< Disconnect detected interrupt mask */ #define GINTMSK_SRQIM_Pos (30U) -#define GINTMSK_SRQIM_Msk (0x1UL << GINTMSK_SRQIM_Pos) /*!< 0x40000000 */ -#define GINTMSK_SRQIM GINTMSK_SRQIM_Msk /*!< Session request/new session detected interrupt mask */ +#define GINTMSK_SRQIM_Msk (0x1UL << GINTMSK_SRQIM_Pos) /*!< 0x40000000 */ +#define GINTMSK_SRQIM GINTMSK_SRQIM_Msk /*!< Session request/new session detected interrupt mask */ #define GINTMSK_WUIM_Pos (31U) -#define GINTMSK_WUIM_Msk (0x1UL << GINTMSK_WUIM_Pos) /*!< 0x80000000 */ -#define GINTMSK_WUIM GINTMSK_WUIM_Msk /*!< Resume/remote wakeup detected interrupt mask */ +#define GINTMSK_WUIM_Msk (0x1UL << GINTMSK_WUIM_Pos) /*!< 0x80000000 */ +#define GINTMSK_WUIM GINTMSK_WUIM_Msk /*!< Resume/remote wakeup detected interrupt mask */ /******************** Bit definition for DAINT register ********************/ #define DAINT_IEPINT_Pos (0U) -#define DAINT_IEPINT_Msk (0xFFFFUL << DAINT_IEPINT_Pos) /*!< 0x0000FFFF */ -#define DAINT_IEPINT DAINT_IEPINT_Msk /*!< IN endpoint interrupt bits */ +#define DAINT_IEPINT_Msk (0xFFFFUL << DAINT_IEPINT_Pos) /*!< 0x0000FFFF */ +#define DAINT_IEPINT DAINT_IEPINT_Msk /*!< IN endpoint interrupt bits */ #define DAINT_OEPINT_Pos (16U) -#define DAINT_OEPINT_Msk (0xFFFFUL << DAINT_OEPINT_Pos) /*!< 0xFFFF0000 */ -#define DAINT_OEPINT DAINT_OEPINT_Msk /*!< OUT endpoint interrupt bits */ +#define DAINT_OEPINT_Msk (0xFFFFUL << DAINT_OEPINT_Pos) /*!< 0xFFFF0000 */ +#define DAINT_OEPINT DAINT_OEPINT_Msk /*!< OUT endpoint interrupt bits */ /******************** Bit definition for HAINTMSK register ********************/ #define HAINTMSK_HAINTM_Pos (0U) -#define HAINTMSK_HAINTM_Msk (0xFFFFUL << HAINTMSK_HAINTM_Pos) /*!< 0x0000FFFF */ -#define HAINTMSK_HAINTM HAINTMSK_HAINTM_Msk /*!< Channel interrupt mask */ +#define HAINTMSK_HAINTM_Msk (0xFFFFUL << HAINTMSK_HAINTM_Pos) /*!< 0x0000FFFF */ +#define HAINTMSK_HAINTM HAINTMSK_HAINTM_Msk /*!< Channel interrupt mask */ /******************** Bit definition for GRXSTSP register ********************/ #define GRXSTSP_EPNUM_Pos (0U) -#define GRXSTSP_EPNUM_Msk (0xFUL << GRXSTSP_EPNUM_Pos) /*!< 0x0000000F */ -#define GRXSTSP_EPNUM GRXSTSP_EPNUM_Msk /*!< IN EP interrupt mask bits */ +#define GRXSTSP_EPNUM_Msk (0xFUL << GRXSTSP_EPNUM_Pos) /*!< 0x0000000F */ +#define GRXSTSP_EPNUM GRXSTSP_EPNUM_Msk /*!< IN EP interrupt mask bits */ #define GRXSTSP_BCNT_Pos (4U) -#define GRXSTSP_BCNT_Msk (0x7FFUL << GRXSTSP_BCNT_Pos) /*!< 0x00007FF0 */ -#define GRXSTSP_BCNT GRXSTSP_BCNT_Msk /*!< OUT EP interrupt mask bits */ +#define GRXSTSP_BCNT_Msk (0x7FFUL << GRXSTSP_BCNT_Pos) /*!< 0x00007FF0 */ +#define GRXSTSP_BCNT GRXSTSP_BCNT_Msk /*!< OUT EP interrupt mask bits */ #define GRXSTSP_DPID_Pos (15U) -#define GRXSTSP_DPID_Msk (0x3UL << GRXSTSP_DPID_Pos) /*!< 0x00018000 */ -#define GRXSTSP_DPID GRXSTSP_DPID_Msk /*!< OUT EP interrupt mask bits */ +#define GRXSTSP_DPID_Msk (0x3UL << GRXSTSP_DPID_Pos) /*!< 0x00018000 */ +#define GRXSTSP_DPID GRXSTSP_DPID_Msk /*!< OUT EP interrupt mask bits */ #define GRXSTSP_PKTSTS_Pos (17U) -#define GRXSTSP_PKTSTS_Msk (0xFUL << GRXSTSP_PKTSTS_Pos) /*!< 0x001E0000 */ -#define GRXSTSP_PKTSTS GRXSTSP_PKTSTS_Msk /*!< OUT EP interrupt mask bits */ +#define GRXSTSP_PKTSTS_Msk (0xFUL << GRXSTSP_PKTSTS_Pos) /*!< 0x001E0000 */ +#define GRXSTSP_PKTSTS GRXSTSP_PKTSTS_Msk /*!< OUT EP interrupt mask bits */ /******************** Bit definition for DAINTMSK register ********************/ #define DAINTMSK_IEPM_Pos (0U) -#define DAINTMSK_IEPM_Msk (0xFFFFUL << DAINTMSK_IEPM_Pos) /*!< 0x0000FFFF */ -#define DAINTMSK_IEPM DAINTMSK_IEPM_Msk /*!< IN EP interrupt mask bits */ +#define DAINTMSK_IEPM_Msk (0xFFFFUL << DAINTMSK_IEPM_Pos) /*!< 0x0000FFFF */ +#define DAINTMSK_IEPM DAINTMSK_IEPM_Msk /*!< IN EP interrupt mask bits */ #define DAINTMSK_OEPM_Pos (16U) -#define DAINTMSK_OEPM_Msk (0xFFFFUL << DAINTMSK_OEPM_Pos) /*!< 0xFFFF0000 */ -#define DAINTMSK_OEPM DAINTMSK_OEPM_Msk /*!< OUT EP interrupt mask bits */ +#define DAINTMSK_OEPM_Msk (0xFFFFUL << DAINTMSK_OEPM_Pos) /*!< 0xFFFF0000 */ +#define DAINTMSK_OEPM DAINTMSK_OEPM_Msk /*!< OUT EP interrupt mask bits */ /******************** Bit definition for OTG register ********************/ - #define CHNUM_Pos (0U) -#define CHNUM_Msk (0xFUL << CHNUM_Pos) /*!< 0x0000000F */ -#define CHNUM CHNUM_Msk /*!< Channel number */ -#define CHNUM_0 (0x1UL << CHNUM_Pos) /*!< 0x00000001 */ -#define CHNUM_1 (0x2UL << CHNUM_Pos) /*!< 0x00000002 */ -#define CHNUM_2 (0x4UL << CHNUM_Pos) /*!< 0x00000004 */ -#define CHNUM_3 (0x8UL << CHNUM_Pos) /*!< 0x00000008 */ +#define CHNUM_Msk (0xFUL << CHNUM_Pos) /*!< 0x0000000F */ +#define CHNUM CHNUM_Msk /*!< Channel number */ +#define CHNUM_0 (0x1UL << CHNUM_Pos) /*!< 0x00000001 */ +#define CHNUM_1 (0x2UL << CHNUM_Pos) /*!< 0x00000002 */ +#define CHNUM_2 (0x4UL << CHNUM_Pos) /*!< 0x00000004 */ +#define CHNUM_3 (0x8UL << CHNUM_Pos) /*!< 0x00000008 */ #define BCNT_Pos (4U) -#define BCNT_Msk (0x7FFUL << BCNT_Pos) /*!< 0x00007FF0 */ -#define BCNT BCNT_Msk /*!< Byte count */ +#define BCNT_Msk (0x7FFUL << BCNT_Pos) /*!< 0x00007FF0 */ +#define BCNT BCNT_Msk /*!< Byte count */ #define DPID_Pos (15U) -#define DPID_Msk (0x3UL << DPID_Pos) /*!< 0x00018000 */ -#define DPID DPID_Msk /*!< Data PID */ -#define DPID_0 (0x1UL << DPID_Pos) /*!< 0x00008000 */ -#define DPID_1 (0x2UL << DPID_Pos) /*!< 0x00010000 */ +#define DPID_Msk (0x3UL << DPID_Pos) /*!< 0x00018000 */ +#define DPID DPID_Msk /*!< Data PID */ +#define DPID_0 (0x1UL << DPID_Pos) /*!< 0x00008000 */ +#define DPID_1 (0x2UL << DPID_Pos) /*!< 0x00010000 */ #define PKTSTS_Pos (17U) -#define PKTSTS_Msk (0xFUL << PKTSTS_Pos) /*!< 0x001E0000 */ -#define PKTSTS PKTSTS_Msk /*!< Packet status */ -#define PKTSTS_0 (0x1UL << PKTSTS_Pos) /*!< 0x00020000 */ -#define PKTSTS_1 (0x2UL << PKTSTS_Pos) /*!< 0x00040000 */ -#define PKTSTS_2 (0x4UL << PKTSTS_Pos) /*!< 0x00080000 */ -#define PKTSTS_3 (0x8UL << PKTSTS_Pos) /*!< 0x00100000 */ +#define PKTSTS_Msk (0xFUL << PKTSTS_Pos) /*!< 0x001E0000 */ +#define PKTSTS PKTSTS_Msk /*!< Packet status */ +#define PKTSTS_0 (0x1UL << PKTSTS_Pos) /*!< 0x00020000 */ +#define PKTSTS_1 (0x2UL << PKTSTS_Pos) /*!< 0x00040000 */ +#define PKTSTS_2 (0x4UL << PKTSTS_Pos) /*!< 0x00080000 */ +#define PKTSTS_3 (0x8UL << PKTSTS_Pos) /*!< 0x00100000 */ #define EPNUM_Pos (0U) -#define EPNUM_Msk (0xFUL << EPNUM_Pos) /*!< 0x0000000F */ -#define EPNUM EPNUM_Msk /*!< Endpoint number */ -#define EPNUM_0 (0x1UL << EPNUM_Pos) /*!< 0x00000001 */ -#define EPNUM_1 (0x2UL << EPNUM_Pos) /*!< 0x00000002 */ -#define EPNUM_2 (0x4UL << EPNUM_Pos) /*!< 0x00000004 */ -#define EPNUM_3 (0x8UL << EPNUM_Pos) /*!< 0x00000008 */ +#define EPNUM_Msk (0xFUL << EPNUM_Pos) /*!< 0x0000000F */ +#define EPNUM EPNUM_Msk /*!< Endpoint number */ +#define EPNUM_0 (0x1UL << EPNUM_Pos) /*!< 0x00000001 */ +#define EPNUM_1 (0x2UL << EPNUM_Pos) /*!< 0x00000002 */ +#define EPNUM_2 (0x4UL << EPNUM_Pos) /*!< 0x00000004 */ +#define EPNUM_3 (0x8UL << EPNUM_Pos) /*!< 0x00000008 */ #define FRMNUM_Pos (21U) -#define FRMNUM_Msk (0xFUL << FRMNUM_Pos) /*!< 0x01E00000 */ -#define FRMNUM FRMNUM_Msk /*!< Frame number */ -#define FRMNUM_0 (0x1UL << FRMNUM_Pos) /*!< 0x00200000 */ -#define FRMNUM_1 (0x2UL << FRMNUM_Pos) /*!< 0x00400000 */ -#define FRMNUM_2 (0x4UL << FRMNUM_Pos) /*!< 0x00800000 */ -#define FRMNUM_3 (0x8UL << FRMNUM_Pos) /*!< 0x01000000 */ +#define FRMNUM_Msk (0xFUL << FRMNUM_Pos) /*!< 0x01E00000 */ +#define FRMNUM FRMNUM_Msk /*!< Frame number */ +#define FRMNUM_0 (0x1UL << FRMNUM_Pos) /*!< 0x00200000 */ +#define FRMNUM_1 (0x2UL << FRMNUM_Pos) /*!< 0x00400000 */ +#define FRMNUM_2 (0x4UL << FRMNUM_Pos) /*!< 0x00800000 */ +#define FRMNUM_3 (0x8UL << FRMNUM_Pos) /*!< 0x01000000 */ /******************** Bit definition for GRXFSIZ register ********************/ #define GRXFSIZ_RXFD_Pos (0U) -#define GRXFSIZ_RXFD_Msk (0xFFFFUL << GRXFSIZ_RXFD_Pos) /*!< 0x0000FFFF */ -#define GRXFSIZ_RXFD GRXFSIZ_RXFD_Msk /*!< RxFIFO depth */ +#define GRXFSIZ_RXFD_Msk (0xFFFFUL << GRXFSIZ_RXFD_Pos) /*!< 0x0000FFFF */ +#define GRXFSIZ_RXFD GRXFSIZ_RXFD_Msk /*!< RxFIFO depth */ /******************** Bit definition for DVBUSDIS register ********************/ #define DVBUSDIS_VBUSDT_Pos (0U) -#define DVBUSDIS_VBUSDT_Msk (0xFFFFUL << DVBUSDIS_VBUSDT_Pos) /*!< 0x0000FFFF */ -#define DVBUSDIS_VBUSDT DVBUSDIS_VBUSDT_Msk /*!< Device VBUS discharge time */ +#define DVBUSDIS_VBUSDT_Msk (0xFFFFUL << DVBUSDIS_VBUSDT_Pos) /*!< 0x0000FFFF */ +#define DVBUSDIS_VBUSDT DVBUSDIS_VBUSDT_Msk /*!< Device VBUS discharge time */ /******************** Bit definition for OTG register ********************/ #define NPTXFSA_Pos (0U) -#define NPTXFSA_Msk (0xFFFFUL << NPTXFSA_Pos) /*!< 0x0000FFFF */ -#define NPTXFSA NPTXFSA_Msk /*!< Nonperiodic transmit RAM start address */ +#define NPTXFSA_Msk (0xFFFFUL << NPTXFSA_Pos) /*!< 0x0000FFFF */ +#define NPTXFSA NPTXFSA_Msk /*!< Nonperiodic transmit RAM start address */ #define NPTXFD_Pos (16U) -#define NPTXFD_Msk (0xFFFFUL << NPTXFD_Pos) /*!< 0xFFFF0000 */ -#define NPTXFD NPTXFD_Msk /*!< Nonperiodic TxFIFO depth */ +#define NPTXFD_Msk (0xFFFFUL << NPTXFD_Pos) /*!< 0xFFFF0000 */ +#define NPTXFD NPTXFD_Msk /*!< Nonperiodic TxFIFO depth */ #define TX0FSA_Pos (0U) -#define TX0FSA_Msk (0xFFFFUL << TX0FSA_Pos) /*!< 0x0000FFFF */ -#define TX0FSA TX0FSA_Msk /*!< Endpoint 0 transmit RAM start address */ +#define TX0FSA_Msk (0xFFFFUL << TX0FSA_Pos) /*!< 0x0000FFFF */ +#define TX0FSA TX0FSA_Msk /*!< Endpoint 0 transmit RAM start address */ #define TX0FD_Pos (16U) -#define TX0FD_Msk (0xFFFFUL << TX0FD_Pos) /*!< 0xFFFF0000 */ -#define TX0FD TX0FD_Msk /*!< Endpoint 0 TxFIFO depth */ +#define TX0FD_Msk (0xFFFFUL << TX0FD_Pos) /*!< 0xFFFF0000 */ +#define TX0FD TX0FD_Msk /*!< Endpoint 0 TxFIFO depth */ /******************** Bit definition for DVBUSPULSE register ********************/ #define DVBUSPULSE_DVBUSP_Pos (0U) -#define DVBUSPULSE_DVBUSP_Msk (0xFFFUL << DVBUSPULSE_DVBUSP_Pos) /*!< 0x00000FFF */ -#define DVBUSPULSE_DVBUSP DVBUSPULSE_DVBUSP_Msk /*!< Device VBUS pulsing time */ +#define DVBUSPULSE_DVBUSP_Msk (0xFFFUL << DVBUSPULSE_DVBUSP_Pos) /*!< 0x00000FFF */ +#define DVBUSPULSE_DVBUSP DVBUSPULSE_DVBUSP_Msk /*!< Device VBUS pulsing time */ /******************** Bit definition for GNPTXSTS register ********************/ #define GNPTXSTS_NPTXFSAV_Pos (0U) -#define GNPTXSTS_NPTXFSAV_Msk (0xFFFFUL << GNPTXSTS_NPTXFSAV_Pos) /*!< 0x0000FFFF */ -#define GNPTXSTS_NPTXFSAV GNPTXSTS_NPTXFSAV_Msk /*!< Nonperiodic TxFIFO space available */ +#define GNPTXSTS_NPTXFSAV_Msk (0xFFFFUL << GNPTXSTS_NPTXFSAV_Pos) /*!< 0x0000FFFF */ +#define GNPTXSTS_NPTXFSAV GNPTXSTS_NPTXFSAV_Msk /*!< Nonperiodic TxFIFO space available */ #define GNPTXSTS_NPTQXSAV_Pos (16U) -#define GNPTXSTS_NPTQXSAV_Msk (0xFFUL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00FF0000 */ -#define GNPTXSTS_NPTQXSAV GNPTXSTS_NPTQXSAV_Msk /*!< Nonperiodic transmit request queue space available */ -#define GNPTXSTS_NPTQXSAV_0 (0x01UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00010000 */ -#define GNPTXSTS_NPTQXSAV_1 (0x02UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00020000 */ -#define GNPTXSTS_NPTQXSAV_2 (0x04UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00040000 */ -#define GNPTXSTS_NPTQXSAV_3 (0x08UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00080000 */ -#define GNPTXSTS_NPTQXSAV_4 (0x10UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00100000 */ -#define GNPTXSTS_NPTQXSAV_5 (0x20UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00200000 */ -#define GNPTXSTS_NPTQXSAV_6 (0x40UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00400000 */ -#define GNPTXSTS_NPTQXSAV_7 (0x80UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00800000 */ +#define GNPTXSTS_NPTQXSAV_Msk (0xFFUL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00FF0000 */ +#define GNPTXSTS_NPTQXSAV GNPTXSTS_NPTQXSAV_Msk /*!< Nonperiodic transmit request queue space available */ +#define GNPTXSTS_NPTQXSAV_0 (0x01UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00010000 */ +#define GNPTXSTS_NPTQXSAV_1 (0x02UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00020000 */ +#define GNPTXSTS_NPTQXSAV_2 (0x04UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00040000 */ +#define GNPTXSTS_NPTQXSAV_3 (0x08UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00080000 */ +#define GNPTXSTS_NPTQXSAV_4 (0x10UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00100000 */ +#define GNPTXSTS_NPTQXSAV_5 (0x20UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00200000 */ +#define GNPTXSTS_NPTQXSAV_6 (0x40UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00400000 */ +#define GNPTXSTS_NPTQXSAV_7 (0x80UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00800000 */ #define GNPTXSTS_NPTXQTOP_Pos (24U) -#define GNPTXSTS_NPTXQTOP_Msk (0x7FUL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x7F000000 */ -#define GNPTXSTS_NPTXQTOP GNPTXSTS_NPTXQTOP_Msk /*!< Top of the nonperiodic transmit request queue */ -#define GNPTXSTS_NPTXQTOP_0 (0x01UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x01000000 */ -#define GNPTXSTS_NPTXQTOP_1 (0x02UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x02000000 */ -#define GNPTXSTS_NPTXQTOP_2 (0x04UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x04000000 */ -#define GNPTXSTS_NPTXQTOP_3 (0x08UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x08000000 */ -#define GNPTXSTS_NPTXQTOP_4 (0x10UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x10000000 */ -#define GNPTXSTS_NPTXQTOP_5 (0x20UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x20000000 */ -#define GNPTXSTS_NPTXQTOP_6 (0x40UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x40000000 */ +#define GNPTXSTS_NPTXQTOP_Msk (0x7FUL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x7F000000 */ +#define GNPTXSTS_NPTXQTOP GNPTXSTS_NPTXQTOP_Msk /*!< Top of the nonperiodic transmit request queue */ +#define GNPTXSTS_NPTXQTOP_0 (0x01UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x01000000 */ +#define GNPTXSTS_NPTXQTOP_1 (0x02UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x02000000 */ +#define GNPTXSTS_NPTXQTOP_2 (0x04UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x04000000 */ +#define GNPTXSTS_NPTXQTOP_3 (0x08UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x08000000 */ +#define GNPTXSTS_NPTXQTOP_4 (0x10UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x10000000 */ +#define GNPTXSTS_NPTXQTOP_5 (0x20UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x20000000 */ +#define GNPTXSTS_NPTXQTOP_6 (0x40UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x40000000 */ /******************** Bit definition for DTHRCTL register ********************/ #define DTHRCTL_NONISOTHREN_Pos (0U) -#define DTHRCTL_NONISOTHREN_Msk (0x1UL << DTHRCTL_NONISOTHREN_Pos) /*!< 0x00000001 */ -#define DTHRCTL_NONISOTHREN DTHRCTL_NONISOTHREN_Msk /*!< Nonisochronous IN endpoints threshold enable */ +#define DTHRCTL_NONISOTHREN_Msk (0x1UL << DTHRCTL_NONISOTHREN_Pos) /*!< 0x00000001 */ +#define DTHRCTL_NONISOTHREN DTHRCTL_NONISOTHREN_Msk /*!< Nonisochronous IN endpoints threshold enable */ #define DTHRCTL_ISOTHREN_Pos (1U) -#define DTHRCTL_ISOTHREN_Msk (0x1UL << DTHRCTL_ISOTHREN_Pos) /*!< 0x00000002 */ -#define DTHRCTL_ISOTHREN DTHRCTL_ISOTHREN_Msk /*!< ISO IN endpoint threshold enable */ +#define DTHRCTL_ISOTHREN_Msk (0x1UL << DTHRCTL_ISOTHREN_Pos) /*!< 0x00000002 */ +#define DTHRCTL_ISOTHREN DTHRCTL_ISOTHREN_Msk /*!< ISO IN endpoint threshold enable */ #define DTHRCTL_TXTHRLEN_Pos (2U) -#define DTHRCTL_TXTHRLEN_Msk (0x1FFUL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x000007FC */ -#define DTHRCTL_TXTHRLEN DTHRCTL_TXTHRLEN_Msk /*!< Transmit threshold length */ -#define DTHRCTL_TXTHRLEN_0 (0x001UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000004 */ -#define DTHRCTL_TXTHRLEN_1 (0x002UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000008 */ -#define DTHRCTL_TXTHRLEN_2 (0x004UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000010 */ -#define DTHRCTL_TXTHRLEN_3 (0x008UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000020 */ -#define DTHRCTL_TXTHRLEN_4 (0x010UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000040 */ -#define DTHRCTL_TXTHRLEN_5 (0x020UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000080 */ -#define DTHRCTL_TXTHRLEN_6 (0x040UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000100 */ -#define DTHRCTL_TXTHRLEN_7 (0x080UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000200 */ -#define DTHRCTL_TXTHRLEN_8 (0x100UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000400 */ +#define DTHRCTL_TXTHRLEN_Msk (0x1FFUL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x000007FC */ +#define DTHRCTL_TXTHRLEN DTHRCTL_TXTHRLEN_Msk /*!< Transmit threshold length */ +#define DTHRCTL_TXTHRLEN_0 (0x001UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000004 */ +#define DTHRCTL_TXTHRLEN_1 (0x002UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000008 */ +#define DTHRCTL_TXTHRLEN_2 (0x004UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000010 */ +#define DTHRCTL_TXTHRLEN_3 (0x008UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000020 */ +#define DTHRCTL_TXTHRLEN_4 (0x010UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000040 */ +#define DTHRCTL_TXTHRLEN_5 (0x020UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000080 */ +#define DTHRCTL_TXTHRLEN_6 (0x040UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000100 */ +#define DTHRCTL_TXTHRLEN_7 (0x080UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000200 */ +#define DTHRCTL_TXTHRLEN_8 (0x100UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000400 */ #define DTHRCTL_RXTHREN_Pos (16U) -#define DTHRCTL_RXTHREN_Msk (0x1UL << DTHRCTL_RXTHREN_Pos) /*!< 0x00010000 */ -#define DTHRCTL_RXTHREN DTHRCTL_RXTHREN_Msk /*!< Receive threshold enable */ +#define DTHRCTL_RXTHREN_Msk (0x1UL << DTHRCTL_RXTHREN_Pos) /*!< 0x00010000 */ +#define DTHRCTL_RXTHREN DTHRCTL_RXTHREN_Msk /*!< Receive threshold enable */ #define DTHRCTL_RXTHRLEN_Pos (17U) -#define DTHRCTL_RXTHRLEN_Msk (0x1FFUL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x03FE0000 */ -#define DTHRCTL_RXTHRLEN DTHRCTL_RXTHRLEN_Msk /*!< Receive threshold length */ -#define DTHRCTL_RXTHRLEN_0 (0x001UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00020000 */ -#define DTHRCTL_RXTHRLEN_1 (0x002UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00040000 */ -#define DTHRCTL_RXTHRLEN_2 (0x004UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00080000 */ -#define DTHRCTL_RXTHRLEN_3 (0x008UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00100000 */ -#define DTHRCTL_RXTHRLEN_4 (0x010UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00200000 */ -#define DTHRCTL_RXTHRLEN_5 (0x020UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00400000 */ -#define DTHRCTL_RXTHRLEN_6 (0x040UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00800000 */ -#define DTHRCTL_RXTHRLEN_7 (0x080UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x01000000 */ -#define DTHRCTL_RXTHRLEN_8 (0x100UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x02000000 */ +#define DTHRCTL_RXTHRLEN_Msk (0x1FFUL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x03FE0000 */ +#define DTHRCTL_RXTHRLEN DTHRCTL_RXTHRLEN_Msk /*!< Receive threshold length */ +#define DTHRCTL_RXTHRLEN_0 (0x001UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00020000 */ +#define DTHRCTL_RXTHRLEN_1 (0x002UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00040000 */ +#define DTHRCTL_RXTHRLEN_2 (0x004UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00080000 */ +#define DTHRCTL_RXTHRLEN_3 (0x008UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00100000 */ +#define DTHRCTL_RXTHRLEN_4 (0x010UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00200000 */ +#define DTHRCTL_RXTHRLEN_5 (0x020UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00400000 */ +#define DTHRCTL_RXTHRLEN_6 (0x040UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00800000 */ +#define DTHRCTL_RXTHRLEN_7 (0x080UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x01000000 */ +#define DTHRCTL_RXTHRLEN_8 (0x100UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x02000000 */ #define DTHRCTL_ARPEN_Pos (27U) -#define DTHRCTL_ARPEN_Msk (0x1UL << DTHRCTL_ARPEN_Pos) /*!< 0x08000000 */ -#define DTHRCTL_ARPEN DTHRCTL_ARPEN_Msk /*!< Arbiter parking enable */ +#define DTHRCTL_ARPEN_Msk (0x1UL << DTHRCTL_ARPEN_Pos) /*!< 0x08000000 */ +#define DTHRCTL_ARPEN DTHRCTL_ARPEN_Msk /*!< Arbiter parking enable */ /******************** Bit definition for DIEPEMPMSK register ********************/ #define DIEPEMPMSK_INEPTXFEM_Pos (0U) -#define DIEPEMPMSK_INEPTXFEM_Msk (0xFFFFUL << DIEPEMPMSK_INEPTXFEM_Pos) /*!< 0x0000FFFF */ -#define DIEPEMPMSK_INEPTXFEM DIEPEMPMSK_INEPTXFEM_Msk /*!< IN EP Tx FIFO empty interrupt mask bits */ +#define DIEPEMPMSK_INEPTXFEM_Msk (0xFFFFUL << DIEPEMPMSK_INEPTXFEM_Pos) /*!< 0x0000FFFF */ +#define DIEPEMPMSK_INEPTXFEM DIEPEMPMSK_INEPTXFEM_Msk /*!< IN EP Tx FIFO empty interrupt mask bits */ /******************** Bit definition for DEACHINT register ********************/ #define DEACHINT_IEP1INT_Pos (1U) -#define DEACHINT_IEP1INT_Msk (0x1UL << DEACHINT_IEP1INT_Pos) /*!< 0x00000002 */ -#define DEACHINT_IEP1INT DEACHINT_IEP1INT_Msk /*!< IN endpoint 1interrupt bit */ +#define DEACHINT_IEP1INT_Msk (0x1UL << DEACHINT_IEP1INT_Pos) /*!< 0x00000002 */ +#define DEACHINT_IEP1INT DEACHINT_IEP1INT_Msk /*!< IN endpoint 1interrupt bit */ #define DEACHINT_OEP1INT_Pos (17U) -#define DEACHINT_OEP1INT_Msk (0x1UL << DEACHINT_OEP1INT_Pos) /*!< 0x00020000 */ -#define DEACHINT_OEP1INT DEACHINT_OEP1INT_Msk /*!< OUT endpoint 1 interrupt bit */ +#define DEACHINT_OEP1INT_Msk (0x1UL << DEACHINT_OEP1INT_Pos) /*!< 0x00020000 */ +#define DEACHINT_OEP1INT DEACHINT_OEP1INT_Msk /*!< OUT endpoint 1 interrupt bit */ /******************** Bit definition for GCCFG register ********************/ #define GCCFG_DCDET_Pos (0U) -#define GCCFG_DCDET_Msk (0x1UL << GCCFG_DCDET_Pos) /*!< 0x00000001 */ -#define GCCFG_DCDET GCCFG_DCDET_Msk /*!< Data contact detection (DCD) status */ +#define GCCFG_DCDET_Msk (0x1UL << GCCFG_DCDET_Pos) /*!< 0x00000001 */ +#define GCCFG_DCDET GCCFG_DCDET_Msk /*!< Data contact detection (DCD) status */ #define GCCFG_PDET_Pos (1U) -#define GCCFG_PDET_Msk (0x1UL << GCCFG_PDET_Pos) /*!< 0x00000002 */ -#define GCCFG_PDET GCCFG_PDET_Msk /*!< Primary detection (PD) status */ +#define GCCFG_PDET_Msk (0x1UL << GCCFG_PDET_Pos) /*!< 0x00000002 */ +#define GCCFG_PDET GCCFG_PDET_Msk /*!< Primary detection (PD) status */ #define GCCFG_SDET_Pos (2U) -#define GCCFG_SDET_Msk (0x1UL << GCCFG_SDET_Pos) /*!< 0x00000004 */ -#define GCCFG_SDET GCCFG_SDET_Msk /*!< Secondary detection (SD) status */ +#define GCCFG_SDET_Msk (0x1UL << GCCFG_SDET_Pos) /*!< 0x00000004 */ +#define GCCFG_SDET GCCFG_SDET_Msk /*!< Secondary detection (SD) status */ #define GCCFG_PS2DET_Pos (3U) -#define GCCFG_PS2DET_Msk (0x1UL << GCCFG_PS2DET_Pos) /*!< 0x00000008 */ -#define GCCFG_PS2DET GCCFG_PS2DET_Msk /*!< DM pull-up detection status */ +#define GCCFG_PS2DET_Msk (0x1UL << GCCFG_PS2DET_Pos) /*!< 0x00000008 */ +#define GCCFG_PS2DET GCCFG_PS2DET_Msk /*!< DM pull-up detection status */ #define GCCFG_PWRDWN_Pos (16U) -#define GCCFG_PWRDWN_Msk (0x1UL << GCCFG_PWRDWN_Pos) /*!< 0x00010000 */ -#define GCCFG_PWRDWN GCCFG_PWRDWN_Msk /*!< Power down */ +#define GCCFG_PWRDWN_Msk (0x1UL << GCCFG_PWRDWN_Pos) /*!< 0x00010000 */ +#define GCCFG_PWRDWN GCCFG_PWRDWN_Msk /*!< Power down */ #define GCCFG_BCDEN_Pos (17U) -#define GCCFG_BCDEN_Msk (0x1UL << GCCFG_BCDEN_Pos) /*!< 0x00020000 */ -#define GCCFG_BCDEN GCCFG_BCDEN_Msk /*!< Battery charging detector (BCD) enable */ +#define GCCFG_BCDEN_Msk (0x1UL << GCCFG_BCDEN_Pos) /*!< 0x00020000 */ +#define GCCFG_BCDEN GCCFG_BCDEN_Msk /*!< Battery charging detector (BCD) enable */ #define GCCFG_DCDEN_Pos (18U) -#define GCCFG_DCDEN_Msk (0x1UL << GCCFG_DCDEN_Pos) /*!< 0x00040000 */ -#define GCCFG_DCDEN GCCFG_DCDEN_Msk /*!< Data contact detection (DCD) mode enable*/ +#define GCCFG_DCDEN_Msk (0x1UL << GCCFG_DCDEN_Pos) /*!< 0x00040000 */ +#define GCCFG_DCDEN GCCFG_DCDEN_Msk /*!< Data contact detection (DCD) mode enable*/ #define GCCFG_PDEN_Pos (19U) -#define GCCFG_PDEN_Msk (0x1UL << GCCFG_PDEN_Pos) /*!< 0x00080000 */ -#define GCCFG_PDEN GCCFG_PDEN_Msk /*!< Primary detection (PD) mode enable*/ +#define GCCFG_PDEN_Msk (0x1UL << GCCFG_PDEN_Pos) /*!< 0x00080000 */ +#define GCCFG_PDEN GCCFG_PDEN_Msk /*!< Primary detection (PD) mode enable*/ #define GCCFG_SDEN_Pos (20U) -#define GCCFG_SDEN_Msk (0x1UL << GCCFG_SDEN_Pos) /*!< 0x00100000 */ -#define GCCFG_SDEN GCCFG_SDEN_Msk /*!< Secondary detection (SD) mode enable */ +#define GCCFG_SDEN_Msk (0x1UL << GCCFG_SDEN_Pos) /*!< 0x00100000 */ +#define GCCFG_SDEN GCCFG_SDEN_Msk /*!< Secondary detection (SD) mode enable */ #define GCCFG_VBDEN_Pos (21U) -#define GCCFG_VBDEN_Msk (0x1UL << GCCFG_VBDEN_Pos) /*!< 0x00200000 */ -#define GCCFG_VBDEN GCCFG_VBDEN_Msk /*!< VBUS mode enable */ +#define GCCFG_VBDEN_Msk (0x1UL << GCCFG_VBDEN_Pos) /*!< 0x00200000 */ +#define GCCFG_VBDEN GCCFG_VBDEN_Msk /*!< VBUS mode enable */ #define GCCFG_OTGIDEN_Pos (22U) -#define GCCFG_OTGIDEN_Msk (0x1UL << GCCFG_OTGIDEN_Pos) /*!< 0x00400000 */ -#define GCCFG_OTGIDEN GCCFG_OTGIDEN_Msk /*!< OTG Id enable */ +#define GCCFG_OTGIDEN_Msk (0x1UL << GCCFG_OTGIDEN_Pos) /*!< 0x00400000 */ +#define GCCFG_OTGIDEN GCCFG_OTGIDEN_Msk /*!< OTG Id enable */ #define GCCFG_PHYHSEN_Pos (23U) -#define GCCFG_PHYHSEN_Msk (0x1UL << GCCFG_PHYHSEN_Pos) /*!< 0x00800000 */ -#define GCCFG_PHYHSEN GCCFG_PHYHSEN_Msk /*!< HS PHY enable */ +#define GCCFG_PHYHSEN_Msk (0x1UL << GCCFG_PHYHSEN_Pos) /*!< 0x00800000 */ +#define GCCFG_PHYHSEN GCCFG_PHYHSEN_Msk /*!< HS PHY enable */ /******************** Bit definition for DEACHINTMSK register ********************/ #define DEACHINTMSK_IEP1INTM_Pos (1U) -#define DEACHINTMSK_IEP1INTM_Msk (0x1UL << DEACHINTMSK_IEP1INTM_Pos) /*!< 0x00000002 */ -#define DEACHINTMSK_IEP1INTM DEACHINTMSK_IEP1INTM_Msk /*!< IN Endpoint 1 interrupt mask bit */ +#define DEACHINTMSK_IEP1INTM_Msk (0x1UL << DEACHINTMSK_IEP1INTM_Pos) /*!< 0x00000002 */ +#define DEACHINTMSK_IEP1INTM DEACHINTMSK_IEP1INTM_Msk /*!< IN Endpoint 1 interrupt mask bit */ #define DEACHINTMSK_OEP1INTM_Pos (17U) -#define DEACHINTMSK_OEP1INTM_Msk (0x1UL << DEACHINTMSK_OEP1INTM_Pos) /*!< 0x00020000 */ -#define DEACHINTMSK_OEP1INTM DEACHINTMSK_OEP1INTM_Msk /*!< OUT Endpoint 1 interrupt mask bit */ +#define DEACHINTMSK_OEP1INTM_Msk (0x1UL << DEACHINTMSK_OEP1INTM_Pos) /*!< 0x00020000 */ +#define DEACHINTMSK_OEP1INTM DEACHINTMSK_OEP1INTM_Msk /*!< OUT Endpoint 1 interrupt mask bit */ /******************** Bit definition for CID register ********************/ #define CID_PRODUCT_ID_Pos (0U) -#define CID_PRODUCT_ID_Msk (0xFFFFFFFFUL << CID_PRODUCT_ID_Pos) /*!< 0xFFFFFFFF */ -#define CID_PRODUCT_ID CID_PRODUCT_ID_Msk /*!< Product ID field */ +#define CID_PRODUCT_ID_Msk (0xFFFFFFFFUL << CID_PRODUCT_ID_Pos) /*!< 0xFFFFFFFF */ +#define CID_PRODUCT_ID CID_PRODUCT_ID_Msk /*!< Product ID field */ /******************** Bit definition for GLPMCFG register ********************/ #define GLPMCFG_LPMEN_Pos (0U) -#define GLPMCFG_LPMEN_Msk (0x1UL << GLPMCFG_LPMEN_Pos) /*!< 0x00000001 */ -#define GLPMCFG_LPMEN GLPMCFG_LPMEN_Msk /*!< LPM support enable */ +#define GLPMCFG_LPMEN_Msk (0x1UL << GLPMCFG_LPMEN_Pos) /*!< 0x00000001 */ +#define GLPMCFG_LPMEN GLPMCFG_LPMEN_Msk /*!< LPM support enable */ #define GLPMCFG_LPMACK_Pos (1U) -#define GLPMCFG_LPMACK_Msk (0x1UL << GLPMCFG_LPMACK_Pos) /*!< 0x00000002 */ -#define GLPMCFG_LPMACK GLPMCFG_LPMACK_Msk /*!< LPM Token acknowledge enable */ +#define GLPMCFG_LPMACK_Msk (0x1UL << GLPMCFG_LPMACK_Pos) /*!< 0x00000002 */ +#define GLPMCFG_LPMACK GLPMCFG_LPMACK_Msk /*!< LPM Token acknowledge enable */ #define GLPMCFG_BESL_Pos (2U) -#define GLPMCFG_BESL_Msk (0xFUL << GLPMCFG_BESL_Pos) /*!< 0x0000003C */ -#define GLPMCFG_BESL GLPMCFG_BESL_Msk /*!< BESL value received with last ACKed LPM Token */ +#define GLPMCFG_BESL_Msk (0xFUL << GLPMCFG_BESL_Pos) /*!< 0x0000003C */ +#define GLPMCFG_BESL GLPMCFG_BESL_Msk /*!< BESL value received with last ACKed LPM Token */ #define GLPMCFG_REMWAKE_Pos (6U) -#define GLPMCFG_REMWAKE_Msk (0x1UL << GLPMCFG_REMWAKE_Pos) /*!< 0x00000040 */ -#define GLPMCFG_REMWAKE GLPMCFG_REMWAKE_Msk /*!< bRemoteWake value received with last ACKed LPM Token */ +#define GLPMCFG_REMWAKE_Msk (0x1UL << GLPMCFG_REMWAKE_Pos) /*!< 0x00000040 */ +#define GLPMCFG_REMWAKE GLPMCFG_REMWAKE_Msk /*!< bRemoteWake value received with last ACKed LPM Token */ #define GLPMCFG_L1SSEN_Pos (7U) -#define GLPMCFG_L1SSEN_Msk (0x1UL << GLPMCFG_L1SSEN_Pos) /*!< 0x00000080 */ -#define GLPMCFG_L1SSEN GLPMCFG_L1SSEN_Msk /*!< L1 shallow sleep enable */ +#define GLPMCFG_L1SSEN_Msk (0x1UL << GLPMCFG_L1SSEN_Pos) /*!< 0x00000080 */ +#define GLPMCFG_L1SSEN GLPMCFG_L1SSEN_Msk /*!< L1 shallow sleep enable */ #define GLPMCFG_BESLTHRS_Pos (8U) -#define GLPMCFG_BESLTHRS_Msk (0xFUL << GLPMCFG_BESLTHRS_Pos) /*!< 0x00000F00 */ -#define GLPMCFG_BESLTHRS GLPMCFG_BESLTHRS_Msk /*!< BESL threshold */ +#define GLPMCFG_BESLTHRS_Msk (0xFUL << GLPMCFG_BESLTHRS_Pos) /*!< 0x00000F00 */ +#define GLPMCFG_BESLTHRS GLPMCFG_BESLTHRS_Msk /*!< BESL threshold */ #define GLPMCFG_L1DSEN_Pos (12U) -#define GLPMCFG_L1DSEN_Msk (0x1UL << GLPMCFG_L1DSEN_Pos) /*!< 0x00001000 */ -#define GLPMCFG_L1DSEN GLPMCFG_L1DSEN_Msk /*!< L1 deep sleep enable */ +#define GLPMCFG_L1DSEN_Msk (0x1UL << GLPMCFG_L1DSEN_Pos) /*!< 0x00001000 */ +#define GLPMCFG_L1DSEN GLPMCFG_L1DSEN_Msk /*!< L1 deep sleep enable */ #define GLPMCFG_LPMRSP_Pos (13U) -#define GLPMCFG_LPMRSP_Msk (0x3UL << GLPMCFG_LPMRSP_Pos) /*!< 0x00006000 */ -#define GLPMCFG_LPMRSP GLPMCFG_LPMRSP_Msk /*!< LPM response */ +#define GLPMCFG_LPMRSP_Msk (0x3UL << GLPMCFG_LPMRSP_Pos) /*!< 0x00006000 */ +#define GLPMCFG_LPMRSP GLPMCFG_LPMRSP_Msk /*!< LPM response */ #define GLPMCFG_SLPSTS_Pos (15U) -#define GLPMCFG_SLPSTS_Msk (0x1UL << GLPMCFG_SLPSTS_Pos) /*!< 0x00008000 */ -#define GLPMCFG_SLPSTS GLPMCFG_SLPSTS_Msk /*!< Port sleep status */ +#define GLPMCFG_SLPSTS_Msk (0x1UL << GLPMCFG_SLPSTS_Pos) /*!< 0x00008000 */ +#define GLPMCFG_SLPSTS GLPMCFG_SLPSTS_Msk /*!< Port sleep status */ #define GLPMCFG_L1RSMOK_Pos (16U) -#define GLPMCFG_L1RSMOK_Msk (0x1UL << GLPMCFG_L1RSMOK_Pos) /*!< 0x00010000 */ -#define GLPMCFG_L1RSMOK GLPMCFG_L1RSMOK_Msk /*!< Sleep State Resume OK */ +#define GLPMCFG_L1RSMOK_Msk (0x1UL << GLPMCFG_L1RSMOK_Pos) /*!< 0x00010000 */ +#define GLPMCFG_L1RSMOK GLPMCFG_L1RSMOK_Msk /*!< Sleep State Resume OK */ #define GLPMCFG_LPMCHIDX_Pos (17U) -#define GLPMCFG_LPMCHIDX_Msk (0xFUL << GLPMCFG_LPMCHIDX_Pos) /*!< 0x001E0000 */ -#define GLPMCFG_LPMCHIDX GLPMCFG_LPMCHIDX_Msk /*!< LPM Channel Index */ +#define GLPMCFG_LPMCHIDX_Msk (0xFUL << GLPMCFG_LPMCHIDX_Pos) /*!< 0x001E0000 */ +#define GLPMCFG_LPMCHIDX GLPMCFG_LPMCHIDX_Msk /*!< LPM Channel Index */ #define GLPMCFG_LPMRCNT_Pos (21U) -#define GLPMCFG_LPMRCNT_Msk (0x7UL << GLPMCFG_LPMRCNT_Pos) /*!< 0x00E00000 */ -#define GLPMCFG_LPMRCNT GLPMCFG_LPMRCNT_Msk /*!< LPM retry count */ +#define GLPMCFG_LPMRCNT_Msk (0x7UL << GLPMCFG_LPMRCNT_Pos) /*!< 0x00E00000 */ +#define GLPMCFG_LPMRCNT GLPMCFG_LPMRCNT_Msk /*!< LPM retry count */ #define GLPMCFG_SNDLPM_Pos (24U) -#define GLPMCFG_SNDLPM_Msk (0x1UL << GLPMCFG_SNDLPM_Pos) /*!< 0x01000000 */ -#define GLPMCFG_SNDLPM GLPMCFG_SNDLPM_Msk /*!< Send LPM transaction */ +#define GLPMCFG_SNDLPM_Msk (0x1UL << GLPMCFG_SNDLPM_Pos) /*!< 0x01000000 */ +#define GLPMCFG_SNDLPM GLPMCFG_SNDLPM_Msk /*!< Send LPM transaction */ #define GLPMCFG_LPMRCNTSTS_Pos (25U) -#define GLPMCFG_LPMRCNTSTS_Msk (0x7UL << GLPMCFG_LPMRCNTSTS_Pos) /*!< 0x0E000000 */ -#define GLPMCFG_LPMRCNTSTS GLPMCFG_LPMRCNTSTS_Msk /*!< LPM retry count status */ +#define GLPMCFG_LPMRCNTSTS_Msk (0x7UL << GLPMCFG_LPMRCNTSTS_Pos) /*!< 0x0E000000 */ +#define GLPMCFG_LPMRCNTSTS GLPMCFG_LPMRCNTSTS_Msk /*!< LPM retry count status */ #define GLPMCFG_ENBESL_Pos (28U) -#define GLPMCFG_ENBESL_Msk (0x1UL << GLPMCFG_ENBESL_Pos) /*!< 0x10000000 */ -#define GLPMCFG_ENBESL GLPMCFG_ENBESL_Msk /*!< Enable best effort service latency */ +#define GLPMCFG_ENBESL_Msk (0x1UL << GLPMCFG_ENBESL_Pos) /*!< 0x10000000 */ +#define GLPMCFG_ENBESL GLPMCFG_ENBESL_Msk /*!< Enable best effort service latency */ /******************** Bit definition for DIEPEACHMSK1 register ********************/ #define DIEPEACHMSK1_XFRCM_Pos (0U) -#define DIEPEACHMSK1_XFRCM_Msk (0x1UL << DIEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ -#define DIEPEACHMSK1_XFRCM DIEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define DIEPEACHMSK1_XFRCM_Msk (0x1UL << DIEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ +#define DIEPEACHMSK1_XFRCM DIEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ #define DIEPEACHMSK1_EPDM_Pos (1U) -#define DIEPEACHMSK1_EPDM_Msk (0x1UL << DIEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ -#define DIEPEACHMSK1_EPDM DIEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define DIEPEACHMSK1_EPDM_Msk (0x1UL << DIEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ +#define DIEPEACHMSK1_EPDM DIEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ #define DIEPEACHMSK1_TOM_Pos (3U) -#define DIEPEACHMSK1_TOM_Msk (0x1UL << DIEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ -#define DIEPEACHMSK1_TOM DIEPEACHMSK1_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ +#define DIEPEACHMSK1_TOM_Msk (0x1UL << DIEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ +#define DIEPEACHMSK1_TOM DIEPEACHMSK1_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ #define DIEPEACHMSK1_ITTXFEMSK_Pos (4U) -#define DIEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << DIEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ -#define DIEPEACHMSK1_ITTXFEMSK DIEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define DIEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << DIEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ +#define DIEPEACHMSK1_ITTXFEMSK DIEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ #define DIEPEACHMSK1_INEPNMM_Pos (5U) -#define DIEPEACHMSK1_INEPNMM_Msk (0x1UL << DIEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ -#define DIEPEACHMSK1_INEPNMM DIEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define DIEPEACHMSK1_INEPNMM_Msk (0x1UL << DIEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ +#define DIEPEACHMSK1_INEPNMM DIEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ #define DIEPEACHMSK1_INEPNEM_Pos (6U) -#define DIEPEACHMSK1_INEPNEM_Msk (0x1UL << DIEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ -#define DIEPEACHMSK1_INEPNEM DIEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define DIEPEACHMSK1_INEPNEM_Msk (0x1UL << DIEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ +#define DIEPEACHMSK1_INEPNEM DIEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ #define DIEPEACHMSK1_TXFURM_Pos (8U) -#define DIEPEACHMSK1_TXFURM_Msk (0x1UL << DIEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ -#define DIEPEACHMSK1_TXFURM DIEPEACHMSK1_TXFURM_Msk /*!< FIFO underrun mask */ +#define DIEPEACHMSK1_TXFURM_Msk (0x1UL << DIEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ +#define DIEPEACHMSK1_TXFURM DIEPEACHMSK1_TXFURM_Msk /*!< FIFO underrun mask */ #define DIEPEACHMSK1_BIM_Pos (9U) -#define DIEPEACHMSK1_BIM_Msk (0x1UL << DIEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ -#define DIEPEACHMSK1_BIM DIEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ +#define DIEPEACHMSK1_BIM_Msk (0x1UL << DIEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ +#define DIEPEACHMSK1_BIM DIEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ #define DIEPEACHMSK1_NAKM_Pos (13U) -#define DIEPEACHMSK1_NAKM_Msk (0x1UL << DIEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ -#define DIEPEACHMSK1_NAKM DIEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ +#define DIEPEACHMSK1_NAKM_Msk (0x1UL << DIEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ +#define DIEPEACHMSK1_NAKM DIEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ /******************** Bit definition for HPRT register ********************/ #define HPRT_PCSTS_Pos (0U) -#define HPRT_PCSTS_Msk (0x1UL << HPRT_PCSTS_Pos) /*!< 0x00000001 */ -#define HPRT_PCSTS HPRT_PCSTS_Msk /*!< Port connect status */ +#define HPRT_PCSTS_Msk (0x1UL << HPRT_PCSTS_Pos) /*!< 0x00000001 */ +#define HPRT_PCSTS HPRT_PCSTS_Msk /*!< Port connect status */ #define HPRT_PCDET_Pos (1U) -#define HPRT_PCDET_Msk (0x1UL << HPRT_PCDET_Pos) /*!< 0x00000002 */ -#define HPRT_PCDET HPRT_PCDET_Msk /*!< Port connect detected */ +#define HPRT_PCDET_Msk (0x1UL << HPRT_PCDET_Pos) /*!< 0x00000002 */ +#define HPRT_PCDET HPRT_PCDET_Msk /*!< Port connect detected */ #define HPRT_PENA_Pos (2U) -#define HPRT_PENA_Msk (0x1UL << HPRT_PENA_Pos) /*!< 0x00000004 */ -#define HPRT_PENA HPRT_PENA_Msk /*!< Port enable */ +#define HPRT_PENA_Msk (0x1UL << HPRT_PENA_Pos) /*!< 0x00000004 */ +#define HPRT_PENA HPRT_PENA_Msk /*!< Port enable */ #define HPRT_PENCHNG_Pos (3U) -#define HPRT_PENCHNG_Msk (0x1UL << HPRT_PENCHNG_Pos) /*!< 0x00000008 */ -#define HPRT_PENCHNG HPRT_PENCHNG_Msk /*!< Port enable/disable change */ +#define HPRT_PENCHNG_Msk (0x1UL << HPRT_PENCHNG_Pos) /*!< 0x00000008 */ +#define HPRT_PENCHNG HPRT_PENCHNG_Msk /*!< Port enable/disable change */ #define HPRT_POCA_Pos (4U) -#define HPRT_POCA_Msk (0x1UL << HPRT_POCA_Pos) /*!< 0x00000010 */ -#define HPRT_POCA HPRT_POCA_Msk /*!< Port overcurrent active */ +#define HPRT_POCA_Msk (0x1UL << HPRT_POCA_Pos) /*!< 0x00000010 */ +#define HPRT_POCA HPRT_POCA_Msk /*!< Port overcurrent active */ #define HPRT_POCCHNG_Pos (5U) -#define HPRT_POCCHNG_Msk (0x1UL << HPRT_POCCHNG_Pos) /*!< 0x00000020 */ -#define HPRT_POCCHNG HPRT_POCCHNG_Msk /*!< Port overcurrent change */ +#define HPRT_POCCHNG_Msk (0x1UL << HPRT_POCCHNG_Pos) /*!< 0x00000020 */ +#define HPRT_POCCHNG HPRT_POCCHNG_Msk /*!< Port overcurrent change */ #define HPRT_PRES_Pos (6U) -#define HPRT_PRES_Msk (0x1UL << HPRT_PRES_Pos) /*!< 0x00000040 */ -#define HPRT_PRES HPRT_PRES_Msk /*!< Port resume */ +#define HPRT_PRES_Msk (0x1UL << HPRT_PRES_Pos) /*!< 0x00000040 */ +#define HPRT_PRES HPRT_PRES_Msk /*!< Port resume */ #define HPRT_PSUSP_Pos (7U) -#define HPRT_PSUSP_Msk (0x1UL << HPRT_PSUSP_Pos) /*!< 0x00000080 */ -#define HPRT_PSUSP HPRT_PSUSP_Msk /*!< Port suspend */ +#define HPRT_PSUSP_Msk (0x1UL << HPRT_PSUSP_Pos) /*!< 0x00000080 */ +#define HPRT_PSUSP HPRT_PSUSP_Msk /*!< Port suspend */ #define HPRT_PRST_Pos (8U) -#define HPRT_PRST_Msk (0x1UL << HPRT_PRST_Pos) /*!< 0x00000100 */ -#define HPRT_PRST HPRT_PRST_Msk /*!< Port reset */ +#define HPRT_PRST_Msk (0x1UL << HPRT_PRST_Pos) /*!< 0x00000100 */ +#define HPRT_PRST HPRT_PRST_Msk /*!< Port reset */ #define HPRT_PLSTS_Pos (10U) -#define HPRT_PLSTS_Msk (0x3UL << HPRT_PLSTS_Pos) /*!< 0x00000C00 */ -#define HPRT_PLSTS HPRT_PLSTS_Msk /*!< Port line status */ -#define HPRT_PLSTS_0 (0x1UL << HPRT_PLSTS_Pos) /*!< 0x00000400 */ -#define HPRT_PLSTS_1 (0x2UL << HPRT_PLSTS_Pos) /*!< 0x00000800 */ +#define HPRT_PLSTS_Msk (0x3UL << HPRT_PLSTS_Pos) /*!< 0x00000C00 */ +#define HPRT_PLSTS HPRT_PLSTS_Msk /*!< Port line status */ +#define HPRT_PLSTS_0 (0x1UL << HPRT_PLSTS_Pos) /*!< 0x00000400 */ +#define HPRT_PLSTS_1 (0x2UL << HPRT_PLSTS_Pos) /*!< 0x00000800 */ #define HPRT_PPWR_Pos (12U) -#define HPRT_PPWR_Msk (0x1UL << HPRT_PPWR_Pos) /*!< 0x00001000 */ -#define HPRT_PPWR HPRT_PPWR_Msk /*!< Port power */ +#define HPRT_PPWR_Msk (0x1UL << HPRT_PPWR_Pos) /*!< 0x00001000 */ +#define HPRT_PPWR HPRT_PPWR_Msk /*!< Port power */ #define HPRT_PTCTL_Pos (13U) -#define HPRT_PTCTL_Msk (0xFUL << HPRT_PTCTL_Pos) /*!< 0x0001E000 */ -#define HPRT_PTCTL HPRT_PTCTL_Msk /*!< Port test control */ -#define HPRT_PTCTL_0 (0x1UL << HPRT_PTCTL_Pos) /*!< 0x00002000 */ -#define HPRT_PTCTL_1 (0x2UL << HPRT_PTCTL_Pos) /*!< 0x00004000 */ -#define HPRT_PTCTL_2 (0x4UL << HPRT_PTCTL_Pos) /*!< 0x00008000 */ -#define HPRT_PTCTL_3 (0x8UL << HPRT_PTCTL_Pos) /*!< 0x00010000 */ +#define HPRT_PTCTL_Msk (0xFUL << HPRT_PTCTL_Pos) /*!< 0x0001E000 */ +#define HPRT_PTCTL HPRT_PTCTL_Msk /*!< Port test control */ +#define HPRT_PTCTL_0 (0x1UL << HPRT_PTCTL_Pos) /*!< 0x00002000 */ +#define HPRT_PTCTL_1 (0x2UL << HPRT_PTCTL_Pos) /*!< 0x00004000 */ +#define HPRT_PTCTL_2 (0x4UL << HPRT_PTCTL_Pos) /*!< 0x00008000 */ +#define HPRT_PTCTL_3 (0x8UL << HPRT_PTCTL_Pos) /*!< 0x00010000 */ #define HPRT_PSPD_Pos (17U) -#define HPRT_PSPD_Msk (0x3UL << HPRT_PSPD_Pos) /*!< 0x00060000 */ -#define HPRT_PSPD HPRT_PSPD_Msk /*!< Port speed */ -#define HPRT_PSPD_0 (0x1UL << HPRT_PSPD_Pos) /*!< 0x00020000 */ -#define HPRT_PSPD_1 (0x2UL << HPRT_PSPD_Pos) /*!< 0x00040000 */ +#define HPRT_PSPD_Msk (0x3UL << HPRT_PSPD_Pos) /*!< 0x00060000 */ +#define HPRT_PSPD HPRT_PSPD_Msk /*!< Port speed */ +#define HPRT_PSPD_0 (0x1UL << HPRT_PSPD_Pos) /*!< 0x00020000 */ +#define HPRT_PSPD_1 (0x2UL << HPRT_PSPD_Pos) /*!< 0x00040000 */ /******************** Bit definition for DOEPEACHMSK1 register ********************/ #define DOEPEACHMSK1_XFRCM_Pos (0U) -#define DOEPEACHMSK1_XFRCM_Msk (0x1UL << DOEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ -#define DOEPEACHMSK1_XFRCM DOEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define DOEPEACHMSK1_XFRCM_Msk (0x1UL << DOEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ +#define DOEPEACHMSK1_XFRCM DOEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ #define DOEPEACHMSK1_EPDM_Pos (1U) -#define DOEPEACHMSK1_EPDM_Msk (0x1UL << DOEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ -#define DOEPEACHMSK1_EPDM DOEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define DOEPEACHMSK1_EPDM_Msk (0x1UL << DOEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ +#define DOEPEACHMSK1_EPDM DOEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ #define DOEPEACHMSK1_TOM_Pos (3U) -#define DOEPEACHMSK1_TOM_Msk (0x1UL << DOEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ -#define DOEPEACHMSK1_TOM DOEPEACHMSK1_TOM_Msk /*!< Timeout condition mask */ +#define DOEPEACHMSK1_TOM_Msk (0x1UL << DOEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ +#define DOEPEACHMSK1_TOM DOEPEACHMSK1_TOM_Msk /*!< Timeout condition mask */ #define DOEPEACHMSK1_ITTXFEMSK_Pos (4U) -#define DOEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << DOEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ -#define DOEPEACHMSK1_ITTXFEMSK DOEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define DOEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << DOEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ +#define DOEPEACHMSK1_ITTXFEMSK DOEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ #define DOEPEACHMSK1_INEPNMM_Pos (5U) -#define DOEPEACHMSK1_INEPNMM_Msk (0x1UL << DOEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ -#define DOEPEACHMSK1_INEPNMM DOEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define DOEPEACHMSK1_INEPNMM_Msk (0x1UL << DOEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ +#define DOEPEACHMSK1_INEPNMM DOEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ #define DOEPEACHMSK1_INEPNEM_Pos (6U) -#define DOEPEACHMSK1_INEPNEM_Msk (0x1UL << DOEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ -#define DOEPEACHMSK1_INEPNEM DOEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define DOEPEACHMSK1_INEPNEM_Msk (0x1UL << DOEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ +#define DOEPEACHMSK1_INEPNEM DOEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ #define DOEPEACHMSK1_TXFURM_Pos (8U) -#define DOEPEACHMSK1_TXFURM_Msk (0x1UL << DOEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ -#define DOEPEACHMSK1_TXFURM DOEPEACHMSK1_TXFURM_Msk /*!< OUT packet error mask */ +#define DOEPEACHMSK1_TXFURM_Msk (0x1UL << DOEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ +#define DOEPEACHMSK1_TXFURM DOEPEACHMSK1_TXFURM_Msk /*!< OUT packet error mask */ #define DOEPEACHMSK1_BIM_Pos (9U) -#define DOEPEACHMSK1_BIM_Msk (0x1UL << DOEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ -#define DOEPEACHMSK1_BIM DOEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ +#define DOEPEACHMSK1_BIM_Msk (0x1UL << DOEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ +#define DOEPEACHMSK1_BIM DOEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ #define DOEPEACHMSK1_BERRM_Pos (12U) -#define DOEPEACHMSK1_BERRM_Msk (0x1UL << DOEPEACHMSK1_BERRM_Pos) /*!< 0x00001000 */ -#define DOEPEACHMSK1_BERRM DOEPEACHMSK1_BERRM_Msk /*!< Bubble error interrupt mask */ +#define DOEPEACHMSK1_BERRM_Msk (0x1UL << DOEPEACHMSK1_BERRM_Pos) /*!< 0x00001000 */ +#define DOEPEACHMSK1_BERRM DOEPEACHMSK1_BERRM_Msk /*!< Bubble error interrupt mask */ #define DOEPEACHMSK1_NAKM_Pos (13U) -#define DOEPEACHMSK1_NAKM_Msk (0x1UL << DOEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ -#define DOEPEACHMSK1_NAKM DOEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ +#define DOEPEACHMSK1_NAKM_Msk (0x1UL << DOEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ +#define DOEPEACHMSK1_NAKM DOEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ #define DOEPEACHMSK1_NYETM_Pos (14U) -#define DOEPEACHMSK1_NYETM_Msk (0x1UL << DOEPEACHMSK1_NYETM_Pos) /*!< 0x00004000 */ -#define DOEPEACHMSK1_NYETM DOEPEACHMSK1_NYETM_Msk /*!< NYET interrupt mask */ +#define DOEPEACHMSK1_NYETM_Msk (0x1UL << DOEPEACHMSK1_NYETM_Pos) /*!< 0x00004000 */ +#define DOEPEACHMSK1_NYETM DOEPEACHMSK1_NYETM_Msk /*!< NYET interrupt mask */ /******************** Bit definition for HPTXFSIZ register ********************/ #define HPTXFSIZ_PTXSA_Pos (0U) -#define HPTXFSIZ_PTXSA_Msk (0xFFFFUL << HPTXFSIZ_PTXSA_Pos) /*!< 0x0000FFFF */ -#define HPTXFSIZ_PTXSA HPTXFSIZ_PTXSA_Msk /*!< Host periodic TxFIFO start address */ +#define HPTXFSIZ_PTXSA_Msk (0xFFFFUL << HPTXFSIZ_PTXSA_Pos) /*!< 0x0000FFFF */ +#define HPTXFSIZ_PTXSA HPTXFSIZ_PTXSA_Msk /*!< Host periodic TxFIFO start address */ #define HPTXFSIZ_PTXFD_Pos (16U) -#define HPTXFSIZ_PTXFD_Msk (0xFFFFUL << HPTXFSIZ_PTXFD_Pos) /*!< 0xFFFF0000 */ -#define HPTXFSIZ_PTXFD HPTXFSIZ_PTXFD_Msk /*!< Host periodic TxFIFO depth */ +#define HPTXFSIZ_PTXFD_Msk (0xFFFFUL << HPTXFSIZ_PTXFD_Pos) /*!< 0xFFFF0000 */ +#define HPTXFSIZ_PTXFD HPTXFSIZ_PTXFD_Msk /*!< Host periodic TxFIFO depth */ /******************** Bit definition for DIEPCTL register ********************/ #define DIEPCTL_MPSIZ_Pos (0U) -#define DIEPCTL_MPSIZ_Msk (0x7FFUL << DIEPCTL_MPSIZ_Pos) /*!< 0x000007FF */ -#define DIEPCTL_MPSIZ DIEPCTL_MPSIZ_Msk /*!< Maximum packet size */ +#define DIEPCTL_MPSIZ_Msk (0x7FFUL << DIEPCTL_MPSIZ_Pos) /*!< 0x000007FF */ +#define DIEPCTL_MPSIZ DIEPCTL_MPSIZ_Msk /*!< Maximum packet size */ #define DIEPCTL_USBAEP_Pos (15U) -#define DIEPCTL_USBAEP_Msk (0x1UL << DIEPCTL_USBAEP_Pos) /*!< 0x00008000 */ -#define DIEPCTL_USBAEP DIEPCTL_USBAEP_Msk /*!< USB active endpoint */ +#define DIEPCTL_USBAEP_Msk (0x1UL << DIEPCTL_USBAEP_Pos) /*!< 0x00008000 */ +#define DIEPCTL_USBAEP DIEPCTL_USBAEP_Msk /*!< USB active endpoint */ #define DIEPCTL_EONUM_DPID_Pos (16U) -#define DIEPCTL_EONUM_DPID_Msk (0x1UL << DIEPCTL_EONUM_DPID_Pos) /*!< 0x00010000 */ -#define DIEPCTL_EONUM_DPID DIEPCTL_EONUM_DPID_Msk /*!< Even/odd frame */ +#define DIEPCTL_EONUM_DPID_Msk (0x1UL << DIEPCTL_EONUM_DPID_Pos) /*!< 0x00010000 */ +#define DIEPCTL_EONUM_DPID DIEPCTL_EONUM_DPID_Msk /*!< Even/odd frame */ #define DIEPCTL_NAKSTS_Pos (17U) -#define DIEPCTL_NAKSTS_Msk (0x1UL << DIEPCTL_NAKSTS_Pos) /*!< 0x00020000 */ -#define DIEPCTL_NAKSTS DIEPCTL_NAKSTS_Msk /*!< NAK status */ +#define DIEPCTL_NAKSTS_Msk (0x1UL << DIEPCTL_NAKSTS_Pos) /*!< 0x00020000 */ +#define DIEPCTL_NAKSTS DIEPCTL_NAKSTS_Msk /*!< NAK status */ #define DIEPCTL_EPTYP_Pos (18U) -#define DIEPCTL_EPTYP_Msk (0x3UL << DIEPCTL_EPTYP_Pos) /*!< 0x000C0000 */ -#define DIEPCTL_EPTYP DIEPCTL_EPTYP_Msk /*!< Endpoint type */ -#define DIEPCTL_EPTYP_0 (0x1UL << DIEPCTL_EPTYP_Pos) /*!< 0x00040000 */ -#define DIEPCTL_EPTYP_1 (0x2UL << DIEPCTL_EPTYP_Pos) /*!< 0x00080000 */ +#define DIEPCTL_EPTYP_Msk (0x3UL << DIEPCTL_EPTYP_Pos) /*!< 0x000C0000 */ +#define DIEPCTL_EPTYP DIEPCTL_EPTYP_Msk /*!< Endpoint type */ +#define DIEPCTL_EPTYP_0 (0x1UL << DIEPCTL_EPTYP_Pos) /*!< 0x00040000 */ +#define DIEPCTL_EPTYP_1 (0x2UL << DIEPCTL_EPTYP_Pos) /*!< 0x00080000 */ #define DIEPCTL_STALL_Pos (21U) -#define DIEPCTL_STALL_Msk (0x1UL << DIEPCTL_STALL_Pos) /*!< 0x00200000 */ -#define DIEPCTL_STALL DIEPCTL_STALL_Msk /*!< STALL handshake */ +#define DIEPCTL_STALL_Msk (0x1UL << DIEPCTL_STALL_Pos) /*!< 0x00200000 */ +#define DIEPCTL_STALL DIEPCTL_STALL_Msk /*!< STALL handshake */ #define DIEPCTL_TXFNUM_Pos (22U) -#define DIEPCTL_TXFNUM_Msk (0xFUL << DIEPCTL_TXFNUM_Pos) /*!< 0x03C00000 */ -#define DIEPCTL_TXFNUM DIEPCTL_TXFNUM_Msk /*!< TxFIFO number */ -#define DIEPCTL_TXFNUM_0 (0x1UL << DIEPCTL_TXFNUM_Pos) /*!< 0x00400000 */ -#define DIEPCTL_TXFNUM_1 (0x2UL << DIEPCTL_TXFNUM_Pos) /*!< 0x00800000 */ -#define DIEPCTL_TXFNUM_2 (0x4UL << DIEPCTL_TXFNUM_Pos) /*!< 0x01000000 */ -#define DIEPCTL_TXFNUM_3 (0x8UL << DIEPCTL_TXFNUM_Pos) /*!< 0x02000000 */ +#define DIEPCTL_TXFNUM_Msk (0xFUL << DIEPCTL_TXFNUM_Pos) /*!< 0x03C00000 */ +#define DIEPCTL_TXFNUM DIEPCTL_TXFNUM_Msk /*!< TxFIFO number */ +#define DIEPCTL_TXFNUM_0 (0x1UL << DIEPCTL_TXFNUM_Pos) /*!< 0x00400000 */ +#define DIEPCTL_TXFNUM_1 (0x2UL << DIEPCTL_TXFNUM_Pos) /*!< 0x00800000 */ +#define DIEPCTL_TXFNUM_2 (0x4UL << DIEPCTL_TXFNUM_Pos) /*!< 0x01000000 */ +#define DIEPCTL_TXFNUM_3 (0x8UL << DIEPCTL_TXFNUM_Pos) /*!< 0x02000000 */ #define DIEPCTL_CNAK_Pos (26U) -#define DIEPCTL_CNAK_Msk (0x1UL << DIEPCTL_CNAK_Pos) /*!< 0x04000000 */ -#define DIEPCTL_CNAK DIEPCTL_CNAK_Msk /*!< Clear NAK */ +#define DIEPCTL_CNAK_Msk (0x1UL << DIEPCTL_CNAK_Pos) /*!< 0x04000000 */ +#define DIEPCTL_CNAK DIEPCTL_CNAK_Msk /*!< Clear NAK */ #define DIEPCTL_SNAK_Pos (27U) -#define DIEPCTL_SNAK_Msk (0x1UL << DIEPCTL_SNAK_Pos) /*!< 0x08000000 */ -#define DIEPCTL_SNAK DIEPCTL_SNAK_Msk /*!< Set NAK */ +#define DIEPCTL_SNAK_Msk (0x1UL << DIEPCTL_SNAK_Pos) /*!< 0x08000000 */ +#define DIEPCTL_SNAK DIEPCTL_SNAK_Msk /*!< Set NAK */ #define DIEPCTL_SD0PID_SEVNFRM_Pos (28U) -#define DIEPCTL_SD0PID_SEVNFRM_Msk (0x1UL << DIEPCTL_SD0PID_SEVNFRM_Pos) /*!< 0x10000000 */ -#define DIEPCTL_SD0PID_SEVNFRM DIEPCTL_SD0PID_SEVNFRM_Msk /*!< Set DATA0 PID */ +#define DIEPCTL_SD0PID_SEVNFRM_Msk (0x1UL << DIEPCTL_SD0PID_SEVNFRM_Pos) /*!< 0x10000000 */ +#define DIEPCTL_SD0PID_SEVNFRM DIEPCTL_SD0PID_SEVNFRM_Msk /*!< Set DATA0 PID */ #define DIEPCTL_SODDFRM_Pos (29U) -#define DIEPCTL_SODDFRM_Msk (0x1UL << DIEPCTL_SODDFRM_Pos) /*!< 0x20000000 */ -#define DIEPCTL_SODDFRM DIEPCTL_SODDFRM_Msk /*!< Set odd frame */ +#define DIEPCTL_SODDFRM_Msk (0x1UL << DIEPCTL_SODDFRM_Pos) /*!< 0x20000000 */ +#define DIEPCTL_SODDFRM DIEPCTL_SODDFRM_Msk /*!< Set odd frame */ #define DIEPCTL_EPDIS_Pos (30U) -#define DIEPCTL_EPDIS_Msk (0x1UL << DIEPCTL_EPDIS_Pos) /*!< 0x40000000 */ -#define DIEPCTL_EPDIS DIEPCTL_EPDIS_Msk /*!< Endpoint disable */ +#define DIEPCTL_EPDIS_Msk (0x1UL << DIEPCTL_EPDIS_Pos) /*!< 0x40000000 */ +#define DIEPCTL_EPDIS DIEPCTL_EPDIS_Msk /*!< Endpoint disable */ #define DIEPCTL_EPENA_Pos (31U) -#define DIEPCTL_EPENA_Msk (0x1UL << DIEPCTL_EPENA_Pos) /*!< 0x80000000 */ -#define DIEPCTL_EPENA DIEPCTL_EPENA_Msk /*!< Endpoint enable */ +#define DIEPCTL_EPENA_Msk (0x1UL << DIEPCTL_EPENA_Pos) /*!< 0x80000000 */ +#define DIEPCTL_EPENA DIEPCTL_EPENA_Msk /*!< Endpoint enable */ /******************** Bit definition for HCCHAR register ********************/ #define HCCHAR_MPSIZ_Pos (0U) -#define HCCHAR_MPSIZ_Msk (0x7FFUL << HCCHAR_MPSIZ_Pos) /*!< 0x000007FF */ -#define HCCHAR_MPSIZ HCCHAR_MPSIZ_Msk /*!< Maximum packet size */ +#define HCCHAR_MPSIZ_Msk (0x7FFUL << HCCHAR_MPSIZ_Pos) /*!< 0x000007FF */ +#define HCCHAR_MPSIZ HCCHAR_MPSIZ_Msk /*!< Maximum packet size */ #define HCCHAR_EPNUM_Pos (11U) -#define HCCHAR_EPNUM_Msk (0xFUL << HCCHAR_EPNUM_Pos) /*!< 0x00007800 */ -#define HCCHAR_EPNUM HCCHAR_EPNUM_Msk /*!< Endpoint number */ -#define HCCHAR_EPNUM_0 (0x1UL << HCCHAR_EPNUM_Pos) /*!< 0x00000800 */ -#define HCCHAR_EPNUM_1 (0x2UL << HCCHAR_EPNUM_Pos) /*!< 0x00001000 */ -#define HCCHAR_EPNUM_2 (0x4UL << HCCHAR_EPNUM_Pos) /*!< 0x00002000 */ -#define HCCHAR_EPNUM_3 (0x8UL << HCCHAR_EPNUM_Pos) /*!< 0x00004000 */ +#define HCCHAR_EPNUM_Msk (0xFUL << HCCHAR_EPNUM_Pos) /*!< 0x00007800 */ +#define HCCHAR_EPNUM HCCHAR_EPNUM_Msk /*!< Endpoint number */ +#define HCCHAR_EPNUM_0 (0x1UL << HCCHAR_EPNUM_Pos) /*!< 0x00000800 */ +#define HCCHAR_EPNUM_1 (0x2UL << HCCHAR_EPNUM_Pos) /*!< 0x00001000 */ +#define HCCHAR_EPNUM_2 (0x4UL << HCCHAR_EPNUM_Pos) /*!< 0x00002000 */ +#define HCCHAR_EPNUM_3 (0x8UL << HCCHAR_EPNUM_Pos) /*!< 0x00004000 */ #define HCCHAR_EPDIR_Pos (15U) -#define HCCHAR_EPDIR_Msk (0x1UL << HCCHAR_EPDIR_Pos) /*!< 0x00008000 */ -#define HCCHAR_EPDIR HCCHAR_EPDIR_Msk /*!< Endpoint direction */ +#define HCCHAR_EPDIR_Msk (0x1UL << HCCHAR_EPDIR_Pos) /*!< 0x00008000 */ +#define HCCHAR_EPDIR HCCHAR_EPDIR_Msk /*!< Endpoint direction */ #define HCCHAR_LSDEV_Pos (17U) -#define HCCHAR_LSDEV_Msk (0x1UL << HCCHAR_LSDEV_Pos) /*!< 0x00020000 */ -#define HCCHAR_LSDEV HCCHAR_LSDEV_Msk /*!< Low-speed device */ +#define HCCHAR_LSDEV_Msk (0x1UL << HCCHAR_LSDEV_Pos) /*!< 0x00020000 */ +#define HCCHAR_LSDEV HCCHAR_LSDEV_Msk /*!< Low-speed device */ #define HCCHAR_EPTYP_Pos (18U) -#define HCCHAR_EPTYP_Msk (0x3UL << HCCHAR_EPTYP_Pos) /*!< 0x000C0000 */ -#define HCCHAR_EPTYP HCCHAR_EPTYP_Msk /*!< Endpoint type */ -#define HCCHAR_EPTYP_0 (0x1UL << HCCHAR_EPTYP_Pos) /*!< 0x00040000 */ -#define HCCHAR_EPTYP_1 (0x2UL << HCCHAR_EPTYP_Pos) /*!< 0x00080000 */ +#define HCCHAR_EPTYP_Msk (0x3UL << HCCHAR_EPTYP_Pos) /*!< 0x000C0000 */ +#define HCCHAR_EPTYP HCCHAR_EPTYP_Msk /*!< Endpoint type */ +#define HCCHAR_EPTYP_0 (0x1UL << HCCHAR_EPTYP_Pos) /*!< 0x00040000 */ +#define HCCHAR_EPTYP_1 (0x2UL << HCCHAR_EPTYP_Pos) /*!< 0x00080000 */ #define HCCHAR_MC_Pos (20U) -#define HCCHAR_MC_Msk (0x3UL << HCCHAR_MC_Pos) /*!< 0x00300000 */ -#define HCCHAR_MC HCCHAR_MC_Msk /*!< Multi Count (MC) / Error Count (EC) */ -#define HCCHAR_MC_0 (0x1UL << HCCHAR_MC_Pos) /*!< 0x00100000 */ -#define HCCHAR_MC_1 (0x2UL << HCCHAR_MC_Pos) /*!< 0x00200000 */ +#define HCCHAR_MC_Msk (0x3UL << HCCHAR_MC_Pos) /*!< 0x00300000 */ +#define HCCHAR_MC HCCHAR_MC_Msk /*!< Multi Count (MC) / Error Count (EC) */ +#define HCCHAR_MC_0 (0x1UL << HCCHAR_MC_Pos) /*!< 0x00100000 */ +#define HCCHAR_MC_1 (0x2UL << HCCHAR_MC_Pos) /*!< 0x00200000 */ #define HCCHAR_DAD_Pos (22U) -#define HCCHAR_DAD_Msk (0x7FUL << HCCHAR_DAD_Pos) /*!< 0x1FC00000 */ -#define HCCHAR_DAD HCCHAR_DAD_Msk /*!< Device address */ -#define HCCHAR_DAD_0 (0x01UL << HCCHAR_DAD_Pos) /*!< 0x00400000 */ -#define HCCHAR_DAD_1 (0x02UL << HCCHAR_DAD_Pos) /*!< 0x00800000 */ -#define HCCHAR_DAD_2 (0x04UL << HCCHAR_DAD_Pos) /*!< 0x01000000 */ -#define HCCHAR_DAD_3 (0x08UL << HCCHAR_DAD_Pos) /*!< 0x02000000 */ -#define HCCHAR_DAD_4 (0x10UL << HCCHAR_DAD_Pos) /*!< 0x04000000 */ -#define HCCHAR_DAD_5 (0x20UL << HCCHAR_DAD_Pos) /*!< 0x08000000 */ -#define HCCHAR_DAD_6 (0x40UL << HCCHAR_DAD_Pos) /*!< 0x10000000 */ +#define HCCHAR_DAD_Msk (0x7FUL << HCCHAR_DAD_Pos) /*!< 0x1FC00000 */ +#define HCCHAR_DAD HCCHAR_DAD_Msk /*!< Device address */ +#define HCCHAR_DAD_0 (0x01UL << HCCHAR_DAD_Pos) /*!< 0x00400000 */ +#define HCCHAR_DAD_1 (0x02UL << HCCHAR_DAD_Pos) /*!< 0x00800000 */ +#define HCCHAR_DAD_2 (0x04UL << HCCHAR_DAD_Pos) /*!< 0x01000000 */ +#define HCCHAR_DAD_3 (0x08UL << HCCHAR_DAD_Pos) /*!< 0x02000000 */ +#define HCCHAR_DAD_4 (0x10UL << HCCHAR_DAD_Pos) /*!< 0x04000000 */ +#define HCCHAR_DAD_5 (0x20UL << HCCHAR_DAD_Pos) /*!< 0x08000000 */ +#define HCCHAR_DAD_6 (0x40UL << HCCHAR_DAD_Pos) /*!< 0x10000000 */ #define HCCHAR_ODDFRM_Pos (29U) -#define HCCHAR_ODDFRM_Msk (0x1UL << HCCHAR_ODDFRM_Pos) /*!< 0x20000000 */ -#define HCCHAR_ODDFRM HCCHAR_ODDFRM_Msk /*!< Odd frame */ +#define HCCHAR_ODDFRM_Msk (0x1UL << HCCHAR_ODDFRM_Pos) /*!< 0x20000000 */ +#define HCCHAR_ODDFRM HCCHAR_ODDFRM_Msk /*!< Odd frame */ #define HCCHAR_CHDIS_Pos (30U) -#define HCCHAR_CHDIS_Msk (0x1UL << HCCHAR_CHDIS_Pos) /*!< 0x40000000 */ -#define HCCHAR_CHDIS HCCHAR_CHDIS_Msk /*!< Channel disable */ +#define HCCHAR_CHDIS_Msk (0x1UL << HCCHAR_CHDIS_Pos) /*!< 0x40000000 */ +#define HCCHAR_CHDIS HCCHAR_CHDIS_Msk /*!< Channel disable */ #define HCCHAR_CHENA_Pos (31U) -#define HCCHAR_CHENA_Msk (0x1UL << HCCHAR_CHENA_Pos) /*!< 0x80000000 */ -#define HCCHAR_CHENA HCCHAR_CHENA_Msk /*!< Channel enable */ +#define HCCHAR_CHENA_Msk (0x1UL << HCCHAR_CHENA_Pos) /*!< 0x80000000 */ +#define HCCHAR_CHENA HCCHAR_CHENA_Msk /*!< Channel enable */ /******************** Bit definition for HCSPLT register ********************/ #define HCSPLT_PRTADDR_Pos (0U) -#define HCSPLT_PRTADDR_Msk (0x7FUL << HCSPLT_PRTADDR_Pos) /*!< 0x0000007F */ -#define HCSPLT_PRTADDR HCSPLT_PRTADDR_Msk /*!< Port address */ -#define HCSPLT_PRTADDR_0 (0x01UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000001 */ -#define HCSPLT_PRTADDR_1 (0x02UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000002 */ -#define HCSPLT_PRTADDR_2 (0x04UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000004 */ -#define HCSPLT_PRTADDR_3 (0x08UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000008 */ -#define HCSPLT_PRTADDR_4 (0x10UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000010 */ -#define HCSPLT_PRTADDR_5 (0x20UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000020 */ -#define HCSPLT_PRTADDR_6 (0x40UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000040 */ +#define HCSPLT_PRTADDR_Msk (0x7FUL << HCSPLT_PRTADDR_Pos) /*!< 0x0000007F */ +#define HCSPLT_PRTADDR HCSPLT_PRTADDR_Msk /*!< Port address */ +#define HCSPLT_PRTADDR_0 (0x01UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000001 */ +#define HCSPLT_PRTADDR_1 (0x02UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000002 */ +#define HCSPLT_PRTADDR_2 (0x04UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000004 */ +#define HCSPLT_PRTADDR_3 (0x08UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000008 */ +#define HCSPLT_PRTADDR_4 (0x10UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000010 */ +#define HCSPLT_PRTADDR_5 (0x20UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000020 */ +#define HCSPLT_PRTADDR_6 (0x40UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000040 */ #define HCSPLT_HUBADDR_Pos (7U) -#define HCSPLT_HUBADDR_Msk (0x7FUL << HCSPLT_HUBADDR_Pos) /*!< 0x00003F80 */ -#define HCSPLT_HUBADDR HCSPLT_HUBADDR_Msk /*!< Hub address */ -#define HCSPLT_HUBADDR_0 (0x01UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000080 */ -#define HCSPLT_HUBADDR_1 (0x02UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000100 */ -#define HCSPLT_HUBADDR_2 (0x04UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000200 */ -#define HCSPLT_HUBADDR_3 (0x08UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000400 */ -#define HCSPLT_HUBADDR_4 (0x10UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000800 */ -#define HCSPLT_HUBADDR_5 (0x20UL << HCSPLT_HUBADDR_Pos) /*!< 0x00001000 */ -#define HCSPLT_HUBADDR_6 (0x40UL << HCSPLT_HUBADDR_Pos) /*!< 0x00002000 */ +#define HCSPLT_HUBADDR_Msk (0x7FUL << HCSPLT_HUBADDR_Pos) /*!< 0x00003F80 */ +#define HCSPLT_HUBADDR HCSPLT_HUBADDR_Msk /*!< Hub address */ +#define HCSPLT_HUBADDR_0 (0x01UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000080 */ +#define HCSPLT_HUBADDR_1 (0x02UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000100 */ +#define HCSPLT_HUBADDR_2 (0x04UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000200 */ +#define HCSPLT_HUBADDR_3 (0x08UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000400 */ +#define HCSPLT_HUBADDR_4 (0x10UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000800 */ +#define HCSPLT_HUBADDR_5 (0x20UL << HCSPLT_HUBADDR_Pos) /*!< 0x00001000 */ +#define HCSPLT_HUBADDR_6 (0x40UL << HCSPLT_HUBADDR_Pos) /*!< 0x00002000 */ #define HCSPLT_XACTPOS_Pos (14U) -#define HCSPLT_XACTPOS_Msk (0x3UL << HCSPLT_XACTPOS_Pos) /*!< 0x0000C000 */ -#define HCSPLT_XACTPOS HCSPLT_XACTPOS_Msk /*!< XACTPOS */ -#define HCSPLT_XACTPOS_0 (0x1UL << HCSPLT_XACTPOS_Pos) /*!< 0x00004000 */ -#define HCSPLT_XACTPOS_1 (0x2UL << HCSPLT_XACTPOS_Pos) /*!< 0x00008000 */ +#define HCSPLT_XACTPOS_Msk (0x3UL << HCSPLT_XACTPOS_Pos) /*!< 0x0000C000 */ +#define HCSPLT_XACTPOS HCSPLT_XACTPOS_Msk /*!< XACTPOS */ +#define HCSPLT_XACTPOS_0 (0x1UL << HCSPLT_XACTPOS_Pos) /*!< 0x00004000 */ +#define HCSPLT_XACTPOS_1 (0x2UL << HCSPLT_XACTPOS_Pos) /*!< 0x00008000 */ #define HCSPLT_COMPLSPLT_Pos (16U) -#define HCSPLT_COMPLSPLT_Msk (0x1UL << HCSPLT_COMPLSPLT_Pos) /*!< 0x00010000 */ -#define HCSPLT_COMPLSPLT HCSPLT_COMPLSPLT_Msk /*!< Do complete split */ +#define HCSPLT_COMPLSPLT_Msk (0x1UL << HCSPLT_COMPLSPLT_Pos) /*!< 0x00010000 */ +#define HCSPLT_COMPLSPLT HCSPLT_COMPLSPLT_Msk /*!< Do complete split */ #define HCSPLT_SPLITEN_Pos (31U) -#define HCSPLT_SPLITEN_Msk (0x1UL << HCSPLT_SPLITEN_Pos) /*!< 0x80000000 */ -#define HCSPLT_SPLITEN HCSPLT_SPLITEN_Msk /*!< Split enable */ +#define HCSPLT_SPLITEN_Msk (0x1UL << HCSPLT_SPLITEN_Pos) /*!< 0x80000000 */ +#define HCSPLT_SPLITEN HCSPLT_SPLITEN_Msk /*!< Split enable */ /******************** Bit definition for HCINT register ********************/ #define HCINT_XFRC_Pos (0U) -#define HCINT_XFRC_Msk (0x1UL << HCINT_XFRC_Pos) /*!< 0x00000001 */ -#define HCINT_XFRC HCINT_XFRC_Msk /*!< Transfer completed */ +#define HCINT_XFRC_Msk (0x1UL << HCINT_XFRC_Pos) /*!< 0x00000001 */ +#define HCINT_XFRC HCINT_XFRC_Msk /*!< Transfer completed */ #define HCINT_CHH_Pos (1U) -#define HCINT_CHH_Msk (0x1UL << HCINT_CHH_Pos) /*!< 0x00000002 */ -#define HCINT_CHH HCINT_CHH_Msk /*!< Channel halted */ +#define HCINT_CHH_Msk (0x1UL << HCINT_CHH_Pos) /*!< 0x00000002 */ +#define HCINT_CHH HCINT_CHH_Msk /*!< Channel halted */ #define HCINT_AHBERR_Pos (2U) -#define HCINT_AHBERR_Msk (0x1UL << HCINT_AHBERR_Pos) /*!< 0x00000004 */ -#define HCINT_AHBERR HCINT_AHBERR_Msk /*!< AHB error */ +#define HCINT_AHBERR_Msk (0x1UL << HCINT_AHBERR_Pos) /*!< 0x00000004 */ +#define HCINT_AHBERR HCINT_AHBERR_Msk /*!< AHB error */ #define HCINT_STALL_Pos (3U) -#define HCINT_STALL_Msk (0x1UL << HCINT_STALL_Pos) /*!< 0x00000008 */ -#define HCINT_STALL HCINT_STALL_Msk /*!< STALL response received interrupt */ +#define HCINT_STALL_Msk (0x1UL << HCINT_STALL_Pos) /*!< 0x00000008 */ +#define HCINT_STALL HCINT_STALL_Msk /*!< STALL response received interrupt */ #define HCINT_NAK_Pos (4U) -#define HCINT_NAK_Msk (0x1UL << HCINT_NAK_Pos) /*!< 0x00000010 */ -#define HCINT_NAK HCINT_NAK_Msk /*!< NAK response received interrupt */ +#define HCINT_NAK_Msk (0x1UL << HCINT_NAK_Pos) /*!< 0x00000010 */ +#define HCINT_NAK HCINT_NAK_Msk /*!< NAK response received interrupt */ #define HCINT_ACK_Pos (5U) -#define HCINT_ACK_Msk (0x1UL << HCINT_ACK_Pos) /*!< 0x00000020 */ -#define HCINT_ACK HCINT_ACK_Msk /*!< ACK response received/transmitted interrupt */ +#define HCINT_ACK_Msk (0x1UL << HCINT_ACK_Pos) /*!< 0x00000020 */ +#define HCINT_ACK HCINT_ACK_Msk /*!< ACK response received/transmitted interrupt */ #define HCINT_NYET_Pos (6U) -#define HCINT_NYET_Msk (0x1UL << HCINT_NYET_Pos) /*!< 0x00000040 */ -#define HCINT_NYET HCINT_NYET_Msk /*!< Response received interrupt */ +#define HCINT_NYET_Msk (0x1UL << HCINT_NYET_Pos) /*!< 0x00000040 */ +#define HCINT_NYET HCINT_NYET_Msk /*!< Response received interrupt */ #define HCINT_TXERR_Pos (7U) -#define HCINT_TXERR_Msk (0x1UL << HCINT_TXERR_Pos) /*!< 0x00000080 */ -#define HCINT_TXERR HCINT_TXERR_Msk /*!< Transaction error */ +#define HCINT_TXERR_Msk (0x1UL << HCINT_TXERR_Pos) /*!< 0x00000080 */ +#define HCINT_TXERR HCINT_TXERR_Msk /*!< Transaction error */ #define HCINT_BBERR_Pos (8U) -#define HCINT_BBERR_Msk (0x1UL << HCINT_BBERR_Pos) /*!< 0x00000100 */ -#define HCINT_BBERR HCINT_BBERR_Msk /*!< Babble error */ +#define HCINT_BBERR_Msk (0x1UL << HCINT_BBERR_Pos) /*!< 0x00000100 */ +#define HCINT_BBERR HCINT_BBERR_Msk /*!< Babble error */ #define HCINT_FRMOR_Pos (9U) -#define HCINT_FRMOR_Msk (0x1UL << HCINT_FRMOR_Pos) /*!< 0x00000200 */ -#define HCINT_FRMOR HCINT_FRMOR_Msk /*!< Frame overrun */ +#define HCINT_FRMOR_Msk (0x1UL << HCINT_FRMOR_Pos) /*!< 0x00000200 */ +#define HCINT_FRMOR HCINT_FRMOR_Msk /*!< Frame overrun */ #define HCINT_DTERR_Pos (10U) -#define HCINT_DTERR_Msk (0x1UL << HCINT_DTERR_Pos) /*!< 0x00000400 */ -#define HCINT_DTERR HCINT_DTERR_Msk /*!< Data toggle error */ +#define HCINT_DTERR_Msk (0x1UL << HCINT_DTERR_Pos) /*!< 0x00000400 */ +#define HCINT_DTERR HCINT_DTERR_Msk /*!< Data toggle error */ /******************** Bit definition for DIEPINT register ********************/ #define DIEPINT_XFRC_Pos (0U) -#define DIEPINT_XFRC_Msk (0x1UL << DIEPINT_XFRC_Pos) /*!< 0x00000001 */ -#define DIEPINT_XFRC DIEPINT_XFRC_Msk /*!< Transfer completed interrupt */ +#define DIEPINT_XFRC_Msk (0x1UL << DIEPINT_XFRC_Pos) /*!< 0x00000001 */ +#define DIEPINT_XFRC DIEPINT_XFRC_Msk /*!< Transfer completed interrupt */ #define DIEPINT_EPDISD_Pos (1U) -#define DIEPINT_EPDISD_Msk (0x1UL << DIEPINT_EPDISD_Pos) /*!< 0x00000002 */ -#define DIEPINT_EPDISD DIEPINT_EPDISD_Msk /*!< Endpoint disabled interrupt */ +#define DIEPINT_EPDISD_Msk (0x1UL << DIEPINT_EPDISD_Pos) /*!< 0x00000002 */ +#define DIEPINT_EPDISD DIEPINT_EPDISD_Msk /*!< Endpoint disabled interrupt */ #define DIEPINT_AHBERR_Pos (2U) -#define DIEPINT_AHBERR_Msk (0x1UL << DIEPINT_AHBERR_Pos) /*!< 0x00000004 */ -#define DIEPINT_AHBERR DIEPINT_AHBERR_Msk /*!< AHB Error (AHBErr) during an IN transaction */ +#define DIEPINT_AHBERR_Msk (0x1UL << DIEPINT_AHBERR_Pos) /*!< 0x00000004 */ +#define DIEPINT_AHBERR DIEPINT_AHBERR_Msk /*!< AHB Error (AHBErr) during an IN transaction */ #define DIEPINT_TOC_Pos (3U) -#define DIEPINT_TOC_Msk (0x1UL << DIEPINT_TOC_Pos) /*!< 0x00000008 */ -#define DIEPINT_TOC DIEPINT_TOC_Msk /*!< Timeout condition */ +#define DIEPINT_TOC_Msk (0x1UL << DIEPINT_TOC_Pos) /*!< 0x00000008 */ +#define DIEPINT_TOC DIEPINT_TOC_Msk /*!< Timeout condition */ #define DIEPINT_ITTXFE_Pos (4U) -#define DIEPINT_ITTXFE_Msk (0x1UL << DIEPINT_ITTXFE_Pos) /*!< 0x00000010 */ -#define DIEPINT_ITTXFE DIEPINT_ITTXFE_Msk /*!< IN token received when TxFIFO is empty */ +#define DIEPINT_ITTXFE_Msk (0x1UL << DIEPINT_ITTXFE_Pos) /*!< 0x00000010 */ +#define DIEPINT_ITTXFE DIEPINT_ITTXFE_Msk /*!< IN token received when TxFIFO is empty */ #define DIEPINT_INEPNM_Pos (5U) -#define DIEPINT_INEPNM_Msk (0x1UL << DIEPINT_INEPNM_Pos) /*!< 0x00000020 */ -#define DIEPINT_INEPNM DIEPINT_INEPNM_Msk /*!< IN token received with EP mismatch */ +#define DIEPINT_INEPNM_Msk (0x1UL << DIEPINT_INEPNM_Pos) /*!< 0x00000020 */ +#define DIEPINT_INEPNM DIEPINT_INEPNM_Msk /*!< IN token received with EP mismatch */ #define DIEPINT_INEPNE_Pos (6U) -#define DIEPINT_INEPNE_Msk (0x1UL << DIEPINT_INEPNE_Pos) /*!< 0x00000040 */ -#define DIEPINT_INEPNE DIEPINT_INEPNE_Msk /*!< IN endpoint NAK effective */ +#define DIEPINT_INEPNE_Msk (0x1UL << DIEPINT_INEPNE_Pos) /*!< 0x00000040 */ +#define DIEPINT_INEPNE DIEPINT_INEPNE_Msk /*!< IN endpoint NAK effective */ #define DIEPINT_TXFE_Pos (7U) -#define DIEPINT_TXFE_Msk (0x1UL << DIEPINT_TXFE_Pos) /*!< 0x00000080 */ -#define DIEPINT_TXFE DIEPINT_TXFE_Msk /*!< Transmit FIFO empty */ +#define DIEPINT_TXFE_Msk (0x1UL << DIEPINT_TXFE_Pos) /*!< 0x00000080 */ +#define DIEPINT_TXFE DIEPINT_TXFE_Msk /*!< Transmit FIFO empty */ #define DIEPINT_TXFIFOUDRN_Pos (8U) -#define DIEPINT_TXFIFOUDRN_Msk (0x1UL << DIEPINT_TXFIFOUDRN_Pos) /*!< 0x00000100 */ -#define DIEPINT_TXFIFOUDRN DIEPINT_TXFIFOUDRN_Msk /*!< Transmit Fifo Underrun */ +#define DIEPINT_TXFIFOUDRN_Msk (0x1UL << DIEPINT_TXFIFOUDRN_Pos) /*!< 0x00000100 */ +#define DIEPINT_TXFIFOUDRN DIEPINT_TXFIFOUDRN_Msk /*!< Transmit Fifo Underrun */ #define DIEPINT_BNA_Pos (9U) -#define DIEPINT_BNA_Msk (0x1UL << DIEPINT_BNA_Pos) /*!< 0x00000200 */ -#define DIEPINT_BNA DIEPINT_BNA_Msk /*!< Buffer not available interrupt */ +#define DIEPINT_BNA_Msk (0x1UL << DIEPINT_BNA_Pos) /*!< 0x00000200 */ +#define DIEPINT_BNA DIEPINT_BNA_Msk /*!< Buffer not available interrupt */ #define DIEPINT_PKTDRPSTS_Pos (11U) -#define DIEPINT_PKTDRPSTS_Msk (0x1UL << DIEPINT_PKTDRPSTS_Pos) /*!< 0x00000800 */ -#define DIEPINT_PKTDRPSTS DIEPINT_PKTDRPSTS_Msk /*!< Packet dropped status */ +#define DIEPINT_PKTDRPSTS_Msk (0x1UL << DIEPINT_PKTDRPSTS_Pos) /*!< 0x00000800 */ +#define DIEPINT_PKTDRPSTS DIEPINT_PKTDRPSTS_Msk /*!< Packet dropped status */ #define DIEPINT_BERR_Pos (12U) -#define DIEPINT_BERR_Msk (0x1UL << DIEPINT_BERR_Pos) /*!< 0x00001000 */ -#define DIEPINT_BERR DIEPINT_BERR_Msk /*!< Babble error interrupt */ +#define DIEPINT_BERR_Msk (0x1UL << DIEPINT_BERR_Pos) /*!< 0x00001000 */ +#define DIEPINT_BERR DIEPINT_BERR_Msk /*!< Babble error interrupt */ #define DIEPINT_NAK_Pos (13U) -#define DIEPINT_NAK_Msk (0x1UL << DIEPINT_NAK_Pos) /*!< 0x00002000 */ -#define DIEPINT_NAK DIEPINT_NAK_Msk /*!< NAK interrupt */ +#define DIEPINT_NAK_Msk (0x1UL << DIEPINT_NAK_Pos) /*!< 0x00002000 */ +#define DIEPINT_NAK DIEPINT_NAK_Msk /*!< NAK interrupt */ /******************** Bit definition for HCINTMSK register ********************/ #define HCINTMSK_XFRCM_Pos (0U) -#define HCINTMSK_XFRCM_Msk (0x1UL << HCINTMSK_XFRCM_Pos) /*!< 0x00000001 */ -#define HCINTMSK_XFRCM HCINTMSK_XFRCM_Msk /*!< Transfer completed mask */ +#define HCINTMSK_XFRCM_Msk (0x1UL << HCINTMSK_XFRCM_Pos) /*!< 0x00000001 */ +#define HCINTMSK_XFRCM HCINTMSK_XFRCM_Msk /*!< Transfer completed mask */ #define HCINTMSK_CHHM_Pos (1U) -#define HCINTMSK_CHHM_Msk (0x1UL << HCINTMSK_CHHM_Pos) /*!< 0x00000002 */ -#define HCINTMSK_CHHM HCINTMSK_CHHM_Msk /*!< Channel halted mask */ +#define HCINTMSK_CHHM_Msk (0x1UL << HCINTMSK_CHHM_Pos) /*!< 0x00000002 */ +#define HCINTMSK_CHHM HCINTMSK_CHHM_Msk /*!< Channel halted mask */ #define HCINTMSK_AHBERR_Pos (2U) -#define HCINTMSK_AHBERR_Msk (0x1UL << HCINTMSK_AHBERR_Pos) /*!< 0x00000004 */ -#define HCINTMSK_AHBERR HCINTMSK_AHBERR_Msk /*!< AHB error */ +#define HCINTMSK_AHBERR_Msk (0x1UL << HCINTMSK_AHBERR_Pos) /*!< 0x00000004 */ +#define HCINTMSK_AHBERR HCINTMSK_AHBERR_Msk /*!< AHB error */ #define HCINTMSK_STALLM_Pos (3U) -#define HCINTMSK_STALLM_Msk (0x1UL << HCINTMSK_STALLM_Pos) /*!< 0x00000008 */ -#define HCINTMSK_STALLM HCINTMSK_STALLM_Msk /*!< STALL response received interrupt mask */ +#define HCINTMSK_STALLM_Msk (0x1UL << HCINTMSK_STALLM_Pos) /*!< 0x00000008 */ +#define HCINTMSK_STALLM HCINTMSK_STALLM_Msk /*!< STALL response received interrupt mask */ #define HCINTMSK_NAKM_Pos (4U) -#define HCINTMSK_NAKM_Msk (0x1UL << HCINTMSK_NAKM_Pos) /*!< 0x00000010 */ -#define HCINTMSK_NAKM HCINTMSK_NAKM_Msk /*!< NAK response received interrupt mask */ +#define HCINTMSK_NAKM_Msk (0x1UL << HCINTMSK_NAKM_Pos) /*!< 0x00000010 */ +#define HCINTMSK_NAKM HCINTMSK_NAKM_Msk /*!< NAK response received interrupt mask */ #define HCINTMSK_ACKM_Pos (5U) -#define HCINTMSK_ACKM_Msk (0x1UL << HCINTMSK_ACKM_Pos) /*!< 0x00000020 */ -#define HCINTMSK_ACKM HCINTMSK_ACKM_Msk /*!< ACK response received/transmitted interrupt mask */ +#define HCINTMSK_ACKM_Msk (0x1UL << HCINTMSK_ACKM_Pos) /*!< 0x00000020 */ +#define HCINTMSK_ACKM HCINTMSK_ACKM_Msk /*!< ACK response received/transmitted interrupt mask */ #define HCINTMSK_NYET_Pos (6U) -#define HCINTMSK_NYET_Msk (0x1UL << HCINTMSK_NYET_Pos) /*!< 0x00000040 */ -#define HCINTMSK_NYET HCINTMSK_NYET_Msk /*!< response received interrupt mask */ +#define HCINTMSK_NYET_Msk (0x1UL << HCINTMSK_NYET_Pos) /*!< 0x00000040 */ +#define HCINTMSK_NYET HCINTMSK_NYET_Msk /*!< response received interrupt mask */ #define HCINTMSK_TXERRM_Pos (7U) -#define HCINTMSK_TXERRM_Msk (0x1UL << HCINTMSK_TXERRM_Pos) /*!< 0x00000080 */ -#define HCINTMSK_TXERRM HCINTMSK_TXERRM_Msk /*!< Transaction error mask */ +#define HCINTMSK_TXERRM_Msk (0x1UL << HCINTMSK_TXERRM_Pos) /*!< 0x00000080 */ +#define HCINTMSK_TXERRM HCINTMSK_TXERRM_Msk /*!< Transaction error mask */ #define HCINTMSK_BBERRM_Pos (8U) -#define HCINTMSK_BBERRM_Msk (0x1UL << HCINTMSK_BBERRM_Pos) /*!< 0x00000100 */ -#define HCINTMSK_BBERRM HCINTMSK_BBERRM_Msk /*!< Babble error mask */ +#define HCINTMSK_BBERRM_Msk (0x1UL << HCINTMSK_BBERRM_Pos) /*!< 0x00000100 */ +#define HCINTMSK_BBERRM HCINTMSK_BBERRM_Msk /*!< Babble error mask */ #define HCINTMSK_FRMORM_Pos (9U) -#define HCINTMSK_FRMORM_Msk (0x1UL << HCINTMSK_FRMORM_Pos) /*!< 0x00000200 */ -#define HCINTMSK_FRMORM HCINTMSK_FRMORM_Msk /*!< Frame overrun mask */ +#define HCINTMSK_FRMORM_Msk (0x1UL << HCINTMSK_FRMORM_Pos) /*!< 0x00000200 */ +#define HCINTMSK_FRMORM HCINTMSK_FRMORM_Msk /*!< Frame overrun mask */ #define HCINTMSK_DTERRM_Pos (10U) -#define HCINTMSK_DTERRM_Msk (0x1UL << HCINTMSK_DTERRM_Pos) /*!< 0x00000400 */ -#define HCINTMSK_DTERRM HCINTMSK_DTERRM_Msk /*!< Data toggle error mask */ +#define HCINTMSK_DTERRM_Msk (0x1UL << HCINTMSK_DTERRM_Pos) /*!< 0x00000400 */ +#define HCINTMSK_DTERRM HCINTMSK_DTERRM_Msk /*!< Data toggle error mask */ /******************** Bit definition for DIEPTSIZ register ********************/ #define DIEPTSIZ_XFRSIZ_Pos (0U) -#define DIEPTSIZ_XFRSIZ_Msk (0x7FFFFUL << DIEPTSIZ_XFRSIZ_Pos) /*!< 0x0007FFFF */ -#define DIEPTSIZ_XFRSIZ DIEPTSIZ_XFRSIZ_Msk /*!< Transfer size */ +#define DIEPTSIZ_XFRSIZ_Msk (0x7FFFFUL << DIEPTSIZ_XFRSIZ_Pos) /*!< 0x0007FFFF */ +#define DIEPTSIZ_XFRSIZ DIEPTSIZ_XFRSIZ_Msk /*!< Transfer size */ #define DIEPTSIZ_PKTCNT_Pos (19U) -#define DIEPTSIZ_PKTCNT_Msk (0x3FFUL << DIEPTSIZ_PKTCNT_Pos) /*!< 0x1FF80000 */ -#define DIEPTSIZ_PKTCNT DIEPTSIZ_PKTCNT_Msk /*!< Packet count */ +#define DIEPTSIZ_PKTCNT_Msk (0x3FFUL << DIEPTSIZ_PKTCNT_Pos) /*!< 0x1FF80000 */ +#define DIEPTSIZ_PKTCNT DIEPTSIZ_PKTCNT_Msk /*!< Packet count */ #define DIEPTSIZ_MULCNT_Pos (29U) -#define DIEPTSIZ_MULCNT_Msk (0x3UL << DIEPTSIZ_MULCNT_Pos) /*!< 0x60000000 */ -#define DIEPTSIZ_MULCNT DIEPTSIZ_MULCNT_Msk /*!< Packet count */ -/******************** Bit definition for HCTSIZ register ********************/ +#define DIEPTSIZ_MULCNT_Msk (0x3UL << DIEPTSIZ_MULCNT_Pos) /*!< 0x60000000 */ +#define DIEPTSIZ_MULCNT DIEPTSIZ_MULCNT_Msk /*!< Packet count */ + /******************** Bit definition for HCTSIZ register ********************/ #define HCTSIZ_XFRSIZ_Pos (0U) -#define HCTSIZ_XFRSIZ_Msk (0x7FFFFUL << HCTSIZ_XFRSIZ_Pos) /*!< 0x0007FFFF */ -#define HCTSIZ_XFRSIZ HCTSIZ_XFRSIZ_Msk /*!< Transfer size */ +#define HCTSIZ_XFRSIZ_Msk (0x7FFFFUL << HCTSIZ_XFRSIZ_Pos) /*!< 0x0007FFFF */ +#define HCTSIZ_XFRSIZ HCTSIZ_XFRSIZ_Msk /*!< Transfer size */ #define HCTSIZ_PKTCNT_Pos (19U) -#define HCTSIZ_PKTCNT_Msk (0x3FFUL << HCTSIZ_PKTCNT_Pos) /*!< 0x1FF80000 */ -#define HCTSIZ_PKTCNT HCTSIZ_PKTCNT_Msk /*!< Packet count */ +#define HCTSIZ_PKTCNT_Msk (0x3FFUL << HCTSIZ_PKTCNT_Pos) /*!< 0x1FF80000 */ +#define HCTSIZ_PKTCNT HCTSIZ_PKTCNT_Msk /*!< Packet count */ #define HCTSIZ_DOPING_Pos (31U) -#define HCTSIZ_DOPING_Msk (0x1UL << HCTSIZ_DOPING_Pos) /*!< 0x80000000 */ -#define HCTSIZ_DOPING HCTSIZ_DOPING_Msk /*!< Do PING */ +#define HCTSIZ_DOPING_Msk (0x1UL << HCTSIZ_DOPING_Pos) /*!< 0x80000000 */ +#define HCTSIZ_DOPING HCTSIZ_DOPING_Msk /*!< Do PING */ #define HCTSIZ_DPID_Pos (29U) -#define HCTSIZ_DPID_Msk (0x3UL << HCTSIZ_DPID_Pos) /*!< 0x60000000 */ -#define HCTSIZ_DPID HCTSIZ_DPID_Msk /*!< Data PID */ -#define HCTSIZ_DPID_0 (0x1UL << HCTSIZ_DPID_Pos) /*!< 0x20000000 */ -#define HCTSIZ_DPID_1 (0x2UL << HCTSIZ_DPID_Pos) /*!< 0x40000000 */ +#define HCTSIZ_DPID_Msk (0x3UL << HCTSIZ_DPID_Pos) /*!< 0x60000000 */ +#define HCTSIZ_DPID HCTSIZ_DPID_Msk /*!< Data PID */ +#define HCTSIZ_DPID_0 (0x1UL << HCTSIZ_DPID_Pos) /*!< 0x20000000 */ +#define HCTSIZ_DPID_1 (0x2UL << HCTSIZ_DPID_Pos) /*!< 0x40000000 */ /******************** Bit definition for DIEPDMA register ********************/ #define DIEPDMA_DMAADDR_Pos (0U) -#define DIEPDMA_DMAADDR_Msk (0xFFFFFFFFUL << DIEPDMA_DMAADDR_Pos) /*!< 0xFFFFFFFF */ -#define DIEPDMA_DMAADDR DIEPDMA_DMAADDR_Msk /*!< DMA address */ +#define DIEPDMA_DMAADDR_Msk (0xFFFFFFFFUL << DIEPDMA_DMAADDR_Pos) /*!< 0xFFFFFFFF */ +#define DIEPDMA_DMAADDR DIEPDMA_DMAADDR_Msk /*!< DMA address */ /******************** Bit definition for HCDMA register ********************/ #define HCDMA_DMAADDR_Pos (0U) -#define HCDMA_DMAADDR_Msk (0xFFFFFFFFUL << HCDMA_DMAADDR_Pos) /*!< 0xFFFFFFFF */ -#define HCDMA_DMAADDR HCDMA_DMAADDR_Msk /*!< DMA address */ +#define HCDMA_DMAADDR_Msk (0xFFFFFFFFUL << HCDMA_DMAADDR_Pos) /*!< 0xFFFFFFFF */ +#define HCDMA_DMAADDR HCDMA_DMAADDR_Msk /*!< DMA address */ -/******************** Bit definition for DTXFSTS register ********************/ + /******************** Bit definition for DTXFSTS register ********************/ #define DTXFSTS_INEPTFSAV_Pos (0U) -#define DTXFSTS_INEPTFSAV_Msk (0xFFFFUL << DTXFSTS_INEPTFSAV_Pos) /*!< 0x0000FFFF */ -#define DTXFSTS_INEPTFSAV DTXFSTS_INEPTFSAV_Msk /*!< IN endpoint TxFIFO space available */ +#define DTXFSTS_INEPTFSAV_Msk (0xFFFFUL << DTXFSTS_INEPTFSAV_Pos) /*!< 0x0000FFFF */ +#define DTXFSTS_INEPTFSAV DTXFSTS_INEPTFSAV_Msk /*!< IN endpoint TxFIFO space available */ -/******************** Bit definition for DIEPTXF register ********************/ + /******************** Bit definition for DIEPTXF register ********************/ #define DIEPTXF_INEPTXSA_Pos (0U) -#define DIEPTXF_INEPTXSA_Msk (0xFFFFUL << DIEPTXF_INEPTXSA_Pos) /*!< 0x0000FFFF */ -#define DIEPTXF_INEPTXSA DIEPTXF_INEPTXSA_Msk /*!< IN endpoint FIFOx transmit RAM start address */ +#define DIEPTXF_INEPTXSA_Msk (0xFFFFUL << DIEPTXF_INEPTXSA_Pos) /*!< 0x0000FFFF */ +#define DIEPTXF_INEPTXSA DIEPTXF_INEPTXSA_Msk /*!< IN endpoint FIFOx transmit RAM start address */ #define DIEPTXF_INEPTXFD_Pos (16U) -#define DIEPTXF_INEPTXFD_Msk (0xFFFFUL << DIEPTXF_INEPTXFD_Pos) /*!< 0xFFFF0000 */ -#define DIEPTXF_INEPTXFD DIEPTXF_INEPTXFD_Msk /*!< IN endpoint TxFIFO depth */ +#define DIEPTXF_INEPTXFD_Msk (0xFFFFUL << DIEPTXF_INEPTXFD_Pos) /*!< 0xFFFF0000 */ +#define DIEPTXF_INEPTXFD DIEPTXF_INEPTXFD_Msk /*!< IN endpoint TxFIFO depth */ /******************** Bit definition for DOEPCTL register ********************/ #define DOEPCTL_MPSIZ_Pos (0U) -#define DOEPCTL_MPSIZ_Msk (0x7FFUL << DOEPCTL_MPSIZ_Pos) /*!< 0x000007FF */ -#define DOEPCTL_MPSIZ DOEPCTL_MPSIZ_Msk /*!< Maximum packet size */ /*! Date: Tue, 26 Oct 2021 00:55:24 +0700 Subject: [PATCH 20/51] update dwc2_type --- src/portable/synopsys/dwc2/dcd_dwc2.c | 175 +- src/portable/synopsys/dwc2/dwc2_stm32.h | 6 +- src/portable/synopsys/dwc2/dwc2_type.h | 2030 ++++++++++++----------- 3 files changed, 1119 insertions(+), 1092 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 7ae10652c..b98bd0055 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -30,6 +30,7 @@ #include "tusb_option.h" #include "device/dcd_attr.h" + #if TUSB_OPT_DEVICE_ENABLED && \ ( defined(DCD_ATTR_DWC2_STM32) || TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3, OPT_MCU_GD32VF103) ) @@ -51,7 +52,7 @@ //--------------------------------------------------------------------+ #define CORE_REG(_port) ((dwc2_core_t*) DWC2_REG_BASE) -#define DEVICE_REG(_port) ((dwc2_device_t*) (DWC2_REG_BASE + DWC2_DEVICE_BASE)) +#define DEVICE_REG(_port) CORE_REG(_port) //((dwc2_core_t*) (DWC2_REG_BASE + DWC2_DEVICE_BASE)) #define EPIN_REG(_port) ((dwc2_epin_t*) (DWC2_REG_BASE + DWC2_IN_ENDPOINT_BASE)) #define EPOUT_REG(_port) ((dwc2_epout_t*) (DWC2_REG_BASE + DWC2_OUT_ENDPOINT_BASE)) #define FIFO_BASE(_port, _x) ((volatile uint32_t*) (DWC2_REG_BASE + DWC2_FIFO_BASE + (_x) * DWC2_FIFO_SIZE)) @@ -63,6 +64,10 @@ enum DCD_FULL_SPEED = 3, // Full speed with internal PHY }; +// PHYSEL, ULPISEL +// UTMI internal HS PHY +// ULPI external HS PHY + static TU_ATTR_ALIGNED(4) uint32_t _setup_packet[2]; typedef struct { @@ -103,7 +108,7 @@ static void update_grxfsiz(uint8_t rhport) } // Update size of RX FIFO - core->GRXFSIZ = calc_rx_ff_size(max_epsize); + core->grxfsiz = calc_rx_ff_size(max_epsize); } // Setup the control endpoint 0. @@ -112,7 +117,7 @@ static void bus_reset(uint8_t rhport) (void) rhport; dwc2_core_t * core = CORE_REG(rhport); - dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_core_t * dev = DEVICE_REG(rhport); dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); @@ -120,7 +125,7 @@ static void bus_reset(uint8_t rhport) _out_ep_closed = false; // clear device address - dev->DCFG &= ~DCFG_DAD_Msk; + dev->dcfg &= ~DCFG_DAD_Msk; // 1. NAK for all OUT endpoints for(uint8_t n = 0; n < DWC2_EP_MAX; n++) { @@ -128,9 +133,9 @@ static void bus_reset(uint8_t rhport) } // 2. Un-mask interrupt bits - dev->DAINTMSK = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); - dev->DOEPMSK = DOEPMSK_STUPM | DOEPMSK_XFRCM; - dev->DIEPMSK = DIEPMSK_TOM | DIEPMSK_XFRCM; + dev->daintmsk = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); + dev->doepmsk = DOEPMSK_STUPM | DOEPMSK_XFRCM; + dev->diepmsk = DIEPMSK_TOM | DIEPMSK_XFRCM; // "USB Data FIFOs" section in reference manual // Peripheral FIFO architecture @@ -182,12 +187,12 @@ static void bus_reset(uint8_t rhport) // are enabled at least "2 x (Largest-EPsize/4) + 1" are recommended. Maybe provide a macro for application to // overwrite this. - core->GRXFSIZ = calc_rx_ff_size(TUD_OPT_HIGH_SPEED ? 512 : 64); + core->grxfsiz = calc_rx_ff_size(TUD_OPT_HIGH_SPEED ? 512 : 64); _allocated_fifo_words_tx = 16; // Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) - core->DIEPTXF0_HNPTXFSIZ = (16 << TX0FD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + core->dieptxf0 = (16 << TX0FD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); // Fixed control EP0 size to 64 bytes in_ep[0].DIEPCTL &= ~(0x03 << DIEPCTL_MPSIZ_Pos); @@ -195,15 +200,15 @@ static void bus_reset(uint8_t rhport) out_ep[0].DOEPTSIZ |= (3 << DOEPTSIZ_STUPCNT_Pos); - core->GINTMSK |= GINTMSK_OEPINT | GINTMSK_IEPINT; + core->gintmsk |= GINTMSK_OEPINT | GINTMSK_IEPINT; } static tusb_speed_t get_speed(uint8_t rhport) { (void) rhport; - dwc2_device_t * dev = DEVICE_REG(rhport); - uint32_t const enum_spd = (dev->DSTS & DSTS_ENUMSPD_Msk) >> DSTS_ENUMSPD_Pos; + dwc2_core_t * dev = DEVICE_REG(rhport); + uint32_t const enum_spd = (dev->dsts & DSTS_ENUMSPD_Msk) >> DSTS_ENUMSPD_Pos; return (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL; } @@ -220,11 +225,11 @@ static void set_speed(uint8_t rhport, tusb_speed_t speed) bitvalue = DCD_FULL_SPEED; } - dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_core_t * dev = DEVICE_REG(rhport); // Clear and set speed bits - dev->DCFG &= ~(3 << DCFG_DSPD_Pos); - dev->DCFG |= (bitvalue << DCFG_DSPD_Pos); + dev->dcfg &= ~(3 << DCFG_DSPD_Pos); + dev->dcfg |= (bitvalue << DCFG_DSPD_Pos); } #if defined(USB_HS_PHYC) @@ -272,7 +277,7 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c { (void) rhport; - dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_core_t * dev = DEVICE_REG(rhport); dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); @@ -296,12 +301,12 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c if ((in_ep[epnum].DIEPCTL & DIEPCTL_EPTYP) == DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) { // Take odd/even bit from frame counter. - uint32_t const odd_frame_now = (dev->DSTS & (1u << DSTS_FNSOF_Pos)); + uint32_t const odd_frame_now = (dev->dsts & (1u << DSTS_FNSOF_Pos)); in_ep[epnum].DIEPCTL |= (odd_frame_now ? DIEPCTL_SD0PID_SEVNFRM_Msk : DIEPCTL_SODDFRM_Msk); } // Enable fifo empty interrupt only if there are something to put in the fifo. if(total_bytes != 0) { - dev->DIEPEMPMSK |= (1 << epnum); + dev->diepempmsk |= (1 << epnum); } } else { // A full OUT transfer (multiple packets, possibly) triggers XFRC. @@ -313,7 +318,7 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c if ((out_ep[epnum].DOEPCTL & DOEPCTL_EPTYP) == DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) { // Take odd/even bit from frame counter. - uint32_t const odd_frame_now = (dev->DSTS & (1u << DSTS_FNSOF_Pos)); + uint32_t const odd_frame_now = (dev->dsts & (1u << DSTS_FNSOF_Pos)); out_ep[epnum].DOEPCTL |= (odd_frame_now ? DOEPCTL_SD0PID_SEVNFRM_Msk : DOEPCTL_SODDFRM_Msk); } } @@ -336,23 +341,23 @@ void dcd_init (uint8_t rhport) // On selected MCUs HS port1 can be used with external PHY via ULPI interface #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED // deactivate internal PHY - core->GCCFG &= ~GCCFG_PWRDWN; + core->gccfg &= ~GCCFG_PWRDWN; // Init The UTMI Interface - core->GUSBCFG &= ~(GUSBCFG_TSDPS | GUSBCFG_ULPIFSLS | GUSBCFG_PHYSEL); + core->gusbcfg &= ~(GUSBCFG_TSDPS | GUSBCFG_ULPIFSLS | GUSBCFG_PHYSEL); // Select default internal VBUS Indicator and Drive for ULPI - core->GUSBCFG &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI); + core->gusbcfg &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI); #else - core->GUSBCFG |= GUSBCFG_PHYSEL; + core->gusbcfg |= GUSBCFG_PHYSEL; #endif #if defined(USB_HS_PHYC) // Highspeed with embedded UTMI PHYC // Select UTMI Interface - core->GUSBCFG &= ~GUSBCFG_ULPI_UTMI_SEL; - core->GCCFG |= GCCFG_PHYHSEN; + core->gusbcfg &= ~GUSBCFG_ULPI_UTMI_SEL; + core->gccfg |= GCCFG_PHYHSEN; // Enables control of a High Speed USB PHY USB_HS_PHYCInit(); @@ -360,42 +365,42 @@ void dcd_init (uint8_t rhport) } else { // Enable internal PHY - core->GUSBCFG |= GUSBCFG_PHYSEL; + core->gusbcfg |= GUSBCFG_PHYSEL; } // Reset core after selecting PHYst // Wait AHB IDLE, reset then wait until it is cleared - while ((core->GRSTCTL & GRSTCTL_AHBIDL) == 0U) {} - core->GRSTCTL |= GRSTCTL_CSRST; - while ((core->GRSTCTL & GRSTCTL_CSRST) == GRSTCTL_CSRST) {} + while ((core->grstctl & GRSTCTL_AHBIDL) == 0U) {} + core->grstctl |= GRSTCTL_CSRST; + while ((core->grstctl & GRSTCTL_CSRST) == GRSTCTL_CSRST) {} // Restart PHY clock *((volatile uint32_t *)(DWC2_REG_BASE + DWC2_PCGCCTL_BASE)) = 0; // Clear all interrupts - core->GINTSTS |= core->GINTSTS; + core->gintsts |= core->gintsts; // Required as part of core initialization. // TODO: How should mode mismatch be handled? It will cause // the core to stop working/require reset. - core->GINTMSK |= GINTMSK_OTGINT | GINTMSK_MMISM; + core->gintmsk |= GINTMSK_OTGINT | GINTMSK_MMISM; - dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_core_t * dev = DEVICE_REG(rhport); // If USB host misbehaves during status portion of control xfer // (non zero-length packet), send STALL back and discard. - dev->DCFG |= DCFG_NZLSOHSK; + dev->dcfg |= DCFG_NZLSOHSK; set_speed(rhport, TUD_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL); // Enable internal USB transceiver, unless using HS core (port 1) with external PHY. - if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) core->GCCFG |= GCCFG_PWRDWN; + if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) core->gccfg |= GCCFG_PWRDWN; - core->GINTMSK |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_USBSUSPM | + core->gintmsk |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_USBSUSPM | GINTMSK_WUIM | GINTMSK_RXFLVLM; // Enable global interrupt - core->GAHBCFG |= GAHBCFG_GINT; + core->gahbcfg |= GAHBCFG_GINT; dcd_connect(rhport); } @@ -412,8 +417,8 @@ void dcd_int_disable (uint8_t rhport) void dcd_set_address (uint8_t rhport, uint8_t dev_addr) { - dwc2_device_t * dev = DEVICE_REG(rhport); - dev->DCFG = (dev->DCFG & ~DCFG_DAD_Msk) | (dev_addr << DCFG_DAD_Pos); + dwc2_core_t * dev = DEVICE_REG(rhport); + dev->dcfg = (dev->dcfg & ~DCFG_DAD_Msk) | (dev_addr << DCFG_DAD_Pos); // Response with status after changing device address dcd_edpt_xfer(rhport, tu_edpt_addr(0, TUSB_DIR_IN), NULL, 0); @@ -424,33 +429,33 @@ void dcd_remote_wakeup(uint8_t rhport) (void) rhport; dwc2_core_t * core = CORE_REG(rhport); - dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_core_t * dev = DEVICE_REG(rhport); // set remote wakeup - dev->DCTL |= DCTL_RWUSIG; + dev->dctl |= DCTL_RWUSIG; // enable SOF to detect bus resume - core->GINTSTS = GINTSTS_SOF; - core->GINTMSK |= GINTMSK_SOFM; + core->gintsts = GINTSTS_SOF; + core->gintmsk |= GINTMSK_SOFM; // Per specs: remote wakeup signal bit must be clear within 1-15ms dwc2_remote_wakeup_delay(); - dev->DCTL &= ~DCTL_RWUSIG; + dev->dctl &= ~DCTL_RWUSIG; } void dcd_connect(uint8_t rhport) { (void) rhport; - dwc2_device_t * dev = DEVICE_REG(rhport); - dev->DCTL &= ~DCTL_SDIS; + dwc2_core_t * dev = DEVICE_REG(rhport); + dev->dctl &= ~DCTL_SDIS; } void dcd_disconnect(uint8_t rhport) { (void) rhport; - dwc2_device_t * dev = DEVICE_REG(rhport); - dev->DCTL |= DCTL_SDIS; + dwc2_core_t * dev = DEVICE_REG(rhport); + dev->dctl |= DCTL_SDIS; } @@ -463,7 +468,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) (void) rhport; dwc2_core_t * core = CORE_REG(rhport); - dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_core_t * dev = DEVICE_REG(rhport); dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); @@ -484,12 +489,12 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) uint16_t const sz = calc_rx_ff_size(4*fifo_size); // If size_rx needs to be extended check if possible and if so enlarge it - if (core->GRXFSIZ < sz) + if (core->grxfsiz < sz) { TU_ASSERT(sz + _allocated_fifo_words_tx <= DWC2_EP_FIFO_SIZE/4); // Enlarge RX FIFO - core->GRXFSIZ = sz; + core->grxfsiz = sz; } out_ep[epnum].DOEPCTL |= (1 << DOEPCTL_USBAEP_Pos) | @@ -497,7 +502,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DOEPCTL_SD0PID_SEVNFRM : 0) | (xfer->max_size << DOEPCTL_MPSIZ_Pos); - dev->DAINTMSK |= (1 << (DAINTMSK_OEPM_Pos + epnum)); + dev->daintmsk |= (1 << (DAINTMSK_OEPM_Pos + epnum)); } else { @@ -523,7 +528,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // - IN EP 1 gets FIFO 1, IN EP "n" gets FIFO "n". // Check if free space is available - TU_ASSERT(_allocated_fifo_words_tx + fifo_size + core->GRXFSIZ <= DWC2_EP_FIFO_SIZE/4); + TU_ASSERT(_allocated_fifo_words_tx + fifo_size + core->grxfsiz <= DWC2_EP_FIFO_SIZE/4); _allocated_fifo_words_tx += fifo_size; @@ -531,7 +536,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // DIEPTXF starts at FIFO #1. // Both TXFD and TXSA are in unit of 32-bit words. - core->DIEPTXF[epnum - 1] = (fifo_size << DIEPTXF_INEPTXFD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + core->dieptxf[epnum - 1] = (fifo_size << DIEPTXF_INEPTXFD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); in_ep[epnum].DIEPCTL |= (1 << DIEPCTL_USBAEP_Pos) | (epnum << DIEPCTL_TXFNUM_Pos) | @@ -539,7 +544,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DIEPCTL_SD0PID_SEVNFRM : 0) | (xfer->max_size << DIEPCTL_MPSIZ_Pos); - dev->DAINTMSK |= (1 << (DAINTMSK_IEPM_Pos + epnum)); + dev->daintmsk |= (1 << (DAINTMSK_IEPM_Pos + epnum)); } return true; @@ -551,12 +556,12 @@ void dcd_edpt_close_all (uint8_t rhport) (void) rhport; // dwc2_core_t * core = CORE_REG(rhport); - dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_core_t * dev = DEVICE_REG(rhport); dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); // Disable non-control interrupt - dev->DAINTMSK = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); + dev->daintmsk = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); for(uint8_t n = 1; n < DWC2_EP_MAX; n++) { @@ -638,7 +643,7 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) (void) rhport; dwc2_core_t * core = CORE_REG(rhport); - dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_core_t * dev = DEVICE_REG(rhport); dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); @@ -666,9 +671,9 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) } // Flush the FIFO, and wait until we have confirmed it cleared. - core->GRSTCTL |= (epnum << GRSTCTL_TXFNUM_Pos); - core->GRSTCTL |= GRSTCTL_TXFFLSH; - while ( (core->GRSTCTL & GRSTCTL_TXFFLSH_Msk) != 0 ) {} + core->grstctl |= (epnum << GRSTCTL_TXFNUM_Pos); + core->grstctl |= GRSTCTL_TXFFLSH; + while ( (core->grstctl & GRSTCTL_TXFFLSH_Msk) != 0 ) {} } else { @@ -683,8 +688,8 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) // Simpler to use polling here, we don't use the "B"OUTNAKEFF interrupt // anyway, and it can't be cleared by user code. If this while loop never // finishes, we have bigger problems than just the stack. - dev->DCTL |= DCTL_SGONAK; - while ( (core->GINTSTS & GINTSTS_BOUTNAKEFF_Msk) == 0 ) {} + dev->dctl |= DCTL_SGONAK; + while ( (core->gintsts & GINTSTS_BOUTNAKEFF_Msk) == 0 ) {} // Ditto here- disable the endpoint. out_ep[epnum].DOEPCTL |= DOEPCTL_EPDIS | (stall ? DOEPCTL_STALL : 0); @@ -693,7 +698,7 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) out_ep[epnum].DOEPINT = DOEPINT_EPDISD; // Allow other OUT endpoints to keep receiving. - dev->DCTL |= DCTL_CGONAK; + dev->dctl |= DCTL_CGONAK; } } } @@ -715,8 +720,8 @@ void dcd_edpt_close (uint8_t rhport, uint8_t ep_addr) if (dir == TUSB_DIR_IN) { - uint16_t const fifo_size = (core->DIEPTXF[epnum - 1] & DIEPTXF_INEPTXFD_Msk) >> DIEPTXF_INEPTXFD_Pos; - uint16_t const fifo_start = (core->DIEPTXF[epnum - 1] & DIEPTXF_INEPTXSA_Msk) >> DIEPTXF_INEPTXSA_Pos; + uint16_t const fifo_size = (core->dieptxf[epnum - 1] & DIEPTXF_INEPTXFD_Msk) >> DIEPTXF_INEPTXFD_Pos; + uint16_t const fifo_start = (core->dieptxf[epnum - 1] & DIEPTXF_INEPTXSA_Msk) >> DIEPTXF_INEPTXSA_Pos; // For now only the last opened endpoint can be closed without fuss. TU_ASSERT(fifo_start == DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx,); _allocated_fifo_words_tx -= fifo_size; @@ -831,7 +836,7 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { volatile uint32_t * rx_fifo = FIFO_BASE(rhport, 0); // Pop control word off FIFO - uint32_t ctl_word = core->GRXSTSP; + uint32_t ctl_word = core->grxstsp; uint8_t pktsts = (ctl_word & GRXSTSP_PKTSTS_Msk) >> GRXSTSP_PKTSTS_Pos; uint8_t epnum = (ctl_word & GRXSTSP_EPNUM_Msk) >> GRXSTSP_EPNUM_Pos; uint16_t bcnt = (ctl_word & GRXSTSP_BCNT_Msk) >> GRXSTSP_BCNT_Pos; @@ -891,7 +896,7 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { } } -static void handle_epout_ints (uint8_t rhport, dwc2_device_t *dev, dwc2_epout_t *out_ep) +static void handle_epout_ints (uint8_t rhport, dwc2_core_t *dev, dwc2_epout_t *out_ep) { // DAINT for a given EP clears when DOEPINTx is cleared. // OEPINT will be cleared when DAINT's out bits are cleared. @@ -899,7 +904,7 @@ static void handle_epout_ints (uint8_t rhport, dwc2_device_t *dev, dwc2_epout_t { xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_OUT); - if ( dev->DAINT & (1 << (DAINT_OEPINT_Pos + n)) ) + if ( dev->daint & (1 << (DAINT_OEPINT_Pos + n)) ) { // SETUP packet Setup Phase done. if ( out_ep[n].DOEPINT & DOEPINT_STUP ) @@ -928,14 +933,14 @@ static void handle_epout_ints (uint8_t rhport, dwc2_device_t *dev, dwc2_epout_t } } -static void handle_epin_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epin_t * in_ep) { +static void handle_epin_ints(uint8_t rhport, dwc2_core_t * dev, dwc2_epin_t * in_ep) { // DAINT for a given EP clears when DIEPINTx is cleared. // IEPINT will be cleared when DAINT's out bits are cleared. for ( uint8_t n = 0; n < DWC2_EP_MAX; n++ ) { xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_IN); - if ( dev->DAINT & (1 << (DAINT_IEPINT_Pos + n)) ) + if ( dev->daint & (1 << (DAINT_IEPINT_Pos + n)) ) { // IN XFER complete (entire xfer). if ( in_ep[n].DIEPINT & DIEPINT_XFRC ) @@ -952,7 +957,7 @@ static void handle_epin_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epin_t * } // XFER FIFO empty - if ( (in_ep[n].DIEPINT & DIEPINT_TXFE) && (dev->DIEPEMPMSK & (1 << n)) ) + if ( (in_ep[n].DIEPINT & DIEPINT_TXFE) && (dev->diepempmsk & (1 << n)) ) { // DIEPINT's TXFE bit is read-only, software cannot clear it. // It will only be cleared by hardware when written bytes is more than @@ -991,7 +996,7 @@ static void handle_epin_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epin_t * // Turn off TXFE if all bytes are written. if (((in_ep[n].DIEPTSIZ & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos) == 0) { - dev->DIEPEMPMSK &= ~(1 << n); + dev->diepempmsk &= ~(1 << n); } } } @@ -1001,16 +1006,16 @@ static void handle_epin_ints(uint8_t rhport, dwc2_device_t * dev, dwc2_epin_t * void dcd_int_handler(uint8_t rhport) { dwc2_core_t * core = CORE_REG(rhport); - dwc2_device_t * dev = DEVICE_REG(rhport); + dwc2_core_t * dev = DEVICE_REG(rhport); dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); - uint32_t const int_status = core->GINTSTS & core->GINTMSK; + uint32_t const int_status = core->gintsts & core->gintmsk; if(int_status & GINTSTS_USBRST) { // USBRST is start of reset. - core->GINTSTS = GINTSTS_USBRST; + core->gintsts = GINTSTS_USBRST; bus_reset(rhport); } @@ -1018,7 +1023,7 @@ void dcd_int_handler(uint8_t rhport) { // ENUMDNE is the end of reset where speed of the link is detected - core->GINTSTS = GINTSTS_ENUMDNE; + core->gintsts = GINTSTS_ENUMDNE; tusb_speed_t const speed = get_speed(rhport); @@ -1028,13 +1033,13 @@ void dcd_int_handler(uint8_t rhport) if(int_status & GINTSTS_USBSUSP) { - core->GINTSTS = GINTSTS_USBSUSP; + core->gintsts = GINTSTS_USBSUSP; dcd_event_bus_signal(rhport, DCD_EVENT_SUSPEND, true); } if(int_status & GINTSTS_WKUINT) { - core->GINTSTS = GINTSTS_WKUINT; + core->gintsts = GINTSTS_WKUINT; dcd_event_bus_signal(rhport, DCD_EVENT_RESUME, true); } @@ -1044,22 +1049,22 @@ void dcd_int_handler(uint8_t rhport) if(int_status & GINTSTS_OTGINT) { // OTG INT bit is read-only - uint32_t const otg_int = core->GOTGINT; + uint32_t const otg_int = core->gotgint; if (otg_int & GOTGINT_SEDET) { dcd_event_bus_signal(rhport, DCD_EVENT_UNPLUGGED, true); } - core->GOTGINT = otg_int; + core->gotgint = otg_int; } if(int_status & GINTSTS_SOF) { - core->GINTSTS = GINTSTS_SOF; + core->gotgint = GINTSTS_SOF; // Disable SOF interrupt since currently only used for remote wakeup detection - core->GINTMSK &= ~GINTMSK_SOFM; + core->gintmsk &= ~GINTMSK_SOFM; dcd_event_bus_signal(rhport, DCD_EVENT_SOF, true); } @@ -1070,13 +1075,13 @@ void dcd_int_handler(uint8_t rhport) // RXFLVL bit is read-only // Mask out RXFLVL while reading data from FIFO - core->GINTMSK &= ~GINTMSK_RXFLVLM; + core->gintmsk &= ~GINTMSK_RXFLVLM; // Loop until all available packets were handled do { handle_rxflvl_ints(rhport, out_ep); - } while(core->GINTSTS & GINTSTS_RXFLVL); + } while(core->gotgint & GINTSTS_RXFLVL); // Manage RX FIFO size if (_out_ep_closed) @@ -1087,7 +1092,7 @@ void dcd_int_handler(uint8_t rhport) _out_ep_closed = false; } - core->GINTMSK |= GINTMSK_RXFLVLM; + core->gintmsk |= GINTMSK_RXFLVLM; } // OUT endpoint interrupt handling. diff --git a/src/portable/synopsys/dwc2/dwc2_stm32.h b/src/portable/synopsys/dwc2/dwc2_stm32.h index 2a6d58e9a..d2ad8abb7 100644 --- a/src/portable/synopsys/dwc2/dwc2_stm32.h +++ b/src/portable/synopsys/dwc2/dwc2_stm32.h @@ -115,12 +115,12 @@ static inline void dwc2_remote_wakeup_delay(void) // Set turn-around timeout according to link speed static inline void dwc2_set_turnaround(dwc2_core_t * core, tusb_speed_t speed) { - core->GUSBCFG &= ~GUSBCFG_TRDT; + core->gusbcfg &= ~GUSBCFG_TRDT; if ( speed == TUSB_SPEED_HIGH ) { // Use fixed 0x09 for Highspeed - core->GUSBCFG |= (0x09 << GUSBCFG_TRDT_Pos); + core->gusbcfg |= (0x09 << GUSBCFG_TRDT_Pos); } else { @@ -149,7 +149,7 @@ static inline void dwc2_set_turnaround(dwc2_core_t * core, tusb_speed_t speed) turnaround = 0xFU; // Fullspeed depends on MCU clocks, but we will use 0x06 for 32+ Mhz - core->GUSBCFG |= (turnaround << GUSBCFG_TRDT_Pos); + core->gusbcfg |= (turnaround << GUSBCFG_TRDT_Pos); } } diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 8d12e21ce..b83ac67f9 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -27,120 +27,142 @@ // HS PHY typedef struct { - volatile uint32_t HS_PHYC_PLL; /*!< This register is used to control the PLL of the HS PHY. 000h */ - volatile uint32_t Reserved04; /*!< Reserved 004h */ - volatile uint32_t Reserved08; /*!< Reserved 008h */ - volatile uint32_t HS_PHYC_TUNE; /*!< This register is used to control the tuning interface of the High Speed PHY. 00Ch */ - volatile uint32_t Reserved10; /*!< Reserved 010h */ - volatile uint32_t Reserved14; /*!< Reserved 014h */ - volatile uint32_t HS_PHYC_LDO; /*!< This register is used to control the regulator (LDO). 018h */ + volatile uint32_t HS_PHYC_PLL; // This register is used to control the PLL of the HS PHY. 000h */ + volatile uint32_t Reserved04; // Reserved 004h */ + volatile uint32_t Reserved08; // Reserved 008h */ + volatile uint32_t HS_PHYC_TUNE; // This register is used to control the tuning interface of the High Speed PHY. 00Ch */ + volatile uint32_t Reserved10; // Reserved 010h */ + volatile uint32_t Reserved14; // Reserved 014h */ + volatile uint32_t HS_PHYC_LDO; // This register is used to control the regulator (LDO). 018h */ } HS_PHYC_GlobalTypeDef; #endif -// Core -typedef struct -{ - volatile uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ - volatile uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ - volatile uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ - volatile uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ - volatile uint32_t GRSTCTL; /*!< Core Reset Register 010h */ - volatile uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ - volatile uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ - volatile uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ - volatile uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ - volatile uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ - volatile uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ - volatile uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ - uint32_t Reserved30[2]; /*!< Reserved 030h */ - volatile uint32_t GCCFG; /*!< General Purpose IO Register 038h */ - volatile uint32_t CID; /*!< User ID Register 03Ch */ - volatile uint32_t GSNPSID; /* USB_OTG core ID 040h*/ - volatile uint32_t GHWCFG1; /* User HW config1 044h*/ - volatile uint32_t GHWCFG2; /* User HW config2 048h*/ - volatile uint32_t GHWCFG3; /*!< User HW config3 04Ch */ - uint32_t Reserved6; /*!< Reserved 050h */ - volatile uint32_t GLPMCFG; /*!< LPM Register 054h */ - volatile uint32_t GPWRDN; /*!< Power Down Register 058h */ - volatile uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ - volatile uint32_t GADPCTL; /*!< ADP Timer, Control and Status Register 60Ch */ - uint32_t Reserved43[39]; /*!< Reserved 058h-0FFh */ - volatile uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ - volatile uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO 104h-13Ch */ -} dwc2_core_t; - -// Host -typedef struct -{ - volatile uint32_t HCFG; /*!< Host Configuration Register 400h */ - volatile uint32_t HFIR; /*!< Host Frame Interval Register 404h */ - volatile uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ - uint32_t Reserved40C; /*!< Reserved 40Ch */ - volatile uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ - volatile uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ - volatile uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ -} dwc2_host_t; - // Host Channel typedef struct { - volatile uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ - volatile uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ - volatile uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ - volatile uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ - volatile uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ - volatile uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ - uint32_t Reserved[2]; /*!< Reserved */ + volatile uint32_t hcchar; // 500 + 20n Host Channel Characteristics Register + volatile uint32_t hcsplt; // 504 + 20n Host Channel Split Control Register + volatile uint32_t hcint; // 508 + 20n Host Channel Interrupt Register + volatile uint32_t hcintmsk; // 50C + 20n Host Channel Interrupt Mask Register + volatile uint32_t hctsiz; // 510 + 20n Host Channel Transfer Size Register + volatile uint32_t hcdma; // 514 + 20n Host Channel DMA Address Register + uint32_t reserved518; // 518 + 20n + volatile uint32_t hcdmab; // 51C + 20n Host Channel DMA Address Register } dwc2_channel_t; -// Device typedef struct { - volatile uint32_t DCFG; /*!< dev Configuration Register 800h */ - volatile uint32_t DCTL; /*!< dev Control Register 804h */ - volatile uint32_t DSTS; /*!< dev Status Register (RO) 808h */ - uint32_t Reserved0C; /*!< Reserved 80Ch */ - volatile uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ - volatile uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ - volatile uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ - volatile uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ - uint32_t Reserved20; /*!< Reserved 820h */ - uint32_t Reserved9; /*!< Reserved 824h */ - volatile uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ - volatile uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ - volatile uint32_t DTHRCTL; /*!< dev threshold 830h */ - volatile uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ - volatile uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ - volatile uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ - uint32_t Reserved40; /*!< dedicated EP mask 840h */ - volatile uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ - uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ - volatile uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ -} dwc2_device_t; + //------------- Core Global -------------// + volatile uint32_t gotgctl; // 000 OTG Control and Status Register + volatile uint32_t gotgint; // 004 OTG Interrupt Register + volatile uint32_t gahbcfg; // 008 AHB Configuration Register + volatile uint32_t gusbcfg; // 00c USB Configuration Register + volatile uint32_t grstctl; // 010 Reset Register + volatile uint32_t gintsts; // 014 Interrupt Register + volatile uint32_t gintmsk; // 018 Interrupt Mask Register + volatile uint32_t grxstsr; // 01c Receive Status Debug Read Register + volatile uint32_t grxstsp; // 020 Receive Status Read/Pop Register + volatile uint32_t grxfsiz; // 024 Receive FIFO Size Register +union { + volatile uint32_t dieptxf0; // 028 EP0 Tx FIFO Size Register + volatile uint32_t gnptxfsiz; // 028 Non-periodic Transmit FIFO Size Register +}; + volatile uint32_t gnptxsts; // 02c Non-periodic Transmit FIFO/Queue Status Register + volatile uint32_t gi2cctl; // 030 I2C Address Register + volatile uint32_t gpvndctl; // 034 PHY Vendor Control Register +union { + volatile uint32_t ggpio; // 038 General Purpose IO Register + volatile uint32_t gccfg; // 038 STM32 General Core Configuration +}; + volatile uint32_t guid; // 03C User ID Register + volatile uint32_t gsnpsid; // 040 Synopsys ID Register + volatile uint32_t ghwcfg1; // 044 User Hardware Configuration 1 Register + volatile uint32_t ghwcfg2; // 048 User Hardware Configuration 2 Register + volatile uint32_t ghwcfg3; // 04C User Hardware Configuration 3 Register + volatile uint32_t ghwcfg4; // 050 User Hardware Configuration 4 Register + volatile uint32_t glpmcfg; // 054 Core LPM Configuration Register + volatile uint32_t gpwrdn; // 058 Power Down Register + volatile uint32_t gdfifocfg; // 05C DFIFO Software Configuration Register + volatile uint32_t gadpctl; // 060 ADP Timer, Control and Status Register + + uint32_t reserved64[39]; // 064..0FF + volatile uint32_t hptxfsiz; // 100 Host Periodic Tx FIFO Size Register + volatile uint32_t dieptxf[15]; // 104..13C Device Periodic Transmit FIFO Size Register + uint32_t reserved140[176]; // 140..3FC + + //------------- Host -------------// + volatile uint32_t hcfg; // 400 Host Configuration Register + volatile uint32_t hfir; // 404 Host Frame Interval Register + volatile uint32_t hfnum; // 408 Host Frame Number / Frame Remaining + uint32_t reserved40c; // 40C + volatile uint32_t hptxsts; // 410 Host Periodic TX FIFO / Queue Status + volatile uint32_t haint; // 414 Host All Channels Interrupt Register + volatile uint32_t haintmsk; // 418 Host All Channels Interrupt Mask + volatile uint32_t hflbaddr; // 41C Host Frame List Base Address Register + uint32_t reserved420[8]; // 420..43C + volatile uint32_t hprt; // 440 Host Port Control and Status + uint32_t reserved444[47]; // 444..4FC + + //------------- Host Channel -------------// + dwc2_channel_t channel[16]; // 500..6FC Host Channels 0-15 + + uint32_t reserved700[64]; // 700..7FC + + //------------- Device -------------// + volatile uint32_t dcfg; // 800 Device Configuration Register + volatile uint32_t dctl; // 804 Device Control Register + volatile uint32_t dsts; // 808 Device Status Register (RO) + uint32_t reserved80c; // 80C + volatile uint32_t diepmsk; // 810 Device IN Endpoint Interrupt Mask + volatile uint32_t doepmsk; // 814 Device OUT Endpoint Interrupt Mask + volatile uint32_t daint; // 818 Device All Endpoints Interrupt + volatile uint32_t daintmsk; // 81C Device All Endpoints Interrupt Mask + volatile uint32_t dtknqr1; // 820 Device IN token sequence learning queue read register1 + volatile uint32_t dtknqr2; // 824 Device IN token sequence learning queue read register2 + volatile uint32_t dvbusdis; // 828 Device VBUS Discharge Time Register + volatile uint32_t dvbuspulse; // 82C Device VBUS Pulsing Time Register + volatile uint32_t dthrctl; // 830 Device threshold Control + volatile uint32_t diepempmsk; // 834 Device IN Endpoint FIFO Empty Interrupt Mask + + volatile uint32_t deachint; // 838 Device Each Endpoint Interrupt + volatile uint32_t deachmsk; // 83C Device Each Endpoint Interrupt msk + volatile uint32_t diepeachmsk[16]; // 840..87C Device Each IN Endpoint mask + volatile uint32_t doepeachmsk[16]; // 880..8BC Device Each OUT Endpoint mask + uint32_t reserved8c0[16]; // 8C0..8FC + + //------------- Device IN Endpoint -------------// + + + //------------- Device OUT Endpoint -------------// +} dwc2_core_t; + +TU_VERIFY_STATIC(offsetof(dwc2_core_t, hcfg ) == 0x0400, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_core_t, channel) == 0x0500, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_core_t, dcfg ) == 0x0800, "incorrect size"); // Endpoint IN typedef struct { - volatile uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ - volatile uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ - volatile uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - volatile uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - volatile uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ + volatile uint32_t DIEPCTL; // dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ + uint32_t Reserved04; // Reserved 900h + (ep_num * 20h) + 04h */ + volatile uint32_t DIEPINT; // dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ + uint32_t Reserved0C; // Reserved 900h + (ep_num * 20h) + 0Ch */ + volatile uint32_t DIEPTSIZ; // IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ + volatile uint32_t DIEPDMA; // IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ + volatile uint32_t DTXFSTS; // IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ + uint32_t Reserved18; // Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ } dwc2_epin_t; // Endpoint OUT typedef struct { - volatile uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ - volatile uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ - volatile uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ - volatile uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ - uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ + volatile uint32_t DOEPCTL; // dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ + uint32_t Reserved04; // Reserved B00h + (ep_num * 20h) + 04h */ + volatile uint32_t DOEPINT; // dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ + uint32_t Reserved0C; // Reserved B00h + (ep_num * 20h) + 0Ch */ + volatile uint32_t DOEPTSIZ; // dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ + volatile uint32_t DOEPDMA; // dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ + uint32_t Reserved18[2]; // Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ } dwc2_epout_t; @@ -167,1427 +189,1427 @@ typedef struct /******************** Bit definition for GOTGCTL register ********************/ #define GOTGCTL_SRQSCS_Pos (0U) -#define GOTGCTL_SRQSCS_Msk (0x1UL << GOTGCTL_SRQSCS_Pos) /*!< 0x00000001 */ -#define GOTGCTL_SRQSCS GOTGCTL_SRQSCS_Msk /*!< Session request success */ +#define GOTGCTL_SRQSCS_Msk (0x1UL << GOTGCTL_SRQSCS_Pos) // 0x00000001 */ +#define GOTGCTL_SRQSCS GOTGCTL_SRQSCS_Msk // Session request success */ #define GOTGCTL_SRQ_Pos (1U) -#define GOTGCTL_SRQ_Msk (0x1UL << GOTGCTL_SRQ_Pos) /*!< 0x00000002 */ -#define GOTGCTL_SRQ GOTGCTL_SRQ_Msk /*!< Session request */ +#define GOTGCTL_SRQ_Msk (0x1UL << GOTGCTL_SRQ_Pos) // 0x00000002 */ +#define GOTGCTL_SRQ GOTGCTL_SRQ_Msk // Session request */ #define GOTGCTL_VBVALOEN_Pos (2U) -#define GOTGCTL_VBVALOEN_Msk (0x1UL << GOTGCTL_VBVALOEN_Pos) /*!< 0x00000004 */ -#define GOTGCTL_VBVALOEN GOTGCTL_VBVALOEN_Msk /*!< VBUS valid override enable */ +#define GOTGCTL_VBVALOEN_Msk (0x1UL << GOTGCTL_VBVALOEN_Pos) // 0x00000004 */ +#define GOTGCTL_VBVALOEN GOTGCTL_VBVALOEN_Msk // VBUS valid override enable */ #define GOTGCTL_VBVALOVAL_Pos (3U) -#define GOTGCTL_VBVALOVAL_Msk (0x1UL << GOTGCTL_VBVALOVAL_Pos) /*!< 0x00000008 */ -#define GOTGCTL_VBVALOVAL GOTGCTL_VBVALOVAL_Msk /*!< VBUS valid override value */ +#define GOTGCTL_VBVALOVAL_Msk (0x1UL << GOTGCTL_VBVALOVAL_Pos) // 0x00000008 */ +#define GOTGCTL_VBVALOVAL GOTGCTL_VBVALOVAL_Msk // VBUS valid override value */ #define GOTGCTL_AVALOEN_Pos (4U) -#define GOTGCTL_AVALOEN_Msk (0x1UL << GOTGCTL_AVALOEN_Pos) /*!< 0x00000010 */ -#define GOTGCTL_AVALOEN GOTGCTL_AVALOEN_Msk /*!< A-peripheral session valid override enable */ +#define GOTGCTL_AVALOEN_Msk (0x1UL << GOTGCTL_AVALOEN_Pos) // 0x00000010 */ +#define GOTGCTL_AVALOEN GOTGCTL_AVALOEN_Msk // A-peripheral session valid override enable */ #define GOTGCTL_AVALOVAL_Pos (5U) -#define GOTGCTL_AVALOVAL_Msk (0x1UL << GOTGCTL_AVALOVAL_Pos) /*!< 0x00000020 */ -#define GOTGCTL_AVALOVAL GOTGCTL_AVALOVAL_Msk /*!< A-peripheral session valid override value */ +#define GOTGCTL_AVALOVAL_Msk (0x1UL << GOTGCTL_AVALOVAL_Pos) // 0x00000020 */ +#define GOTGCTL_AVALOVAL GOTGCTL_AVALOVAL_Msk // A-peripheral session valid override value */ #define GOTGCTL_BVALOEN_Pos (6U) -#define GOTGCTL_BVALOEN_Msk (0x1UL << GOTGCTL_BVALOEN_Pos) /*!< 0x00000040 */ -#define GOTGCTL_BVALOEN GOTGCTL_BVALOEN_Msk /*!< B-peripheral session valid override enable */ +#define GOTGCTL_BVALOEN_Msk (0x1UL << GOTGCTL_BVALOEN_Pos) // 0x00000040 */ +#define GOTGCTL_BVALOEN GOTGCTL_BVALOEN_Msk // B-peripheral session valid override enable */ #define GOTGCTL_BVALOVAL_Pos (7U) -#define GOTGCTL_BVALOVAL_Msk (0x1UL << GOTGCTL_BVALOVAL_Pos) /*!< 0x00000080 */ -#define GOTGCTL_BVALOVAL GOTGCTL_BVALOVAL_Msk /*!< B-peripheral session valid override value */ +#define GOTGCTL_BVALOVAL_Msk (0x1UL << GOTGCTL_BVALOVAL_Pos) // 0x00000080 */ +#define GOTGCTL_BVALOVAL GOTGCTL_BVALOVAL_Msk // B-peripheral session valid override value */ #define GOTGCTL_HNGSCS_Pos (8U) -#define GOTGCTL_HNGSCS_Msk (0x1UL << GOTGCTL_HNGSCS_Pos) /*!< 0x00000100 */ -#define GOTGCTL_HNGSCS GOTGCTL_HNGSCS_Msk /*!< Host set HNP enable */ +#define GOTGCTL_HNGSCS_Msk (0x1UL << GOTGCTL_HNGSCS_Pos) // 0x00000100 */ +#define GOTGCTL_HNGSCS GOTGCTL_HNGSCS_Msk // Host set HNP enable */ #define GOTGCTL_HNPRQ_Pos (9U) -#define GOTGCTL_HNPRQ_Msk (0x1UL << GOTGCTL_HNPRQ_Pos) /*!< 0x00000200 */ -#define GOTGCTL_HNPRQ GOTGCTL_HNPRQ_Msk /*!< HNP request */ +#define GOTGCTL_HNPRQ_Msk (0x1UL << GOTGCTL_HNPRQ_Pos) // 0x00000200 */ +#define GOTGCTL_HNPRQ GOTGCTL_HNPRQ_Msk // HNP request */ #define GOTGCTL_HSHNPEN_Pos (10U) -#define GOTGCTL_HSHNPEN_Msk (0x1UL << GOTGCTL_HSHNPEN_Pos) /*!< 0x00000400 */ -#define GOTGCTL_HSHNPEN GOTGCTL_HSHNPEN_Msk /*!< Host set HNP enable */ +#define GOTGCTL_HSHNPEN_Msk (0x1UL << GOTGCTL_HSHNPEN_Pos) // 0x00000400 */ +#define GOTGCTL_HSHNPEN GOTGCTL_HSHNPEN_Msk // Host set HNP enable */ #define GOTGCTL_DHNPEN_Pos (11U) -#define GOTGCTL_DHNPEN_Msk (0x1UL << GOTGCTL_DHNPEN_Pos) /*!< 0x00000800 */ -#define GOTGCTL_DHNPEN GOTGCTL_DHNPEN_Msk /*!< Device HNP enabled */ +#define GOTGCTL_DHNPEN_Msk (0x1UL << GOTGCTL_DHNPEN_Pos) // 0x00000800 */ +#define GOTGCTL_DHNPEN GOTGCTL_DHNPEN_Msk // Device HNP enabled */ #define GOTGCTL_EHEN_Pos (12U) -#define GOTGCTL_EHEN_Msk (0x1UL << GOTGCTL_EHEN_Pos) /*!< 0x00001000 */ -#define GOTGCTL_EHEN GOTGCTL_EHEN_Msk /*!< Embedded host enable */ +#define GOTGCTL_EHEN_Msk (0x1UL << GOTGCTL_EHEN_Pos) // 0x00001000 */ +#define GOTGCTL_EHEN GOTGCTL_EHEN_Msk // Embedded host enable */ #define GOTGCTL_CIDSTS_Pos (16U) -#define GOTGCTL_CIDSTS_Msk (0x1UL << GOTGCTL_CIDSTS_Pos) /*!< 0x00010000 */ -#define GOTGCTL_CIDSTS GOTGCTL_CIDSTS_Msk /*!< Connector ID status */ +#define GOTGCTL_CIDSTS_Msk (0x1UL << GOTGCTL_CIDSTS_Pos) // 0x00010000 */ +#define GOTGCTL_CIDSTS GOTGCTL_CIDSTS_Msk // Connector ID status */ #define GOTGCTL_DBCT_Pos (17U) -#define GOTGCTL_DBCT_Msk (0x1UL << GOTGCTL_DBCT_Pos) /*!< 0x00020000 */ -#define GOTGCTL_DBCT GOTGCTL_DBCT_Msk /*!< Long/short debounce time */ +#define GOTGCTL_DBCT_Msk (0x1UL << GOTGCTL_DBCT_Pos) // 0x00020000 */ +#define GOTGCTL_DBCT GOTGCTL_DBCT_Msk // Long/short debounce time */ #define GOTGCTL_ASVLD_Pos (18U) -#define GOTGCTL_ASVLD_Msk (0x1UL << GOTGCTL_ASVLD_Pos) /*!< 0x00040000 */ -#define GOTGCTL_ASVLD GOTGCTL_ASVLD_Msk /*!< A-session valid */ +#define GOTGCTL_ASVLD_Msk (0x1UL << GOTGCTL_ASVLD_Pos) // 0x00040000 */ +#define GOTGCTL_ASVLD GOTGCTL_ASVLD_Msk // A-session valid */ #define GOTGCTL_BSESVLD_Pos (19U) -#define GOTGCTL_BSESVLD_Msk (0x1UL << GOTGCTL_BSESVLD_Pos) /*!< 0x00080000 */ -#define GOTGCTL_BSESVLD GOTGCTL_BSESVLD_Msk /*!< B-session valid */ +#define GOTGCTL_BSESVLD_Msk (0x1UL << GOTGCTL_BSESVLD_Pos) // 0x00080000 */ +#define GOTGCTL_BSESVLD GOTGCTL_BSESVLD_Msk // B-session valid */ #define GOTGCTL_OTGVER_Pos (20U) -#define GOTGCTL_OTGVER_Msk (0x1UL << GOTGCTL_OTGVER_Pos) /*!< 0x00100000 */ -#define GOTGCTL_OTGVER GOTGCTL_OTGVER_Msk /*!< OTG version */ +#define GOTGCTL_OTGVER_Msk (0x1UL << GOTGCTL_OTGVER_Pos) // 0x00100000 */ +#define GOTGCTL_OTGVER GOTGCTL_OTGVER_Msk // OTG version */ /******************** Bit definition for HCFG register ********************/ #define HCFG_FSLSPCS_Pos (0U) -#define HCFG_FSLSPCS_Msk (0x3UL << HCFG_FSLSPCS_Pos) /*!< 0x00000003 */ -#define HCFG_FSLSPCS HCFG_FSLSPCS_Msk /*!< FS/LS PHY clock select */ -#define HCFG_FSLSPCS_0 (0x1UL << HCFG_FSLSPCS_Pos) /*!< 0x00000001 */ -#define HCFG_FSLSPCS_1 (0x2UL << HCFG_FSLSPCS_Pos) /*!< 0x00000002 */ +#define HCFG_FSLSPCS_Msk (0x3UL << HCFG_FSLSPCS_Pos) // 0x00000003 */ +#define HCFG_FSLSPCS HCFG_FSLSPCS_Msk // FS/LS PHY clock select */ +#define HCFG_FSLSPCS_0 (0x1UL << HCFG_FSLSPCS_Pos) // 0x00000001 */ +#define HCFG_FSLSPCS_1 (0x2UL << HCFG_FSLSPCS_Pos) // 0x00000002 */ #define HCFG_FSLSS_Pos (2U) -#define HCFG_FSLSS_Msk (0x1UL << HCFG_FSLSS_Pos) /*!< 0x00000004 */ -#define HCFG_FSLSS HCFG_FSLSS_Msk /*!< FS- and LS-only support */ +#define HCFG_FSLSS_Msk (0x1UL << HCFG_FSLSS_Pos) // 0x00000004 */ +#define HCFG_FSLSS HCFG_FSLSS_Msk // FS- and LS-only support */ /******************** Bit definition for DCFG register ********************/ #define DCFG_DSPD_Pos (0U) -#define DCFG_DSPD_Msk (0x3UL << DCFG_DSPD_Pos) /*!< 0x00000003 */ -#define DCFG_DSPD DCFG_DSPD_Msk /*!< Device speed */ -#define DCFG_DSPD_0 (0x1UL << DCFG_DSPD_Pos) /*!< 0x00000001 */ -#define DCFG_DSPD_1 (0x2UL << DCFG_DSPD_Pos) /*!< 0x00000002 */ +#define DCFG_DSPD_Msk (0x3UL << DCFG_DSPD_Pos) // 0x00000003 */ +#define DCFG_DSPD DCFG_DSPD_Msk // Device speed */ +#define DCFG_DSPD_0 (0x1UL << DCFG_DSPD_Pos) // 0x00000001 */ +#define DCFG_DSPD_1 (0x2UL << DCFG_DSPD_Pos) // 0x00000002 */ #define DCFG_NZLSOHSK_Pos (2U) -#define DCFG_NZLSOHSK_Msk (0x1UL << DCFG_NZLSOHSK_Pos) /*!< 0x00000004 */ -#define DCFG_NZLSOHSK DCFG_NZLSOHSK_Msk /*!< Nonzero-length status OUT handshake */ +#define DCFG_NZLSOHSK_Msk (0x1UL << DCFG_NZLSOHSK_Pos) // 0x00000004 */ +#define DCFG_NZLSOHSK DCFG_NZLSOHSK_Msk // Nonzero-length status OUT handshake */ #define DCFG_DAD_Pos (4U) -#define DCFG_DAD_Msk (0x7FUL << DCFG_DAD_Pos) /*!< 0x000007F0 */ -#define DCFG_DAD DCFG_DAD_Msk /*!< Device address */ -#define DCFG_DAD_0 (0x01UL << DCFG_DAD_Pos) /*!< 0x00000010 */ -#define DCFG_DAD_1 (0x02UL << DCFG_DAD_Pos) /*!< 0x00000020 */ -#define DCFG_DAD_2 (0x04UL << DCFG_DAD_Pos) /*!< 0x00000040 */ -#define DCFG_DAD_3 (0x08UL << DCFG_DAD_Pos) /*!< 0x00000080 */ -#define DCFG_DAD_4 (0x10UL << DCFG_DAD_Pos) /*!< 0x00000100 */ -#define DCFG_DAD_5 (0x20UL << DCFG_DAD_Pos) /*!< 0x00000200 */ -#define DCFG_DAD_6 (0x40UL << DCFG_DAD_Pos) /*!< 0x00000400 */ +#define DCFG_DAD_Msk (0x7FUL << DCFG_DAD_Pos) // 0x000007F0 */ +#define DCFG_DAD DCFG_DAD_Msk // Device address */ +#define DCFG_DAD_0 (0x01UL << DCFG_DAD_Pos) // 0x00000010 */ +#define DCFG_DAD_1 (0x02UL << DCFG_DAD_Pos) // 0x00000020 */ +#define DCFG_DAD_2 (0x04UL << DCFG_DAD_Pos) // 0x00000040 */ +#define DCFG_DAD_3 (0x08UL << DCFG_DAD_Pos) // 0x00000080 */ +#define DCFG_DAD_4 (0x10UL << DCFG_DAD_Pos) // 0x00000100 */ +#define DCFG_DAD_5 (0x20UL << DCFG_DAD_Pos) // 0x00000200 */ +#define DCFG_DAD_6 (0x40UL << DCFG_DAD_Pos) // 0x00000400 */ #define DCFG_PFIVL_Pos (11U) -#define DCFG_PFIVL_Msk (0x3UL << DCFG_PFIVL_Pos) /*!< 0x00001800 */ -#define DCFG_PFIVL DCFG_PFIVL_Msk /*!< Periodic (micro)frame interval */ -#define DCFG_PFIVL_0 (0x1UL << DCFG_PFIVL_Pos) /*!< 0x00000800 */ -#define DCFG_PFIVL_1 (0x2UL << DCFG_PFIVL_Pos) /*!< 0x00001000 */ +#define DCFG_PFIVL_Msk (0x3UL << DCFG_PFIVL_Pos) // 0x00001800 */ +#define DCFG_PFIVL DCFG_PFIVL_Msk // Periodic (micro)frame interval */ +#define DCFG_PFIVL_0 (0x1UL << DCFG_PFIVL_Pos) // 0x00000800 */ +#define DCFG_PFIVL_1 (0x2UL << DCFG_PFIVL_Pos) // 0x00001000 */ #define DCFG_PERSCHIVL_Pos (24U) -#define DCFG_PERSCHIVL_Msk (0x3UL << DCFG_PERSCHIVL_Pos) /*!< 0x03000000 */ -#define DCFG_PERSCHIVL DCFG_PERSCHIVL_Msk /*!< Periodic scheduling interval */ -#define DCFG_PERSCHIVL_0 (0x1UL << DCFG_PERSCHIVL_Pos) /*!< 0x01000000 */ -#define DCFG_PERSCHIVL_1 (0x2UL << DCFG_PERSCHIVL_Pos) /*!< 0x02000000 */ +#define DCFG_PERSCHIVL_Msk (0x3UL << DCFG_PERSCHIVL_Pos) // 0x03000000 */ +#define DCFG_PERSCHIVL DCFG_PERSCHIVL_Msk // Periodic scheduling interval */ +#define DCFG_PERSCHIVL_0 (0x1UL << DCFG_PERSCHIVL_Pos) // 0x01000000 */ +#define DCFG_PERSCHIVL_1 (0x2UL << DCFG_PERSCHIVL_Pos) // 0x02000000 */ /******************** Bit definition for PCGCR register ********************/ #define PCGCR_STPPCLK_Pos (0U) -#define PCGCR_STPPCLK_Msk (0x1UL << PCGCR_STPPCLK_Pos) /*!< 0x00000001 */ -#define PCGCR_STPPCLK PCGCR_STPPCLK_Msk /*!< Stop PHY clock */ +#define PCGCR_STPPCLK_Msk (0x1UL << PCGCR_STPPCLK_Pos) // 0x00000001 */ +#define PCGCR_STPPCLK PCGCR_STPPCLK_Msk // Stop PHY clock */ #define PCGCR_GATEHCLK_Pos (1U) -#define PCGCR_GATEHCLK_Msk (0x1UL << PCGCR_GATEHCLK_Pos) /*!< 0x00000002 */ -#define PCGCR_GATEHCLK PCGCR_GATEHCLK_Msk /*!< Gate HCLK */ +#define PCGCR_GATEHCLK_Msk (0x1UL << PCGCR_GATEHCLK_Pos) // 0x00000002 */ +#define PCGCR_GATEHCLK PCGCR_GATEHCLK_Msk // Gate HCLK */ #define PCGCR_PHYSUSP_Pos (4U) -#define PCGCR_PHYSUSP_Msk (0x1UL << PCGCR_PHYSUSP_Pos) /*!< 0x00000010 */ -#define PCGCR_PHYSUSP PCGCR_PHYSUSP_Msk /*!< PHY suspended */ +#define PCGCR_PHYSUSP_Msk (0x1UL << PCGCR_PHYSUSP_Pos) // 0x00000010 */ +#define PCGCR_PHYSUSP PCGCR_PHYSUSP_Msk // PHY suspended */ /******************** Bit definition for GOTGINT register ********************/ #define GOTGINT_SEDET_Pos (2U) -#define GOTGINT_SEDET_Msk (0x1UL << GOTGINT_SEDET_Pos) /*!< 0x00000004 */ -#define GOTGINT_SEDET GOTGINT_SEDET_Msk /*!< Session end detected */ +#define GOTGINT_SEDET_Msk (0x1UL << GOTGINT_SEDET_Pos) // 0x00000004 */ +#define GOTGINT_SEDET GOTGINT_SEDET_Msk // Session end detected */ #define GOTGINT_SRSSCHG_Pos (8U) -#define GOTGINT_SRSSCHG_Msk (0x1UL << GOTGINT_SRSSCHG_Pos) /*!< 0x00000100 */ -#define GOTGINT_SRSSCHG GOTGINT_SRSSCHG_Msk /*!< Session request success status change */ +#define GOTGINT_SRSSCHG_Msk (0x1UL << GOTGINT_SRSSCHG_Pos) // 0x00000100 */ +#define GOTGINT_SRSSCHG GOTGINT_SRSSCHG_Msk // Session request success status change */ #define GOTGINT_HNSSCHG_Pos (9U) -#define GOTGINT_HNSSCHG_Msk (0x1UL << GOTGINT_HNSSCHG_Pos) /*!< 0x00000200 */ -#define GOTGINT_HNSSCHG GOTGINT_HNSSCHG_Msk /*!< Host negotiation success status change */ +#define GOTGINT_HNSSCHG_Msk (0x1UL << GOTGINT_HNSSCHG_Pos) // 0x00000200 */ +#define GOTGINT_HNSSCHG GOTGINT_HNSSCHG_Msk // Host negotiation success status change */ #define GOTGINT_HNGDET_Pos (17U) -#define GOTGINT_HNGDET_Msk (0x1UL << GOTGINT_HNGDET_Pos) /*!< 0x00020000 */ -#define GOTGINT_HNGDET GOTGINT_HNGDET_Msk /*!< Host negotiation detected */ +#define GOTGINT_HNGDET_Msk (0x1UL << GOTGINT_HNGDET_Pos) // 0x00020000 */ +#define GOTGINT_HNGDET GOTGINT_HNGDET_Msk // Host negotiation detected */ #define GOTGINT_ADTOCHG_Pos (18U) -#define GOTGINT_ADTOCHG_Msk (0x1UL << GOTGINT_ADTOCHG_Pos) /*!< 0x00040000 */ -#define GOTGINT_ADTOCHG GOTGINT_ADTOCHG_Msk /*!< A-device timeout change */ +#define GOTGINT_ADTOCHG_Msk (0x1UL << GOTGINT_ADTOCHG_Pos) // 0x00040000 */ +#define GOTGINT_ADTOCHG GOTGINT_ADTOCHG_Msk // A-device timeout change */ #define GOTGINT_DBCDNE_Pos (19U) -#define GOTGINT_DBCDNE_Msk (0x1UL << GOTGINT_DBCDNE_Pos) /*!< 0x00080000 */ -#define GOTGINT_DBCDNE GOTGINT_DBCDNE_Msk /*!< Debounce done */ +#define GOTGINT_DBCDNE_Msk (0x1UL << GOTGINT_DBCDNE_Pos) // 0x00080000 */ +#define GOTGINT_DBCDNE GOTGINT_DBCDNE_Msk // Debounce done */ #define GOTGINT_IDCHNG_Pos (20U) -#define GOTGINT_IDCHNG_Msk (0x1UL << GOTGINT_IDCHNG_Pos) /*!< 0x00100000 */ -#define GOTGINT_IDCHNG GOTGINT_IDCHNG_Msk /*!< Change in ID pin input value */ +#define GOTGINT_IDCHNG_Msk (0x1UL << GOTGINT_IDCHNG_Pos) // 0x00100000 */ +#define GOTGINT_IDCHNG GOTGINT_IDCHNG_Msk // Change in ID pin input value */ /******************** Bit definition for DCTL register ********************/ #define DCTL_RWUSIG_Pos (0U) -#define DCTL_RWUSIG_Msk (0x1UL << DCTL_RWUSIG_Pos) /*!< 0x00000001 */ -#define DCTL_RWUSIG DCTL_RWUSIG_Msk /*!< Remote wakeup signaling */ +#define DCTL_RWUSIG_Msk (0x1UL << DCTL_RWUSIG_Pos) // 0x00000001 */ +#define DCTL_RWUSIG DCTL_RWUSIG_Msk // Remote wakeup signaling */ #define DCTL_SDIS_Pos (1U) -#define DCTL_SDIS_Msk (0x1UL << DCTL_SDIS_Pos) /*!< 0x00000002 */ -#define DCTL_SDIS DCTL_SDIS_Msk /*!< Soft disconnect */ +#define DCTL_SDIS_Msk (0x1UL << DCTL_SDIS_Pos) // 0x00000002 */ +#define DCTL_SDIS DCTL_SDIS_Msk // Soft disconnect */ #define DCTL_GINSTS_Pos (2U) -#define DCTL_GINSTS_Msk (0x1UL << DCTL_GINSTS_Pos) /*!< 0x00000004 */ -#define DCTL_GINSTS DCTL_GINSTS_Msk /*!< Global IN NAK status */ +#define DCTL_GINSTS_Msk (0x1UL << DCTL_GINSTS_Pos) // 0x00000004 */ +#define DCTL_GINSTS DCTL_GINSTS_Msk // Global IN NAK status */ #define DCTL_GONSTS_Pos (3U) -#define DCTL_GONSTS_Msk (0x1UL << DCTL_GONSTS_Pos) /*!< 0x00000008 */ -#define DCTL_GONSTS DCTL_GONSTS_Msk /*!< Global OUT NAK status */ +#define DCTL_GONSTS_Msk (0x1UL << DCTL_GONSTS_Pos) // 0x00000008 */ +#define DCTL_GONSTS DCTL_GONSTS_Msk // Global OUT NAK status */ #define DCTL_TCTL_Pos (4U) -#define DCTL_TCTL_Msk (0x7UL << DCTL_TCTL_Pos) /*!< 0x00000070 */ -#define DCTL_TCTL DCTL_TCTL_Msk /*!< Test control */ -#define DCTL_TCTL_0 (0x1UL << DCTL_TCTL_Pos) /*!< 0x00000010 */ -#define DCTL_TCTL_1 (0x2UL << DCTL_TCTL_Pos) /*!< 0x00000020 */ -#define DCTL_TCTL_2 (0x4UL << DCTL_TCTL_Pos) /*!< 0x00000040 */ +#define DCTL_TCTL_Msk (0x7UL << DCTL_TCTL_Pos) // 0x00000070 */ +#define DCTL_TCTL DCTL_TCTL_Msk // Test control */ +#define DCTL_TCTL_0 (0x1UL << DCTL_TCTL_Pos) // 0x00000010 */ +#define DCTL_TCTL_1 (0x2UL << DCTL_TCTL_Pos) // 0x00000020 */ +#define DCTL_TCTL_2 (0x4UL << DCTL_TCTL_Pos) // 0x00000040 */ #define DCTL_SGINAK_Pos (7U) -#define DCTL_SGINAK_Msk (0x1UL << DCTL_SGINAK_Pos) /*!< 0x00000080 */ -#define DCTL_SGINAK DCTL_SGINAK_Msk /*!< Set global IN NAK */ +#define DCTL_SGINAK_Msk (0x1UL << DCTL_SGINAK_Pos) // 0x00000080 */ +#define DCTL_SGINAK DCTL_SGINAK_Msk // Set global IN NAK */ #define DCTL_CGINAK_Pos (8U) -#define DCTL_CGINAK_Msk (0x1UL << DCTL_CGINAK_Pos) /*!< 0x00000100 */ -#define DCTL_CGINAK DCTL_CGINAK_Msk /*!< Clear global IN NAK */ +#define DCTL_CGINAK_Msk (0x1UL << DCTL_CGINAK_Pos) // 0x00000100 */ +#define DCTL_CGINAK DCTL_CGINAK_Msk // Clear global IN NAK */ #define DCTL_SGONAK_Pos (9U) -#define DCTL_SGONAK_Msk (0x1UL << DCTL_SGONAK_Pos) /*!< 0x00000200 */ -#define DCTL_SGONAK DCTL_SGONAK_Msk /*!< Set global OUT NAK */ +#define DCTL_SGONAK_Msk (0x1UL << DCTL_SGONAK_Pos) // 0x00000200 */ +#define DCTL_SGONAK DCTL_SGONAK_Msk // Set global OUT NAK */ #define DCTL_CGONAK_Pos (10U) -#define DCTL_CGONAK_Msk (0x1UL << DCTL_CGONAK_Pos) /*!< 0x00000400 */ -#define DCTL_CGONAK DCTL_CGONAK_Msk /*!< Clear global OUT NAK */ +#define DCTL_CGONAK_Msk (0x1UL << DCTL_CGONAK_Pos) // 0x00000400 */ +#define DCTL_CGONAK DCTL_CGONAK_Msk // Clear global OUT NAK */ #define DCTL_POPRGDNE_Pos (11U) -#define DCTL_POPRGDNE_Msk (0x1UL << DCTL_POPRGDNE_Pos) /*!< 0x00000800 */ -#define DCTL_POPRGDNE DCTL_POPRGDNE_Msk /*!< Power-on programming done */ +#define DCTL_POPRGDNE_Msk (0x1UL << DCTL_POPRGDNE_Pos) // 0x00000800 */ +#define DCTL_POPRGDNE DCTL_POPRGDNE_Msk // Power-on programming done */ /******************** Bit definition for HFIR register ********************/ #define HFIR_FRIVL_Pos (0U) -#define HFIR_FRIVL_Msk (0xFFFFUL << HFIR_FRIVL_Pos) /*!< 0x0000FFFF */ -#define HFIR_FRIVL HFIR_FRIVL_Msk /*!< Frame interval */ +#define HFIR_FRIVL_Msk (0xFFFFUL << HFIR_FRIVL_Pos) // 0x0000FFFF */ +#define HFIR_FRIVL HFIR_FRIVL_Msk // Frame interval */ /******************** Bit definition for HFNUM register ********************/ #define HFNUM_FRNUM_Pos (0U) -#define HFNUM_FRNUM_Msk (0xFFFFUL << HFNUM_FRNUM_Pos) /*!< 0x0000FFFF */ -#define HFNUM_FRNUM HFNUM_FRNUM_Msk /*!< Frame number */ +#define HFNUM_FRNUM_Msk (0xFFFFUL << HFNUM_FRNUM_Pos) // 0x0000FFFF */ +#define HFNUM_FRNUM HFNUM_FRNUM_Msk // Frame number */ #define HFNUM_FTREM_Pos (16U) -#define HFNUM_FTREM_Msk (0xFFFFUL << HFNUM_FTREM_Pos) /*!< 0xFFFF0000 */ -#define HFNUM_FTREM HFNUM_FTREM_Msk /*!< Frame time remaining */ +#define HFNUM_FTREM_Msk (0xFFFFUL << HFNUM_FTREM_Pos) // 0xFFFF0000 */ +#define HFNUM_FTREM HFNUM_FTREM_Msk // Frame time remaining */ /******************** Bit definition for DSTS register ********************/ #define DSTS_SUSPSTS_Pos (0U) -#define DSTS_SUSPSTS_Msk (0x1UL << DSTS_SUSPSTS_Pos) /*!< 0x00000001 */ -#define DSTS_SUSPSTS DSTS_SUSPSTS_Msk /*!< Suspend status */ +#define DSTS_SUSPSTS_Msk (0x1UL << DSTS_SUSPSTS_Pos) // 0x00000001 */ +#define DSTS_SUSPSTS DSTS_SUSPSTS_Msk // Suspend status */ #define DSTS_ENUMSPD_Pos (1U) -#define DSTS_ENUMSPD_Msk (0x3UL << DSTS_ENUMSPD_Pos) /*!< 0x00000006 */ -#define DSTS_ENUMSPD DSTS_ENUMSPD_Msk /*!< Enumerated speed */ -#define DSTS_ENUMSPD_0 (0x1UL << DSTS_ENUMSPD_Pos) /*!< 0x00000002 */ -#define DSTS_ENUMSPD_1 (0x2UL << DSTS_ENUMSPD_Pos) /*!< 0x00000004 */ +#define DSTS_ENUMSPD_Msk (0x3UL << DSTS_ENUMSPD_Pos) // 0x00000006 */ +#define DSTS_ENUMSPD DSTS_ENUMSPD_Msk // Enumerated speed */ +#define DSTS_ENUMSPD_0 (0x1UL << DSTS_ENUMSPD_Pos) // 0x00000002 */ +#define DSTS_ENUMSPD_1 (0x2UL << DSTS_ENUMSPD_Pos) // 0x00000004 */ #define DSTS_EERR_Pos (3U) -#define DSTS_EERR_Msk (0x1UL << DSTS_EERR_Pos) /*!< 0x00000008 */ -#define DSTS_EERR DSTS_EERR_Msk /*!< Erratic error */ +#define DSTS_EERR_Msk (0x1UL << DSTS_EERR_Pos) // 0x00000008 */ +#define DSTS_EERR DSTS_EERR_Msk // Erratic error */ #define DSTS_FNSOF_Pos (8U) -#define DSTS_FNSOF_Msk (0x3FFFUL << DSTS_FNSOF_Pos) /*!< 0x003FFF00 */ -#define DSTS_FNSOF DSTS_FNSOF_Msk /*!< Frame number of the received SOF */ +#define DSTS_FNSOF_Msk (0x3FFFUL << DSTS_FNSOF_Pos) // 0x003FFF00 */ +#define DSTS_FNSOF DSTS_FNSOF_Msk // Frame number of the received SOF */ /******************** Bit definition for GAHBCFG register ********************/ #define GAHBCFG_GINT_Pos (0U) -#define GAHBCFG_GINT_Msk (0x1UL << GAHBCFG_GINT_Pos) /*!< 0x00000001 */ -#define GAHBCFG_GINT GAHBCFG_GINT_Msk /*!< Global interrupt mask */ +#define GAHBCFG_GINT_Msk (0x1UL << GAHBCFG_GINT_Pos) // 0x00000001 */ +#define GAHBCFG_GINT GAHBCFG_GINT_Msk // Global interrupt mask */ #define GAHBCFG_HBSTLEN_Pos (1U) -#define GAHBCFG_HBSTLEN_Msk (0xFUL << GAHBCFG_HBSTLEN_Pos) /*!< 0x0000001E */ -#define GAHBCFG_HBSTLEN GAHBCFG_HBSTLEN_Msk /*!< Burst length/type */ -#define GAHBCFG_HBSTLEN_0 (0x0UL << GAHBCFG_HBSTLEN_Pos) /*!< Single */ -#define GAHBCFG_HBSTLEN_1 (0x1UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR */ -#define GAHBCFG_HBSTLEN_2 (0x3UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR4 */ -#define GAHBCFG_HBSTLEN_3 (0x5UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR8 */ -#define GAHBCFG_HBSTLEN_4 (0x7UL << GAHBCFG_HBSTLEN_Pos) /*!< INCR16 */ +#define GAHBCFG_HBSTLEN_Msk (0xFUL << GAHBCFG_HBSTLEN_Pos) // 0x0000001E */ +#define GAHBCFG_HBSTLEN GAHBCFG_HBSTLEN_Msk // Burst length/type */ +#define GAHBCFG_HBSTLEN_0 (0x0UL << GAHBCFG_HBSTLEN_Pos) // Single */ +#define GAHBCFG_HBSTLEN_1 (0x1UL << GAHBCFG_HBSTLEN_Pos) // INCR */ +#define GAHBCFG_HBSTLEN_2 (0x3UL << GAHBCFG_HBSTLEN_Pos) // INCR4 */ +#define GAHBCFG_HBSTLEN_3 (0x5UL << GAHBCFG_HBSTLEN_Pos) // INCR8 */ +#define GAHBCFG_HBSTLEN_4 (0x7UL << GAHBCFG_HBSTLEN_Pos) // INCR16 */ #define GAHBCFG_DMAEN_Pos (5U) -#define GAHBCFG_DMAEN_Msk (0x1UL << GAHBCFG_DMAEN_Pos) /*!< 0x00000020 */ -#define GAHBCFG_DMAEN GAHBCFG_DMAEN_Msk /*!< DMA enable */ +#define GAHBCFG_DMAEN_Msk (0x1UL << GAHBCFG_DMAEN_Pos) // 0x00000020 */ +#define GAHBCFG_DMAEN GAHBCFG_DMAEN_Msk // DMA enable */ #define GAHBCFG_TXFELVL_Pos (7U) -#define GAHBCFG_TXFELVL_Msk (0x1UL << GAHBCFG_TXFELVL_Pos) /*!< 0x00000080 */ -#define GAHBCFG_TXFELVL GAHBCFG_TXFELVL_Msk /*!< TxFIFO empty level */ +#define GAHBCFG_TXFELVL_Msk (0x1UL << GAHBCFG_TXFELVL_Pos) // 0x00000080 */ +#define GAHBCFG_TXFELVL GAHBCFG_TXFELVL_Msk // TxFIFO empty level */ #define GAHBCFG_PTXFELVL_Pos (8U) -#define GAHBCFG_PTXFELVL_Msk (0x1UL << GAHBCFG_PTXFELVL_Pos) /*!< 0x00000100 */ -#define GAHBCFG_PTXFELVL GAHBCFG_PTXFELVL_Msk /*!< Periodic TxFIFO empty level */ +#define GAHBCFG_PTXFELVL_Msk (0x1UL << GAHBCFG_PTXFELVL_Pos) // 0x00000100 */ +#define GAHBCFG_PTXFELVL GAHBCFG_PTXFELVL_Msk // Periodic TxFIFO empty level */ /******************** Bit definition for GUSBCFG register ********************/ #define GUSBCFG_TOCAL_Pos (0U) -#define GUSBCFG_TOCAL_Msk (0x7UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000007 */ -#define GUSBCFG_TOCAL GUSBCFG_TOCAL_Msk /*!< FS timeout calibration */ -#define GUSBCFG_TOCAL_0 (0x1UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000001 */ -#define GUSBCFG_TOCAL_1 (0x2UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000002 */ -#define GUSBCFG_TOCAL_2 (0x4UL << GUSBCFG_TOCAL_Pos) /*!< 0x00000004 */ +#define GUSBCFG_TOCAL_Msk (0x7UL << GUSBCFG_TOCAL_Pos) // 0x00000007 */ +#define GUSBCFG_TOCAL GUSBCFG_TOCAL_Msk // FS timeout calibration */ +#define GUSBCFG_TOCAL_0 (0x1UL << GUSBCFG_TOCAL_Pos) // 0x00000001 */ +#define GUSBCFG_TOCAL_1 (0x2UL << GUSBCFG_TOCAL_Pos) // 0x00000002 */ +#define GUSBCFG_TOCAL_2 (0x4UL << GUSBCFG_TOCAL_Pos) // 0x00000004 */ #define GUSBCFG_PHYIF_Pos (3U) -#define GUSBCFG_PHYIF_Msk (0x1UL << GUSBCFG_PHYIF_Pos) /*!< 0x00000008 */ -#define GUSBCFG_PHYIF GUSBCFG_PHYIF_Msk /*!< PHY Interface (PHYIf) */ +#define GUSBCFG_PHYIF_Msk (0x1UL << GUSBCFG_PHYIF_Pos) // 0x00000008 */ +#define GUSBCFG_PHYIF GUSBCFG_PHYIF_Msk // PHY Interface (PHYIf) */ #define GUSBCFG_ULPI_UTMI_SEL_Pos (4U) -#define GUSBCFG_ULPI_UTMI_SEL_Msk (0x1UL << GUSBCFG_ULPI_UTMI_SEL_Pos) /*!< 0x00000010 */ -#define GUSBCFG_ULPI_UTMI_SEL GUSBCFG_ULPI_UTMI_SEL_Msk /*!< ULPI or UTMI+ Select (ULPI_UTMI_Sel) */ +#define GUSBCFG_ULPI_UTMI_SEL_Msk (0x1UL << GUSBCFG_ULPI_UTMI_SEL_Pos) // 0x00000010 */ +#define GUSBCFG_ULPI_UTMI_SEL GUSBCFG_ULPI_UTMI_SEL_Msk // ULPI or UTMI+ Select (ULPI_UTMI_Sel) */ #define GUSBCFG_PHYSEL_Pos (6U) -#define GUSBCFG_PHYSEL_Msk (0x1UL << GUSBCFG_PHYSEL_Pos) /*!< 0x00000040 */ -#define GUSBCFG_PHYSEL GUSBCFG_PHYSEL_Msk /*!< USB 2.0 high-speed ULPI PHY or USB 1.1 full-speed serial transceiver select */ +#define GUSBCFG_PHYSEL_Msk (0x1UL << GUSBCFG_PHYSEL_Pos) // 0x00000040 */ +#define GUSBCFG_PHYSEL GUSBCFG_PHYSEL_Msk // USB 2.0 high-speed ULPI PHY or USB 1.1 full-speed serial transceiver select */ #define GUSBCFG_SRPCAP_Pos (8U) -#define GUSBCFG_SRPCAP_Msk (0x1UL << GUSBCFG_SRPCAP_Pos) /*!< 0x00000100 */ -#define GUSBCFG_SRPCAP GUSBCFG_SRPCAP_Msk /*!< SRP-capable */ +#define GUSBCFG_SRPCAP_Msk (0x1UL << GUSBCFG_SRPCAP_Pos) // 0x00000100 */ +#define GUSBCFG_SRPCAP GUSBCFG_SRPCAP_Msk // SRP-capable */ #define GUSBCFG_HNPCAP_Pos (9U) -#define GUSBCFG_HNPCAP_Msk (0x1UL << GUSBCFG_HNPCAP_Pos) /*!< 0x00000200 */ -#define GUSBCFG_HNPCAP GUSBCFG_HNPCAP_Msk /*!< HNP-capable */ +#define GUSBCFG_HNPCAP_Msk (0x1UL << GUSBCFG_HNPCAP_Pos) // 0x00000200 */ +#define GUSBCFG_HNPCAP GUSBCFG_HNPCAP_Msk // HNP-capable */ #define GUSBCFG_TRDT_Pos (10U) -#define GUSBCFG_TRDT_Msk (0xFUL << GUSBCFG_TRDT_Pos) /*!< 0x00003C00 */ -#define GUSBCFG_TRDT GUSBCFG_TRDT_Msk /*!< USB turnaround time */ -#define GUSBCFG_TRDT_0 (0x1UL << GUSBCFG_TRDT_Pos) /*!< 0x00000400 */ -#define GUSBCFG_TRDT_1 (0x2UL << GUSBCFG_TRDT_Pos) /*!< 0x00000800 */ -#define GUSBCFG_TRDT_2 (0x4UL << GUSBCFG_TRDT_Pos) /*!< 0x00001000 */ -#define GUSBCFG_TRDT_3 (0x8UL << GUSBCFG_TRDT_Pos) /*!< 0x00002000 */ +#define GUSBCFG_TRDT_Msk (0xFUL << GUSBCFG_TRDT_Pos) // 0x00003C00 */ +#define GUSBCFG_TRDT GUSBCFG_TRDT_Msk // USB turnaround time */ +#define GUSBCFG_TRDT_0 (0x1UL << GUSBCFG_TRDT_Pos) // 0x00000400 */ +#define GUSBCFG_TRDT_1 (0x2UL << GUSBCFG_TRDT_Pos) // 0x00000800 */ +#define GUSBCFG_TRDT_2 (0x4UL << GUSBCFG_TRDT_Pos) // 0x00001000 */ +#define GUSBCFG_TRDT_3 (0x8UL << GUSBCFG_TRDT_Pos) // 0x00002000 */ #define GUSBCFG_PHYLPCS_Pos (15U) -#define GUSBCFG_PHYLPCS_Msk (0x1UL << GUSBCFG_PHYLPCS_Pos) /*!< 0x00008000 */ -#define GUSBCFG_PHYLPCS GUSBCFG_PHYLPCS_Msk /*!< PHY Low-power clock select */ +#define GUSBCFG_PHYLPCS_Msk (0x1UL << GUSBCFG_PHYLPCS_Pos) // 0x00008000 */ +#define GUSBCFG_PHYLPCS GUSBCFG_PHYLPCS_Msk // PHY Low-power clock select */ #define GUSBCFG_ULPIFSLS_Pos (17U) -#define GUSBCFG_ULPIFSLS_Msk (0x1UL << GUSBCFG_ULPIFSLS_Pos) /*!< 0x00020000 */ -#define GUSBCFG_ULPIFSLS GUSBCFG_ULPIFSLS_Msk /*!< ULPI FS/LS select */ +#define GUSBCFG_ULPIFSLS_Msk (0x1UL << GUSBCFG_ULPIFSLS_Pos) // 0x00020000 */ +#define GUSBCFG_ULPIFSLS GUSBCFG_ULPIFSLS_Msk // ULPI FS/LS select */ #define GUSBCFG_ULPIAR_Pos (18U) -#define GUSBCFG_ULPIAR_Msk (0x1UL << GUSBCFG_ULPIAR_Pos) /*!< 0x00040000 */ -#define GUSBCFG_ULPIAR GUSBCFG_ULPIAR_Msk /*!< ULPI Auto-resume */ +#define GUSBCFG_ULPIAR_Msk (0x1UL << GUSBCFG_ULPIAR_Pos) // 0x00040000 */ +#define GUSBCFG_ULPIAR GUSBCFG_ULPIAR_Msk // ULPI Auto-resume */ #define GUSBCFG_ULPICSM_Pos (19U) -#define GUSBCFG_ULPICSM_Msk (0x1UL << GUSBCFG_ULPICSM_Pos) /*!< 0x00080000 */ -#define GUSBCFG_ULPICSM GUSBCFG_ULPICSM_Msk /*!< ULPI Clock SuspendM */ +#define GUSBCFG_ULPICSM_Msk (0x1UL << GUSBCFG_ULPICSM_Pos) // 0x00080000 */ +#define GUSBCFG_ULPICSM GUSBCFG_ULPICSM_Msk // ULPI Clock SuspendM */ #define GUSBCFG_ULPIEVBUSD_Pos (20U) -#define GUSBCFG_ULPIEVBUSD_Msk (0x1UL << GUSBCFG_ULPIEVBUSD_Pos) /*!< 0x00100000 */ -#define GUSBCFG_ULPIEVBUSD GUSBCFG_ULPIEVBUSD_Msk /*!< ULPI External VBUS Drive */ +#define GUSBCFG_ULPIEVBUSD_Msk (0x1UL << GUSBCFG_ULPIEVBUSD_Pos) // 0x00100000 */ +#define GUSBCFG_ULPIEVBUSD GUSBCFG_ULPIEVBUSD_Msk // ULPI External VBUS Drive */ #define GUSBCFG_ULPIEVBUSI_Pos (21U) -#define GUSBCFG_ULPIEVBUSI_Msk (0x1UL << GUSBCFG_ULPIEVBUSI_Pos) /*!< 0x00200000 */ -#define GUSBCFG_ULPIEVBUSI GUSBCFG_ULPIEVBUSI_Msk /*!< ULPI external VBUS indicator */ +#define GUSBCFG_ULPIEVBUSI_Msk (0x1UL << GUSBCFG_ULPIEVBUSI_Pos) // 0x00200000 */ +#define GUSBCFG_ULPIEVBUSI GUSBCFG_ULPIEVBUSI_Msk // ULPI external VBUS indicator */ #define GUSBCFG_TSDPS_Pos (22U) -#define GUSBCFG_TSDPS_Msk (0x1UL << GUSBCFG_TSDPS_Pos) /*!< 0x00400000 */ -#define GUSBCFG_TSDPS GUSBCFG_TSDPS_Msk /*!< TermSel DLine pulsing selection */ +#define GUSBCFG_TSDPS_Msk (0x1UL << GUSBCFG_TSDPS_Pos) // 0x00400000 */ +#define GUSBCFG_TSDPS GUSBCFG_TSDPS_Msk // TermSel DLine pulsing selection */ #define GUSBCFG_PCCI_Pos (23U) -#define GUSBCFG_PCCI_Msk (0x1UL << GUSBCFG_PCCI_Pos) /*!< 0x00800000 */ -#define GUSBCFG_PCCI GUSBCFG_PCCI_Msk /*!< Indicator complement */ +#define GUSBCFG_PCCI_Msk (0x1UL << GUSBCFG_PCCI_Pos) // 0x00800000 */ +#define GUSBCFG_PCCI GUSBCFG_PCCI_Msk // Indicator complement */ #define GUSBCFG_PTCI_Pos (24U) -#define GUSBCFG_PTCI_Msk (0x1UL << GUSBCFG_PTCI_Pos) /*!< 0x01000000 */ -#define GUSBCFG_PTCI GUSBCFG_PTCI_Msk /*!< Indicator pass through */ +#define GUSBCFG_PTCI_Msk (0x1UL << GUSBCFG_PTCI_Pos) // 0x01000000 */ +#define GUSBCFG_PTCI GUSBCFG_PTCI_Msk // Indicator pass through */ #define GUSBCFG_ULPIIPD_Pos (25U) -#define GUSBCFG_ULPIIPD_Msk (0x1UL << GUSBCFG_ULPIIPD_Pos) /*!< 0x02000000 */ -#define GUSBCFG_ULPIIPD GUSBCFG_ULPIIPD_Msk /*!< ULPI interface protect disable */ +#define GUSBCFG_ULPIIPD_Msk (0x1UL << GUSBCFG_ULPIIPD_Pos) // 0x02000000 */ +#define GUSBCFG_ULPIIPD GUSBCFG_ULPIIPD_Msk // ULPI interface protect disable */ #define GUSBCFG_FHMOD_Pos (29U) -#define GUSBCFG_FHMOD_Msk (0x1UL << GUSBCFG_FHMOD_Pos) /*!< 0x20000000 */ -#define GUSBCFG_FHMOD GUSBCFG_FHMOD_Msk /*!< Forced host mode */ +#define GUSBCFG_FHMOD_Msk (0x1UL << GUSBCFG_FHMOD_Pos) // 0x20000000 */ +#define GUSBCFG_FHMOD GUSBCFG_FHMOD_Msk // Forced host mode */ #define GUSBCFG_FDMOD_Pos (30U) -#define GUSBCFG_FDMOD_Msk (0x1UL << GUSBCFG_FDMOD_Pos) /*!< 0x40000000 */ -#define GUSBCFG_FDMOD GUSBCFG_FDMOD_Msk /*!< Forced peripheral mode */ +#define GUSBCFG_FDMOD_Msk (0x1UL << GUSBCFG_FDMOD_Pos) // 0x40000000 */ +#define GUSBCFG_FDMOD GUSBCFG_FDMOD_Msk // Forced peripheral mode */ #define GUSBCFG_CTXPKT_Pos (31U) -#define GUSBCFG_CTXPKT_Msk (0x1UL << GUSBCFG_CTXPKT_Pos) /*!< 0x80000000 */ -#define GUSBCFG_CTXPKT GUSBCFG_CTXPKT_Msk /*!< Corrupt Tx packet */ +#define GUSBCFG_CTXPKT_Msk (0x1UL << GUSBCFG_CTXPKT_Pos) // 0x80000000 */ +#define GUSBCFG_CTXPKT GUSBCFG_CTXPKT_Msk // Corrupt Tx packet */ /******************** Bit definition for GRSTCTL register ********************/ #define GRSTCTL_CSRST_Pos (0U) -#define GRSTCTL_CSRST_Msk (0x1UL << GRSTCTL_CSRST_Pos) /*!< 0x00000001 */ -#define GRSTCTL_CSRST GRSTCTL_CSRST_Msk /*!< Core soft reset */ +#define GRSTCTL_CSRST_Msk (0x1UL << GRSTCTL_CSRST_Pos) // 0x00000001 */ +#define GRSTCTL_CSRST GRSTCTL_CSRST_Msk // Core soft reset */ #define GRSTCTL_HSRST_Pos (1U) -#define GRSTCTL_HSRST_Msk (0x1UL << GRSTCTL_HSRST_Pos) /*!< 0x00000002 */ -#define GRSTCTL_HSRST GRSTCTL_HSRST_Msk /*!< HCLK soft reset */ +#define GRSTCTL_HSRST_Msk (0x1UL << GRSTCTL_HSRST_Pos) // 0x00000002 */ +#define GRSTCTL_HSRST GRSTCTL_HSRST_Msk // HCLK soft reset */ #define GRSTCTL_FCRST_Pos (2U) -#define GRSTCTL_FCRST_Msk (0x1UL << GRSTCTL_FCRST_Pos) /*!< 0x00000004 */ -#define GRSTCTL_FCRST GRSTCTL_FCRST_Msk /*!< Host frame counter reset */ +#define GRSTCTL_FCRST_Msk (0x1UL << GRSTCTL_FCRST_Pos) // 0x00000004 */ +#define GRSTCTL_FCRST GRSTCTL_FCRST_Msk // Host frame counter reset */ #define GRSTCTL_RXFFLSH_Pos (4U) -#define GRSTCTL_RXFFLSH_Msk (0x1UL << GRSTCTL_RXFFLSH_Pos) /*!< 0x00000010 */ -#define GRSTCTL_RXFFLSH GRSTCTL_RXFFLSH_Msk /*!< RxFIFO flush */ +#define GRSTCTL_RXFFLSH_Msk (0x1UL << GRSTCTL_RXFFLSH_Pos) // 0x00000010 */ +#define GRSTCTL_RXFFLSH GRSTCTL_RXFFLSH_Msk // RxFIFO flush */ #define GRSTCTL_TXFFLSH_Pos (5U) -#define GRSTCTL_TXFFLSH_Msk (0x1UL << GRSTCTL_TXFFLSH_Pos) /*!< 0x00000020 */ -#define GRSTCTL_TXFFLSH GRSTCTL_TXFFLSH_Msk /*!< TxFIFO flush */ +#define GRSTCTL_TXFFLSH_Msk (0x1UL << GRSTCTL_TXFFLSH_Pos) // 0x00000020 */ +#define GRSTCTL_TXFFLSH GRSTCTL_TXFFLSH_Msk // TxFIFO flush */ #define GRSTCTL_TXFNUM_Pos (6U) -#define GRSTCTL_TXFNUM_Msk (0x1FUL << GRSTCTL_TXFNUM_Pos) /*!< 0x000007C0 */ -#define GRSTCTL_TXFNUM GRSTCTL_TXFNUM_Msk /*!< TxFIFO number */ -#define GRSTCTL_TXFNUM_0 (0x01UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000040 */ -#define GRSTCTL_TXFNUM_1 (0x02UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000080 */ -#define GRSTCTL_TXFNUM_2 (0x04UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000100 */ -#define GRSTCTL_TXFNUM_3 (0x08UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000200 */ -#define GRSTCTL_TXFNUM_4 (0x10UL << GRSTCTL_TXFNUM_Pos) /*!< 0x00000400 */ +#define GRSTCTL_TXFNUM_Msk (0x1FUL << GRSTCTL_TXFNUM_Pos) // 0x000007C0 */ +#define GRSTCTL_TXFNUM GRSTCTL_TXFNUM_Msk // TxFIFO number */ +#define GRSTCTL_TXFNUM_0 (0x01UL << GRSTCTL_TXFNUM_Pos) // 0x00000040 */ +#define GRSTCTL_TXFNUM_1 (0x02UL << GRSTCTL_TXFNUM_Pos) // 0x00000080 */ +#define GRSTCTL_TXFNUM_2 (0x04UL << GRSTCTL_TXFNUM_Pos) // 0x00000100 */ +#define GRSTCTL_TXFNUM_3 (0x08UL << GRSTCTL_TXFNUM_Pos) // 0x00000200 */ +#define GRSTCTL_TXFNUM_4 (0x10UL << GRSTCTL_TXFNUM_Pos) // 0x00000400 */ #define GRSTCTL_DMAREQ_Pos (30U) -#define GRSTCTL_DMAREQ_Msk (0x1UL << GRSTCTL_DMAREQ_Pos) /*!< 0x40000000 */ -#define GRSTCTL_DMAREQ GRSTCTL_DMAREQ_Msk /*!< DMA request signal */ +#define GRSTCTL_DMAREQ_Msk (0x1UL << GRSTCTL_DMAREQ_Pos) // 0x40000000 */ +#define GRSTCTL_DMAREQ GRSTCTL_DMAREQ_Msk // DMA request signal */ #define GRSTCTL_AHBIDL_Pos (31U) -#define GRSTCTL_AHBIDL_Msk (0x1UL << GRSTCTL_AHBIDL_Pos) /*!< 0x80000000 */ -#define GRSTCTL_AHBIDL GRSTCTL_AHBIDL_Msk /*!< AHB master idle */ +#define GRSTCTL_AHBIDL_Msk (0x1UL << GRSTCTL_AHBIDL_Pos) // 0x80000000 */ +#define GRSTCTL_AHBIDL GRSTCTL_AHBIDL_Msk // AHB master idle */ /******************** Bit definition for DIEPMSK register ********************/ #define DIEPMSK_XFRCM_Pos (0U) -#define DIEPMSK_XFRCM_Msk (0x1UL << DIEPMSK_XFRCM_Pos) /*!< 0x00000001 */ -#define DIEPMSK_XFRCM DIEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define DIEPMSK_XFRCM_Msk (0x1UL << DIEPMSK_XFRCM_Pos) // 0x00000001 */ +#define DIEPMSK_XFRCM DIEPMSK_XFRCM_Msk // Transfer completed interrupt mask */ #define DIEPMSK_EPDM_Pos (1U) -#define DIEPMSK_EPDM_Msk (0x1UL << DIEPMSK_EPDM_Pos) /*!< 0x00000002 */ -#define DIEPMSK_EPDM DIEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define DIEPMSK_EPDM_Msk (0x1UL << DIEPMSK_EPDM_Pos) // 0x00000002 */ +#define DIEPMSK_EPDM DIEPMSK_EPDM_Msk // Endpoint disabled interrupt mask */ #define DIEPMSK_TOM_Pos (3U) -#define DIEPMSK_TOM_Msk (0x1UL << DIEPMSK_TOM_Pos) /*!< 0x00000008 */ -#define DIEPMSK_TOM DIEPMSK_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ +#define DIEPMSK_TOM_Msk (0x1UL << DIEPMSK_TOM_Pos) // 0x00000008 */ +#define DIEPMSK_TOM DIEPMSK_TOM_Msk // Timeout condition mask (nonisochronous endpoints) */ #define DIEPMSK_ITTXFEMSK_Pos (4U) -#define DIEPMSK_ITTXFEMSK_Msk (0x1UL << DIEPMSK_ITTXFEMSK_Pos) /*!< 0x00000010 */ -#define DIEPMSK_ITTXFEMSK DIEPMSK_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define DIEPMSK_ITTXFEMSK_Msk (0x1UL << DIEPMSK_ITTXFEMSK_Pos) // 0x00000010 */ +#define DIEPMSK_ITTXFEMSK DIEPMSK_ITTXFEMSK_Msk // IN token received when TxFIFO empty mask */ #define DIEPMSK_INEPNMM_Pos (5U) -#define DIEPMSK_INEPNMM_Msk (0x1UL << DIEPMSK_INEPNMM_Pos) /*!< 0x00000020 */ -#define DIEPMSK_INEPNMM DIEPMSK_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define DIEPMSK_INEPNMM_Msk (0x1UL << DIEPMSK_INEPNMM_Pos) // 0x00000020 */ +#define DIEPMSK_INEPNMM DIEPMSK_INEPNMM_Msk // IN token received with EP mismatch mask */ #define DIEPMSK_INEPNEM_Pos (6U) -#define DIEPMSK_INEPNEM_Msk (0x1UL << DIEPMSK_INEPNEM_Pos) /*!< 0x00000040 */ -#define DIEPMSK_INEPNEM DIEPMSK_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define DIEPMSK_INEPNEM_Msk (0x1UL << DIEPMSK_INEPNEM_Pos) // 0x00000040 */ +#define DIEPMSK_INEPNEM DIEPMSK_INEPNEM_Msk // IN endpoint NAK effective mask */ #define DIEPMSK_TXFURM_Pos (8U) -#define DIEPMSK_TXFURM_Msk (0x1UL << DIEPMSK_TXFURM_Pos) /*!< 0x00000100 */ -#define DIEPMSK_TXFURM DIEPMSK_TXFURM_Msk /*!< FIFO underrun mask */ +#define DIEPMSK_TXFURM_Msk (0x1UL << DIEPMSK_TXFURM_Pos) // 0x00000100 */ +#define DIEPMSK_TXFURM DIEPMSK_TXFURM_Msk // FIFO underrun mask */ #define DIEPMSK_BIM_Pos (9U) -#define DIEPMSK_BIM_Msk (0x1UL << DIEPMSK_BIM_Pos) /*!< 0x00000200 */ -#define DIEPMSK_BIM DIEPMSK_BIM_Msk /*!< BNA interrupt mask */ +#define DIEPMSK_BIM_Msk (0x1UL << DIEPMSK_BIM_Pos) // 0x00000200 */ +#define DIEPMSK_BIM DIEPMSK_BIM_Msk // BNA interrupt mask */ /******************** Bit definition for HPTXSTS register ********************/ #define HPTXSTS_PTXFSAVL_Pos (0U) -#define HPTXSTS_PTXFSAVL_Msk (0xFFFFUL << HPTXSTS_PTXFSAVL_Pos) /*!< 0x0000FFFF */ -#define HPTXSTS_PTXFSAVL HPTXSTS_PTXFSAVL_Msk /*!< Periodic transmit data FIFO space available */ +#define HPTXSTS_PTXFSAVL_Msk (0xFFFFUL << HPTXSTS_PTXFSAVL_Pos) // 0x0000FFFF */ +#define HPTXSTS_PTXFSAVL HPTXSTS_PTXFSAVL_Msk // Periodic transmit data FIFO space available */ #define HPTXSTS_PTXQSAV_Pos (16U) -#define HPTXSTS_PTXQSAV_Msk (0xFFUL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00FF0000 */ -#define HPTXSTS_PTXQSAV HPTXSTS_PTXQSAV_Msk /*!< Periodic transmit request queue space available */ -#define HPTXSTS_PTXQSAV_0 (0x01UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00010000 */ -#define HPTXSTS_PTXQSAV_1 (0x02UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00020000 */ -#define HPTXSTS_PTXQSAV_2 (0x04UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00040000 */ -#define HPTXSTS_PTXQSAV_3 (0x08UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00080000 */ -#define HPTXSTS_PTXQSAV_4 (0x10UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00100000 */ -#define HPTXSTS_PTXQSAV_5 (0x20UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00200000 */ -#define HPTXSTS_PTXQSAV_6 (0x40UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00400000 */ -#define HPTXSTS_PTXQSAV_7 (0x80UL << HPTXSTS_PTXQSAV_Pos) /*!< 0x00800000 */ +#define HPTXSTS_PTXQSAV_Msk (0xFFUL << HPTXSTS_PTXQSAV_Pos) // 0x00FF0000 */ +#define HPTXSTS_PTXQSAV HPTXSTS_PTXQSAV_Msk // Periodic transmit request queue space available */ +#define HPTXSTS_PTXQSAV_0 (0x01UL << HPTXSTS_PTXQSAV_Pos) // 0x00010000 */ +#define HPTXSTS_PTXQSAV_1 (0x02UL << HPTXSTS_PTXQSAV_Pos) // 0x00020000 */ +#define HPTXSTS_PTXQSAV_2 (0x04UL << HPTXSTS_PTXQSAV_Pos) // 0x00040000 */ +#define HPTXSTS_PTXQSAV_3 (0x08UL << HPTXSTS_PTXQSAV_Pos) // 0x00080000 */ +#define HPTXSTS_PTXQSAV_4 (0x10UL << HPTXSTS_PTXQSAV_Pos) // 0x00100000 */ +#define HPTXSTS_PTXQSAV_5 (0x20UL << HPTXSTS_PTXQSAV_Pos) // 0x00200000 */ +#define HPTXSTS_PTXQSAV_6 (0x40UL << HPTXSTS_PTXQSAV_Pos) // 0x00400000 */ +#define HPTXSTS_PTXQSAV_7 (0x80UL << HPTXSTS_PTXQSAV_Pos) // 0x00800000 */ #define HPTXSTS_PTXQTOP_Pos (24U) -#define HPTXSTS_PTXQTOP_Msk (0xFFUL << HPTXSTS_PTXQTOP_Pos) /*!< 0xFF000000 */ -#define HPTXSTS_PTXQTOP HPTXSTS_PTXQTOP_Msk /*!< Top of the periodic transmit request queue */ -#define HPTXSTS_PTXQTOP_0 (0x01UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x01000000 */ -#define HPTXSTS_PTXQTOP_1 (0x02UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x02000000 */ -#define HPTXSTS_PTXQTOP_2 (0x04UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x04000000 */ -#define HPTXSTS_PTXQTOP_3 (0x08UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x08000000 */ -#define HPTXSTS_PTXQTOP_4 (0x10UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x10000000 */ -#define HPTXSTS_PTXQTOP_5 (0x20UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x20000000 */ -#define HPTXSTS_PTXQTOP_6 (0x40UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x40000000 */ -#define HPTXSTS_PTXQTOP_7 (0x80UL << HPTXSTS_PTXQTOP_Pos) /*!< 0x80000000 */ +#define HPTXSTS_PTXQTOP_Msk (0xFFUL << HPTXSTS_PTXQTOP_Pos) // 0xFF000000 */ +#define HPTXSTS_PTXQTOP HPTXSTS_PTXQTOP_Msk // Top of the periodic transmit request queue */ +#define HPTXSTS_PTXQTOP_0 (0x01UL << HPTXSTS_PTXQTOP_Pos) // 0x01000000 */ +#define HPTXSTS_PTXQTOP_1 (0x02UL << HPTXSTS_PTXQTOP_Pos) // 0x02000000 */ +#define HPTXSTS_PTXQTOP_2 (0x04UL << HPTXSTS_PTXQTOP_Pos) // 0x04000000 */ +#define HPTXSTS_PTXQTOP_3 (0x08UL << HPTXSTS_PTXQTOP_Pos) // 0x08000000 */ +#define HPTXSTS_PTXQTOP_4 (0x10UL << HPTXSTS_PTXQTOP_Pos) // 0x10000000 */ +#define HPTXSTS_PTXQTOP_5 (0x20UL << HPTXSTS_PTXQTOP_Pos) // 0x20000000 */ +#define HPTXSTS_PTXQTOP_6 (0x40UL << HPTXSTS_PTXQTOP_Pos) // 0x40000000 */ +#define HPTXSTS_PTXQTOP_7 (0x80UL << HPTXSTS_PTXQTOP_Pos) // 0x80000000 */ /******************** Bit definition for HAINT register ********************/ #define HAINT_HAINT_Pos (0U) -#define HAINT_HAINT_Msk (0xFFFFUL << HAINT_HAINT_Pos) /*!< 0x0000FFFF */ -#define HAINT_HAINT HAINT_HAINT_Msk /*!< Channel interrupts */ +#define HAINT_HAINT_Msk (0xFFFFUL << HAINT_HAINT_Pos) // 0x0000FFFF */ +#define HAINT_HAINT HAINT_HAINT_Msk // Channel interrupts */ /******************** Bit definition for DOEPMSK register ********************/ #define DOEPMSK_XFRCM_Pos (0U) -#define DOEPMSK_XFRCM_Msk (0x1UL << DOEPMSK_XFRCM_Pos) /*!< 0x00000001 */ -#define DOEPMSK_XFRCM DOEPMSK_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define DOEPMSK_XFRCM_Msk (0x1UL << DOEPMSK_XFRCM_Pos) // 0x00000001 */ +#define DOEPMSK_XFRCM DOEPMSK_XFRCM_Msk // Transfer completed interrupt mask */ #define DOEPMSK_EPDM_Pos (1U) -#define DOEPMSK_EPDM_Msk (0x1UL << DOEPMSK_EPDM_Pos) /*!< 0x00000002 */ -#define DOEPMSK_EPDM DOEPMSK_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define DOEPMSK_EPDM_Msk (0x1UL << DOEPMSK_EPDM_Pos) // 0x00000002 */ +#define DOEPMSK_EPDM DOEPMSK_EPDM_Msk // Endpoint disabled interrupt mask */ #define DOEPMSK_AHBERRM_Pos (2U) -#define DOEPMSK_AHBERRM_Msk (0x1UL << DOEPMSK_AHBERRM_Pos) /*!< 0x00000004 */ -#define DOEPMSK_AHBERRM DOEPMSK_AHBERRM_Msk /*!< OUT transaction AHB Error interrupt mask */ +#define DOEPMSK_AHBERRM_Msk (0x1UL << DOEPMSK_AHBERRM_Pos) // 0x00000004 */ +#define DOEPMSK_AHBERRM DOEPMSK_AHBERRM_Msk // OUT transaction AHB Error interrupt mask */ #define DOEPMSK_STUPM_Pos (3U) -#define DOEPMSK_STUPM_Msk (0x1UL << DOEPMSK_STUPM_Pos) /*!< 0x00000008 */ -#define DOEPMSK_STUPM DOEPMSK_STUPM_Msk /*!< SETUP phase done mask */ +#define DOEPMSK_STUPM_Msk (0x1UL << DOEPMSK_STUPM_Pos) // 0x00000008 */ +#define DOEPMSK_STUPM DOEPMSK_STUPM_Msk // SETUP phase done mask */ #define DOEPMSK_OTEPDM_Pos (4U) -#define DOEPMSK_OTEPDM_Msk (0x1UL << DOEPMSK_OTEPDM_Pos) /*!< 0x00000010 */ -#define DOEPMSK_OTEPDM DOEPMSK_OTEPDM_Msk /*!< OUT token received when endpoint disabled mask */ +#define DOEPMSK_OTEPDM_Msk (0x1UL << DOEPMSK_OTEPDM_Pos) // 0x00000010 */ +#define DOEPMSK_OTEPDM DOEPMSK_OTEPDM_Msk // OUT token received when endpoint disabled mask */ #define DOEPMSK_OTEPSPRM_Pos (5U) -#define DOEPMSK_OTEPSPRM_Msk (0x1UL << DOEPMSK_OTEPSPRM_Pos) /*!< 0x00000020 */ -#define DOEPMSK_OTEPSPRM DOEPMSK_OTEPSPRM_Msk /*!< Status Phase Received mask */ +#define DOEPMSK_OTEPSPRM_Msk (0x1UL << DOEPMSK_OTEPSPRM_Pos) // 0x00000020 */ +#define DOEPMSK_OTEPSPRM DOEPMSK_OTEPSPRM_Msk // Status Phase Received mask */ #define DOEPMSK_B2BSTUP_Pos (6U) -#define DOEPMSK_B2BSTUP_Msk (0x1UL << DOEPMSK_B2BSTUP_Pos) /*!< 0x00000040 */ -#define DOEPMSK_B2BSTUP DOEPMSK_B2BSTUP_Msk /*!< Back-to-back SETUP packets received mask */ +#define DOEPMSK_B2BSTUP_Msk (0x1UL << DOEPMSK_B2BSTUP_Pos) // 0x00000040 */ +#define DOEPMSK_B2BSTUP DOEPMSK_B2BSTUP_Msk // Back-to-back SETUP packets received mask */ #define DOEPMSK_OPEM_Pos (8U) -#define DOEPMSK_OPEM_Msk (0x1UL << DOEPMSK_OPEM_Pos) /*!< 0x00000100 */ -#define DOEPMSK_OPEM DOEPMSK_OPEM_Msk /*!< OUT packet error mask */ +#define DOEPMSK_OPEM_Msk (0x1UL << DOEPMSK_OPEM_Pos) // 0x00000100 */ +#define DOEPMSK_OPEM DOEPMSK_OPEM_Msk // OUT packet error mask */ #define DOEPMSK_BOIM_Pos (9U) -#define DOEPMSK_BOIM_Msk (0x1UL << DOEPMSK_BOIM_Pos) /*!< 0x00000200 */ -#define DOEPMSK_BOIM DOEPMSK_BOIM_Msk /*!< BNA interrupt mask */ +#define DOEPMSK_BOIM_Msk (0x1UL << DOEPMSK_BOIM_Pos) // 0x00000200 */ +#define DOEPMSK_BOIM DOEPMSK_BOIM_Msk // BNA interrupt mask */ #define DOEPMSK_BERRM_Pos (12U) -#define DOEPMSK_BERRM_Msk (0x1UL << DOEPMSK_BERRM_Pos) /*!< 0x00001000 */ -#define DOEPMSK_BERRM DOEPMSK_BERRM_Msk /*!< Babble error interrupt mask */ +#define DOEPMSK_BERRM_Msk (0x1UL << DOEPMSK_BERRM_Pos) // 0x00001000 */ +#define DOEPMSK_BERRM DOEPMSK_BERRM_Msk // Babble error interrupt mask */ #define DOEPMSK_NAKM_Pos (13U) -#define DOEPMSK_NAKM_Msk (0x1UL << DOEPMSK_NAKM_Pos) /*!< 0x00002000 */ -#define DOEPMSK_NAKM DOEPMSK_NAKM_Msk /*!< OUT Packet NAK interrupt mask */ +#define DOEPMSK_NAKM_Msk (0x1UL << DOEPMSK_NAKM_Pos) // 0x00002000 */ +#define DOEPMSK_NAKM DOEPMSK_NAKM_Msk // OUT Packet NAK interrupt mask */ #define DOEPMSK_NYETM_Pos (14U) -#define DOEPMSK_NYETM_Msk (0x1UL << DOEPMSK_NYETM_Pos) /*!< 0x00004000 */ -#define DOEPMSK_NYETM DOEPMSK_NYETM_Msk /*!< NYET interrupt mask */ +#define DOEPMSK_NYETM_Msk (0x1UL << DOEPMSK_NYETM_Pos) // 0x00004000 */ +#define DOEPMSK_NYETM DOEPMSK_NYETM_Msk // NYET interrupt mask */ /******************** Bit definition for GINTSTS register ********************/ #define GINTSTS_CMOD_Pos (0U) -#define GINTSTS_CMOD_Msk (0x1UL << GINTSTS_CMOD_Pos) /*!< 0x00000001 */ -#define GINTSTS_CMOD GINTSTS_CMOD_Msk /*!< Current mode of operation */ +#define GINTSTS_CMOD_Msk (0x1UL << GINTSTS_CMOD_Pos) // 0x00000001 */ +#define GINTSTS_CMOD GINTSTS_CMOD_Msk // Current mode of operation */ #define GINTSTS_MMIS_Pos (1U) -#define GINTSTS_MMIS_Msk (0x1UL << GINTSTS_MMIS_Pos) /*!< 0x00000002 */ -#define GINTSTS_MMIS GINTSTS_MMIS_Msk /*!< Mode mismatch interrupt */ +#define GINTSTS_MMIS_Msk (0x1UL << GINTSTS_MMIS_Pos) // 0x00000002 */ +#define GINTSTS_MMIS GINTSTS_MMIS_Msk // Mode mismatch interrupt */ #define GINTSTS_OTGINT_Pos (2U) -#define GINTSTS_OTGINT_Msk (0x1UL << GINTSTS_OTGINT_Pos) /*!< 0x00000004 */ -#define GINTSTS_OTGINT GINTSTS_OTGINT_Msk /*!< OTG interrupt */ +#define GINTSTS_OTGINT_Msk (0x1UL << GINTSTS_OTGINT_Pos) // 0x00000004 */ +#define GINTSTS_OTGINT GINTSTS_OTGINT_Msk // OTG interrupt */ #define GINTSTS_SOF_Pos (3U) -#define GINTSTS_SOF_Msk (0x1UL << GINTSTS_SOF_Pos) /*!< 0x00000008 */ -#define GINTSTS_SOF GINTSTS_SOF_Msk /*!< Start of frame */ +#define GINTSTS_SOF_Msk (0x1UL << GINTSTS_SOF_Pos) // 0x00000008 */ +#define GINTSTS_SOF GINTSTS_SOF_Msk // Start of frame */ #define GINTSTS_RXFLVL_Pos (4U) -#define GINTSTS_RXFLVL_Msk (0x1UL << GINTSTS_RXFLVL_Pos) /*!< 0x00000010 */ -#define GINTSTS_RXFLVL GINTSTS_RXFLVL_Msk /*!< RxFIFO nonempty */ +#define GINTSTS_RXFLVL_Msk (0x1UL << GINTSTS_RXFLVL_Pos) // 0x00000010 */ +#define GINTSTS_RXFLVL GINTSTS_RXFLVL_Msk // RxFIFO nonempty */ #define GINTSTS_NPTXFE_Pos (5U) -#define GINTSTS_NPTXFE_Msk (0x1UL << GINTSTS_NPTXFE_Pos) /*!< 0x00000020 */ -#define GINTSTS_NPTXFE GINTSTS_NPTXFE_Msk /*!< Nonperiodic TxFIFO empty */ +#define GINTSTS_NPTXFE_Msk (0x1UL << GINTSTS_NPTXFE_Pos) // 0x00000020 */ +#define GINTSTS_NPTXFE GINTSTS_NPTXFE_Msk // Nonperiodic TxFIFO empty */ #define GINTSTS_GINAKEFF_Pos (6U) -#define GINTSTS_GINAKEFF_Msk (0x1UL << GINTSTS_GINAKEFF_Pos) /*!< 0x00000040 */ -#define GINTSTS_GINAKEFF GINTSTS_GINAKEFF_Msk /*!< Global IN nonperiodic NAK effective */ +#define GINTSTS_GINAKEFF_Msk (0x1UL << GINTSTS_GINAKEFF_Pos) // 0x00000040 */ +#define GINTSTS_GINAKEFF GINTSTS_GINAKEFF_Msk // Global IN nonperiodic NAK effective */ #define GINTSTS_BOUTNAKEFF_Pos (7U) -#define GINTSTS_BOUTNAKEFF_Msk (0x1UL << GINTSTS_BOUTNAKEFF_Pos) /*!< 0x00000080 */ -#define GINTSTS_BOUTNAKEFF GINTSTS_BOUTNAKEFF_Msk /*!< Global OUT NAK effective */ +#define GINTSTS_BOUTNAKEFF_Msk (0x1UL << GINTSTS_BOUTNAKEFF_Pos) // 0x00000080 */ +#define GINTSTS_BOUTNAKEFF GINTSTS_BOUTNAKEFF_Msk // Global OUT NAK effective */ #define GINTSTS_ESUSP_Pos (10U) -#define GINTSTS_ESUSP_Msk (0x1UL << GINTSTS_ESUSP_Pos) /*!< 0x00000400 */ -#define GINTSTS_ESUSP GINTSTS_ESUSP_Msk /*!< Early suspend */ +#define GINTSTS_ESUSP_Msk (0x1UL << GINTSTS_ESUSP_Pos) // 0x00000400 */ +#define GINTSTS_ESUSP GINTSTS_ESUSP_Msk // Early suspend */ #define GINTSTS_USBSUSP_Pos (11U) -#define GINTSTS_USBSUSP_Msk (0x1UL << GINTSTS_USBSUSP_Pos) /*!< 0x00000800 */ -#define GINTSTS_USBSUSP GINTSTS_USBSUSP_Msk /*!< USB suspend */ +#define GINTSTS_USBSUSP_Msk (0x1UL << GINTSTS_USBSUSP_Pos) // 0x00000800 */ +#define GINTSTS_USBSUSP GINTSTS_USBSUSP_Msk // USB suspend */ #define GINTSTS_USBRST_Pos (12U) -#define GINTSTS_USBRST_Msk (0x1UL << GINTSTS_USBRST_Pos) /*!< 0x00001000 */ -#define GINTSTS_USBRST GINTSTS_USBRST_Msk /*!< USB reset */ +#define GINTSTS_USBRST_Msk (0x1UL << GINTSTS_USBRST_Pos) // 0x00001000 */ +#define GINTSTS_USBRST GINTSTS_USBRST_Msk // USB reset */ #define GINTSTS_ENUMDNE_Pos (13U) -#define GINTSTS_ENUMDNE_Msk (0x1UL << GINTSTS_ENUMDNE_Pos) /*!< 0x00002000 */ -#define GINTSTS_ENUMDNE GINTSTS_ENUMDNE_Msk /*!< Enumeration done */ +#define GINTSTS_ENUMDNE_Msk (0x1UL << GINTSTS_ENUMDNE_Pos) // 0x00002000 */ +#define GINTSTS_ENUMDNE GINTSTS_ENUMDNE_Msk // Enumeration done */ #define GINTSTS_ISOODRP_Pos (14U) -#define GINTSTS_ISOODRP_Msk (0x1UL << GINTSTS_ISOODRP_Pos) /*!< 0x00004000 */ -#define GINTSTS_ISOODRP GINTSTS_ISOODRP_Msk /*!< Isochronous OUT packet dropped interrupt */ +#define GINTSTS_ISOODRP_Msk (0x1UL << GINTSTS_ISOODRP_Pos) // 0x00004000 */ +#define GINTSTS_ISOODRP GINTSTS_ISOODRP_Msk // Isochronous OUT packet dropped interrupt */ #define GINTSTS_EOPF_Pos (15U) -#define GINTSTS_EOPF_Msk (0x1UL << GINTSTS_EOPF_Pos) /*!< 0x00008000 */ -#define GINTSTS_EOPF GINTSTS_EOPF_Msk /*!< End of periodic frame interrupt */ +#define GINTSTS_EOPF_Msk (0x1UL << GINTSTS_EOPF_Pos) // 0x00008000 */ +#define GINTSTS_EOPF GINTSTS_EOPF_Msk // End of periodic frame interrupt */ #define GINTSTS_IEPINT_Pos (18U) -#define GINTSTS_IEPINT_Msk (0x1UL << GINTSTS_IEPINT_Pos) /*!< 0x00040000 */ -#define GINTSTS_IEPINT GINTSTS_IEPINT_Msk /*!< IN endpoint interrupt */ +#define GINTSTS_IEPINT_Msk (0x1UL << GINTSTS_IEPINT_Pos) // 0x00040000 */ +#define GINTSTS_IEPINT GINTSTS_IEPINT_Msk // IN endpoint interrupt */ #define GINTSTS_OEPINT_Pos (19U) -#define GINTSTS_OEPINT_Msk (0x1UL << GINTSTS_OEPINT_Pos) /*!< 0x00080000 */ -#define GINTSTS_OEPINT GINTSTS_OEPINT_Msk /*!< OUT endpoint interrupt */ +#define GINTSTS_OEPINT_Msk (0x1UL << GINTSTS_OEPINT_Pos) // 0x00080000 */ +#define GINTSTS_OEPINT GINTSTS_OEPINT_Msk // OUT endpoint interrupt */ #define GINTSTS_IISOIXFR_Pos (20U) -#define GINTSTS_IISOIXFR_Msk (0x1UL << GINTSTS_IISOIXFR_Pos) /*!< 0x00100000 */ -#define GINTSTS_IISOIXFR GINTSTS_IISOIXFR_Msk /*!< Incomplete isochronous IN transfer */ +#define GINTSTS_IISOIXFR_Msk (0x1UL << GINTSTS_IISOIXFR_Pos) // 0x00100000 */ +#define GINTSTS_IISOIXFR GINTSTS_IISOIXFR_Msk // Incomplete isochronous IN transfer */ #define GINTSTS_PXFR_INCOMPISOOUT_Pos (21U) -#define GINTSTS_PXFR_INCOMPISOOUT_Msk (0x1UL << GINTSTS_PXFR_INCOMPISOOUT_Pos) /*!< 0x00200000 */ -#define GINTSTS_PXFR_INCOMPISOOUT GINTSTS_PXFR_INCOMPISOOUT_Msk /*!< Incomplete periodic transfer */ +#define GINTSTS_PXFR_INCOMPISOOUT_Msk (0x1UL << GINTSTS_PXFR_INCOMPISOOUT_Pos) // 0x00200000 */ +#define GINTSTS_PXFR_INCOMPISOOUT GINTSTS_PXFR_INCOMPISOOUT_Msk // Incomplete periodic transfer */ #define GINTSTS_DATAFSUSP_Pos (22U) -#define GINTSTS_DATAFSUSP_Msk (0x1UL << GINTSTS_DATAFSUSP_Pos) /*!< 0x00400000 */ -#define GINTSTS_DATAFSUSP GINTSTS_DATAFSUSP_Msk /*!< Data fetch suspended */ +#define GINTSTS_DATAFSUSP_Msk (0x1UL << GINTSTS_DATAFSUSP_Pos) // 0x00400000 */ +#define GINTSTS_DATAFSUSP GINTSTS_DATAFSUSP_Msk // Data fetch suspended */ #define GINTSTS_RSTDET_Pos (23U) -#define GINTSTS_RSTDET_Msk (0x1UL << GINTSTS_RSTDET_Pos) /*!< 0x00800000 */ -#define GINTSTS_RSTDET GINTSTS_RSTDET_Msk /*!< Reset detected interrupt */ +#define GINTSTS_RSTDET_Msk (0x1UL << GINTSTS_RSTDET_Pos) // 0x00800000 */ +#define GINTSTS_RSTDET GINTSTS_RSTDET_Msk // Reset detected interrupt */ #define GINTSTS_HPRTINT_Pos (24U) -#define GINTSTS_HPRTINT_Msk (0x1UL << GINTSTS_HPRTINT_Pos) /*!< 0x01000000 */ -#define GINTSTS_HPRTINT GINTSTS_HPRTINT_Msk /*!< Host port interrupt */ +#define GINTSTS_HPRTINT_Msk (0x1UL << GINTSTS_HPRTINT_Pos) // 0x01000000 */ +#define GINTSTS_HPRTINT GINTSTS_HPRTINT_Msk // Host port interrupt */ #define GINTSTS_HCINT_Pos (25U) -#define GINTSTS_HCINT_Msk (0x1UL << GINTSTS_HCINT_Pos) /*!< 0x02000000 */ -#define GINTSTS_HCINT GINTSTS_HCINT_Msk /*!< Host channels interrupt */ +#define GINTSTS_HCINT_Msk (0x1UL << GINTSTS_HCINT_Pos) // 0x02000000 */ +#define GINTSTS_HCINT GINTSTS_HCINT_Msk // Host channels interrupt */ #define GINTSTS_PTXFE_Pos (26U) -#define GINTSTS_PTXFE_Msk (0x1UL << GINTSTS_PTXFE_Pos) /*!< 0x04000000 */ -#define GINTSTS_PTXFE GINTSTS_PTXFE_Msk /*!< Periodic TxFIFO empty */ +#define GINTSTS_PTXFE_Msk (0x1UL << GINTSTS_PTXFE_Pos) // 0x04000000 */ +#define GINTSTS_PTXFE GINTSTS_PTXFE_Msk // Periodic TxFIFO empty */ #define GINTSTS_LPMINT_Pos (27U) -#define GINTSTS_LPMINT_Msk (0x1UL << GINTSTS_LPMINT_Pos) /*!< 0x08000000 */ -#define GINTSTS_LPMINT GINTSTS_LPMINT_Msk /*!< LPM interrupt */ +#define GINTSTS_LPMINT_Msk (0x1UL << GINTSTS_LPMINT_Pos) // 0x08000000 */ +#define GINTSTS_LPMINT GINTSTS_LPMINT_Msk // LPM interrupt */ #define GINTSTS_CIDSCHG_Pos (28U) -#define GINTSTS_CIDSCHG_Msk (0x1UL << GINTSTS_CIDSCHG_Pos) /*!< 0x10000000 */ -#define GINTSTS_CIDSCHG GINTSTS_CIDSCHG_Msk /*!< Connector ID status change */ +#define GINTSTS_CIDSCHG_Msk (0x1UL << GINTSTS_CIDSCHG_Pos) // 0x10000000 */ +#define GINTSTS_CIDSCHG GINTSTS_CIDSCHG_Msk // Connector ID status change */ #define GINTSTS_DISCINT_Pos (29U) -#define GINTSTS_DISCINT_Msk (0x1UL << GINTSTS_DISCINT_Pos) /*!< 0x20000000 */ -#define GINTSTS_DISCINT GINTSTS_DISCINT_Msk /*!< Disconnect detected interrupt */ +#define GINTSTS_DISCINT_Msk (0x1UL << GINTSTS_DISCINT_Pos) // 0x20000000 */ +#define GINTSTS_DISCINT GINTSTS_DISCINT_Msk // Disconnect detected interrupt */ #define GINTSTS_SRQINT_Pos (30U) -#define GINTSTS_SRQINT_Msk (0x1UL << GINTSTS_SRQINT_Pos) /*!< 0x40000000 */ -#define GINTSTS_SRQINT GINTSTS_SRQINT_Msk /*!< Session request/new session detected interrupt */ +#define GINTSTS_SRQINT_Msk (0x1UL << GINTSTS_SRQINT_Pos) // 0x40000000 */ +#define GINTSTS_SRQINT GINTSTS_SRQINT_Msk // Session request/new session detected interrupt */ #define GINTSTS_WKUINT_Pos (31U) -#define GINTSTS_WKUINT_Msk (0x1UL << GINTSTS_WKUINT_Pos) /*!< 0x80000000 */ -#define GINTSTS_WKUINT GINTSTS_WKUINT_Msk /*!< Resume/remote wakeup detected interrupt */ +#define GINTSTS_WKUINT_Msk (0x1UL << GINTSTS_WKUINT_Pos) // 0x80000000 */ +#define GINTSTS_WKUINT GINTSTS_WKUINT_Msk // Resume/remote wakeup detected interrupt */ /******************** Bit definition for GINTMSK register ********************/ #define GINTMSK_MMISM_Pos (1U) -#define GINTMSK_MMISM_Msk (0x1UL << GINTMSK_MMISM_Pos) /*!< 0x00000002 */ -#define GINTMSK_MMISM GINTMSK_MMISM_Msk /*!< Mode mismatch interrupt mask */ +#define GINTMSK_MMISM_Msk (0x1UL << GINTMSK_MMISM_Pos) // 0x00000002 */ +#define GINTMSK_MMISM GINTMSK_MMISM_Msk // Mode mismatch interrupt mask */ #define GINTMSK_OTGINT_Pos (2U) -#define GINTMSK_OTGINT_Msk (0x1UL << GINTMSK_OTGINT_Pos) /*!< 0x00000004 */ -#define GINTMSK_OTGINT GINTMSK_OTGINT_Msk /*!< OTG interrupt mask */ +#define GINTMSK_OTGINT_Msk (0x1UL << GINTMSK_OTGINT_Pos) // 0x00000004 */ +#define GINTMSK_OTGINT GINTMSK_OTGINT_Msk // OTG interrupt mask */ #define GINTMSK_SOFM_Pos (3U) -#define GINTMSK_SOFM_Msk (0x1UL << GINTMSK_SOFM_Pos) /*!< 0x00000008 */ -#define GINTMSK_SOFM GINTMSK_SOFM_Msk /*!< Start of frame mask */ +#define GINTMSK_SOFM_Msk (0x1UL << GINTMSK_SOFM_Pos) // 0x00000008 */ +#define GINTMSK_SOFM GINTMSK_SOFM_Msk // Start of frame mask */ #define GINTMSK_RXFLVLM_Pos (4U) -#define GINTMSK_RXFLVLM_Msk (0x1UL << GINTMSK_RXFLVLM_Pos) /*!< 0x00000010 */ -#define GINTMSK_RXFLVLM GINTMSK_RXFLVLM_Msk /*!< Receive FIFO nonempty mask */ +#define GINTMSK_RXFLVLM_Msk (0x1UL << GINTMSK_RXFLVLM_Pos) // 0x00000010 */ +#define GINTMSK_RXFLVLM GINTMSK_RXFLVLM_Msk // Receive FIFO nonempty mask */ #define GINTMSK_NPTXFEM_Pos (5U) -#define GINTMSK_NPTXFEM_Msk (0x1UL << GINTMSK_NPTXFEM_Pos) /*!< 0x00000020 */ -#define GINTMSK_NPTXFEM GINTMSK_NPTXFEM_Msk /*!< Nonperiodic TxFIFO empty mask */ +#define GINTMSK_NPTXFEM_Msk (0x1UL << GINTMSK_NPTXFEM_Pos) // 0x00000020 */ +#define GINTMSK_NPTXFEM GINTMSK_NPTXFEM_Msk // Nonperiodic TxFIFO empty mask */ #define GINTMSK_GINAKEFFM_Pos (6U) -#define GINTMSK_GINAKEFFM_Msk (0x1UL << GINTMSK_GINAKEFFM_Pos) /*!< 0x00000040 */ -#define GINTMSK_GINAKEFFM GINTMSK_GINAKEFFM_Msk /*!< Global nonperiodic IN NAK effective mask */ +#define GINTMSK_GINAKEFFM_Msk (0x1UL << GINTMSK_GINAKEFFM_Pos) // 0x00000040 */ +#define GINTMSK_GINAKEFFM GINTMSK_GINAKEFFM_Msk // Global nonperiodic IN NAK effective mask */ #define GINTMSK_GONAKEFFM_Pos (7U) -#define GINTMSK_GONAKEFFM_Msk (0x1UL << GINTMSK_GONAKEFFM_Pos) /*!< 0x00000080 */ -#define GINTMSK_GONAKEFFM GINTMSK_GONAKEFFM_Msk /*!< Global OUT NAK effective mask */ +#define GINTMSK_GONAKEFFM_Msk (0x1UL << GINTMSK_GONAKEFFM_Pos) // 0x00000080 */ +#define GINTMSK_GONAKEFFM GINTMSK_GONAKEFFM_Msk // Global OUT NAK effective mask */ #define GINTMSK_ESUSPM_Pos (10U) -#define GINTMSK_ESUSPM_Msk (0x1UL << GINTMSK_ESUSPM_Pos) /*!< 0x00000400 */ -#define GINTMSK_ESUSPM GINTMSK_ESUSPM_Msk /*!< Early suspend mask */ +#define GINTMSK_ESUSPM_Msk (0x1UL << GINTMSK_ESUSPM_Pos) // 0x00000400 */ +#define GINTMSK_ESUSPM GINTMSK_ESUSPM_Msk // Early suspend mask */ #define GINTMSK_USBSUSPM_Pos (11U) -#define GINTMSK_USBSUSPM_Msk (0x1UL << GINTMSK_USBSUSPM_Pos) /*!< 0x00000800 */ -#define GINTMSK_USBSUSPM GINTMSK_USBSUSPM_Msk /*!< USB suspend mask */ +#define GINTMSK_USBSUSPM_Msk (0x1UL << GINTMSK_USBSUSPM_Pos) // 0x00000800 */ +#define GINTMSK_USBSUSPM GINTMSK_USBSUSPM_Msk // USB suspend mask */ #define GINTMSK_USBRST_Pos (12U) -#define GINTMSK_USBRST_Msk (0x1UL << GINTMSK_USBRST_Pos) /*!< 0x00001000 */ -#define GINTMSK_USBRST GINTMSK_USBRST_Msk /*!< USB reset mask */ +#define GINTMSK_USBRST_Msk (0x1UL << GINTMSK_USBRST_Pos) // 0x00001000 */ +#define GINTMSK_USBRST GINTMSK_USBRST_Msk // USB reset mask */ #define GINTMSK_ENUMDNEM_Pos (13U) -#define GINTMSK_ENUMDNEM_Msk (0x1UL << GINTMSK_ENUMDNEM_Pos) /*!< 0x00002000 */ -#define GINTMSK_ENUMDNEM GINTMSK_ENUMDNEM_Msk /*!< Enumeration done mask */ +#define GINTMSK_ENUMDNEM_Msk (0x1UL << GINTMSK_ENUMDNEM_Pos) // 0x00002000 */ +#define GINTMSK_ENUMDNEM GINTMSK_ENUMDNEM_Msk // Enumeration done mask */ #define GINTMSK_ISOODRPM_Pos (14U) -#define GINTMSK_ISOODRPM_Msk (0x1UL << GINTMSK_ISOODRPM_Pos) /*!< 0x00004000 */ -#define GINTMSK_ISOODRPM GINTMSK_ISOODRPM_Msk /*!< Isochronous OUT packet dropped interrupt mask */ +#define GINTMSK_ISOODRPM_Msk (0x1UL << GINTMSK_ISOODRPM_Pos) // 0x00004000 */ +#define GINTMSK_ISOODRPM GINTMSK_ISOODRPM_Msk // Isochronous OUT packet dropped interrupt mask */ #define GINTMSK_EOPFM_Pos (15U) -#define GINTMSK_EOPFM_Msk (0x1UL << GINTMSK_EOPFM_Pos) /*!< 0x00008000 */ -#define GINTMSK_EOPFM GINTMSK_EOPFM_Msk /*!< End of periodic frame interrupt mask */ +#define GINTMSK_EOPFM_Msk (0x1UL << GINTMSK_EOPFM_Pos) // 0x00008000 */ +#define GINTMSK_EOPFM GINTMSK_EOPFM_Msk // End of periodic frame interrupt mask */ #define GINTMSK_EPMISM_Pos (17U) -#define GINTMSK_EPMISM_Msk (0x1UL << GINTMSK_EPMISM_Pos) /*!< 0x00020000 */ -#define GINTMSK_EPMISM GINTMSK_EPMISM_Msk /*!< Endpoint mismatch interrupt mask */ +#define GINTMSK_EPMISM_Msk (0x1UL << GINTMSK_EPMISM_Pos) // 0x00020000 */ +#define GINTMSK_EPMISM GINTMSK_EPMISM_Msk // Endpoint mismatch interrupt mask */ #define GINTMSK_IEPINT_Pos (18U) -#define GINTMSK_IEPINT_Msk (0x1UL << GINTMSK_IEPINT_Pos) /*!< 0x00040000 */ -#define GINTMSK_IEPINT GINTMSK_IEPINT_Msk /*!< IN endpoints interrupt mask */ +#define GINTMSK_IEPINT_Msk (0x1UL << GINTMSK_IEPINT_Pos) // 0x00040000 */ +#define GINTMSK_IEPINT GINTMSK_IEPINT_Msk // IN endpoints interrupt mask */ #define GINTMSK_OEPINT_Pos (19U) -#define GINTMSK_OEPINT_Msk (0x1UL << GINTMSK_OEPINT_Pos) /*!< 0x00080000 */ -#define GINTMSK_OEPINT GINTMSK_OEPINT_Msk /*!< OUT endpoints interrupt mask */ +#define GINTMSK_OEPINT_Msk (0x1UL << GINTMSK_OEPINT_Pos) // 0x00080000 */ +#define GINTMSK_OEPINT GINTMSK_OEPINT_Msk // OUT endpoints interrupt mask */ #define GINTMSK_IISOIXFRM_Pos (20U) -#define GINTMSK_IISOIXFRM_Msk (0x1UL << GINTMSK_IISOIXFRM_Pos) /*!< 0x00100000 */ -#define GINTMSK_IISOIXFRM GINTMSK_IISOIXFRM_Msk /*!< Incomplete isochronous IN transfer mask */ +#define GINTMSK_IISOIXFRM_Msk (0x1UL << GINTMSK_IISOIXFRM_Pos) // 0x00100000 */ +#define GINTMSK_IISOIXFRM GINTMSK_IISOIXFRM_Msk // Incomplete isochronous IN transfer mask */ #define GINTMSK_PXFRM_IISOOXFRM_Pos (21U) -#define GINTMSK_PXFRM_IISOOXFRM_Msk (0x1UL << GINTMSK_PXFRM_IISOOXFRM_Pos) /*!< 0x00200000 */ -#define GINTMSK_PXFRM_IISOOXFRM GINTMSK_PXFRM_IISOOXFRM_Msk /*!< Incomplete periodic transfer mask */ +#define GINTMSK_PXFRM_IISOOXFRM_Msk (0x1UL << GINTMSK_PXFRM_IISOOXFRM_Pos) // 0x00200000 */ +#define GINTMSK_PXFRM_IISOOXFRM GINTMSK_PXFRM_IISOOXFRM_Msk // Incomplete periodic transfer mask */ #define GINTMSK_FSUSPM_Pos (22U) -#define GINTMSK_FSUSPM_Msk (0x1UL << GINTMSK_FSUSPM_Pos) /*!< 0x00400000 */ -#define GINTMSK_FSUSPM GINTMSK_FSUSPM_Msk /*!< Data fetch suspended mask */ +#define GINTMSK_FSUSPM_Msk (0x1UL << GINTMSK_FSUSPM_Pos) // 0x00400000 */ +#define GINTMSK_FSUSPM GINTMSK_FSUSPM_Msk // Data fetch suspended mask */ #define GINTMSK_RSTDEM_Pos (23U) -#define GINTMSK_RSTDEM_Msk (0x1UL << GINTMSK_RSTDEM_Pos) /*!< 0x00800000 */ -#define GINTMSK_RSTDEM GINTMSK_RSTDEM_Msk /*!< Reset detected interrupt mask */ +#define GINTMSK_RSTDEM_Msk (0x1UL << GINTMSK_RSTDEM_Pos) // 0x00800000 */ +#define GINTMSK_RSTDEM GINTMSK_RSTDEM_Msk // Reset detected interrupt mask */ #define GINTMSK_PRTIM_Pos (24U) -#define GINTMSK_PRTIM_Msk (0x1UL << GINTMSK_PRTIM_Pos) /*!< 0x01000000 */ -#define GINTMSK_PRTIM GINTMSK_PRTIM_Msk /*!< Host port interrupt mask */ +#define GINTMSK_PRTIM_Msk (0x1UL << GINTMSK_PRTIM_Pos) // 0x01000000 */ +#define GINTMSK_PRTIM GINTMSK_PRTIM_Msk // Host port interrupt mask */ #define GINTMSK_HCIM_Pos (25U) -#define GINTMSK_HCIM_Msk (0x1UL << GINTMSK_HCIM_Pos) /*!< 0x02000000 */ -#define GINTMSK_HCIM GINTMSK_HCIM_Msk /*!< Host channels interrupt mask */ +#define GINTMSK_HCIM_Msk (0x1UL << GINTMSK_HCIM_Pos) // 0x02000000 */ +#define GINTMSK_HCIM GINTMSK_HCIM_Msk // Host channels interrupt mask */ #define GINTMSK_PTXFEM_Pos (26U) -#define GINTMSK_PTXFEM_Msk (0x1UL << GINTMSK_PTXFEM_Pos) /*!< 0x04000000 */ -#define GINTMSK_PTXFEM GINTMSK_PTXFEM_Msk /*!< Periodic TxFIFO empty mask */ +#define GINTMSK_PTXFEM_Msk (0x1UL << GINTMSK_PTXFEM_Pos) // 0x04000000 */ +#define GINTMSK_PTXFEM GINTMSK_PTXFEM_Msk // Periodic TxFIFO empty mask */ #define GINTMSK_LPMINTM_Pos (27U) -#define GINTMSK_LPMINTM_Msk (0x1UL << GINTMSK_LPMINTM_Pos) /*!< 0x08000000 */ -#define GINTMSK_LPMINTM GINTMSK_LPMINTM_Msk /*!< LPM interrupt Mask */ +#define GINTMSK_LPMINTM_Msk (0x1UL << GINTMSK_LPMINTM_Pos) // 0x08000000 */ +#define GINTMSK_LPMINTM GINTMSK_LPMINTM_Msk // LPM interrupt Mask */ #define GINTMSK_CIDSCHGM_Pos (28U) -#define GINTMSK_CIDSCHGM_Msk (0x1UL << GINTMSK_CIDSCHGM_Pos) /*!< 0x10000000 */ -#define GINTMSK_CIDSCHGM GINTMSK_CIDSCHGM_Msk /*!< Connector ID status change mask */ +#define GINTMSK_CIDSCHGM_Msk (0x1UL << GINTMSK_CIDSCHGM_Pos) // 0x10000000 */ +#define GINTMSK_CIDSCHGM GINTMSK_CIDSCHGM_Msk // Connector ID status change mask */ #define GINTMSK_DISCINT_Pos (29U) -#define GINTMSK_DISCINT_Msk (0x1UL << GINTMSK_DISCINT_Pos) /*!< 0x20000000 */ -#define GINTMSK_DISCINT GINTMSK_DISCINT_Msk /*!< Disconnect detected interrupt mask */ +#define GINTMSK_DISCINT_Msk (0x1UL << GINTMSK_DISCINT_Pos) // 0x20000000 */ +#define GINTMSK_DISCINT GINTMSK_DISCINT_Msk // Disconnect detected interrupt mask */ #define GINTMSK_SRQIM_Pos (30U) -#define GINTMSK_SRQIM_Msk (0x1UL << GINTMSK_SRQIM_Pos) /*!< 0x40000000 */ -#define GINTMSK_SRQIM GINTMSK_SRQIM_Msk /*!< Session request/new session detected interrupt mask */ +#define GINTMSK_SRQIM_Msk (0x1UL << GINTMSK_SRQIM_Pos) // 0x40000000 */ +#define GINTMSK_SRQIM GINTMSK_SRQIM_Msk // Session request/new session detected interrupt mask */ #define GINTMSK_WUIM_Pos (31U) -#define GINTMSK_WUIM_Msk (0x1UL << GINTMSK_WUIM_Pos) /*!< 0x80000000 */ -#define GINTMSK_WUIM GINTMSK_WUIM_Msk /*!< Resume/remote wakeup detected interrupt mask */ +#define GINTMSK_WUIM_Msk (0x1UL << GINTMSK_WUIM_Pos) // 0x80000000 */ +#define GINTMSK_WUIM GINTMSK_WUIM_Msk // Resume/remote wakeup detected interrupt mask */ /******************** Bit definition for DAINT register ********************/ #define DAINT_IEPINT_Pos (0U) -#define DAINT_IEPINT_Msk (0xFFFFUL << DAINT_IEPINT_Pos) /*!< 0x0000FFFF */ -#define DAINT_IEPINT DAINT_IEPINT_Msk /*!< IN endpoint interrupt bits */ +#define DAINT_IEPINT_Msk (0xFFFFUL << DAINT_IEPINT_Pos) // 0x0000FFFF */ +#define DAINT_IEPINT DAINT_IEPINT_Msk // IN endpoint interrupt bits */ #define DAINT_OEPINT_Pos (16U) -#define DAINT_OEPINT_Msk (0xFFFFUL << DAINT_OEPINT_Pos) /*!< 0xFFFF0000 */ -#define DAINT_OEPINT DAINT_OEPINT_Msk /*!< OUT endpoint interrupt bits */ +#define DAINT_OEPINT_Msk (0xFFFFUL << DAINT_OEPINT_Pos) // 0xFFFF0000 */ +#define DAINT_OEPINT DAINT_OEPINT_Msk // OUT endpoint interrupt bits */ /******************** Bit definition for HAINTMSK register ********************/ #define HAINTMSK_HAINTM_Pos (0U) -#define HAINTMSK_HAINTM_Msk (0xFFFFUL << HAINTMSK_HAINTM_Pos) /*!< 0x0000FFFF */ -#define HAINTMSK_HAINTM HAINTMSK_HAINTM_Msk /*!< Channel interrupt mask */ +#define HAINTMSK_HAINTM_Msk (0xFFFFUL << HAINTMSK_HAINTM_Pos) // 0x0000FFFF */ +#define HAINTMSK_HAINTM HAINTMSK_HAINTM_Msk // Channel interrupt mask */ /******************** Bit definition for GRXSTSP register ********************/ #define GRXSTSP_EPNUM_Pos (0U) -#define GRXSTSP_EPNUM_Msk (0xFUL << GRXSTSP_EPNUM_Pos) /*!< 0x0000000F */ -#define GRXSTSP_EPNUM GRXSTSP_EPNUM_Msk /*!< IN EP interrupt mask bits */ +#define GRXSTSP_EPNUM_Msk (0xFUL << GRXSTSP_EPNUM_Pos) // 0x0000000F */ +#define GRXSTSP_EPNUM GRXSTSP_EPNUM_Msk // IN EP interrupt mask bits */ #define GRXSTSP_BCNT_Pos (4U) -#define GRXSTSP_BCNT_Msk (0x7FFUL << GRXSTSP_BCNT_Pos) /*!< 0x00007FF0 */ -#define GRXSTSP_BCNT GRXSTSP_BCNT_Msk /*!< OUT EP interrupt mask bits */ +#define GRXSTSP_BCNT_Msk (0x7FFUL << GRXSTSP_BCNT_Pos) // 0x00007FF0 */ +#define GRXSTSP_BCNT GRXSTSP_BCNT_Msk // OUT EP interrupt mask bits */ #define GRXSTSP_DPID_Pos (15U) -#define GRXSTSP_DPID_Msk (0x3UL << GRXSTSP_DPID_Pos) /*!< 0x00018000 */ -#define GRXSTSP_DPID GRXSTSP_DPID_Msk /*!< OUT EP interrupt mask bits */ +#define GRXSTSP_DPID_Msk (0x3UL << GRXSTSP_DPID_Pos) // 0x00018000 */ +#define GRXSTSP_DPID GRXSTSP_DPID_Msk // OUT EP interrupt mask bits */ #define GRXSTSP_PKTSTS_Pos (17U) -#define GRXSTSP_PKTSTS_Msk (0xFUL << GRXSTSP_PKTSTS_Pos) /*!< 0x001E0000 */ -#define GRXSTSP_PKTSTS GRXSTSP_PKTSTS_Msk /*!< OUT EP interrupt mask bits */ +#define GRXSTSP_PKTSTS_Msk (0xFUL << GRXSTSP_PKTSTS_Pos) // 0x001E0000 */ +#define GRXSTSP_PKTSTS GRXSTSP_PKTSTS_Msk // OUT EP interrupt mask bits */ /******************** Bit definition for DAINTMSK register ********************/ #define DAINTMSK_IEPM_Pos (0U) -#define DAINTMSK_IEPM_Msk (0xFFFFUL << DAINTMSK_IEPM_Pos) /*!< 0x0000FFFF */ -#define DAINTMSK_IEPM DAINTMSK_IEPM_Msk /*!< IN EP interrupt mask bits */ +#define DAINTMSK_IEPM_Msk (0xFFFFUL << DAINTMSK_IEPM_Pos) // 0x0000FFFF */ +#define DAINTMSK_IEPM DAINTMSK_IEPM_Msk // IN EP interrupt mask bits */ #define DAINTMSK_OEPM_Pos (16U) -#define DAINTMSK_OEPM_Msk (0xFFFFUL << DAINTMSK_OEPM_Pos) /*!< 0xFFFF0000 */ -#define DAINTMSK_OEPM DAINTMSK_OEPM_Msk /*!< OUT EP interrupt mask bits */ +#define DAINTMSK_OEPM_Msk (0xFFFFUL << DAINTMSK_OEPM_Pos) // 0xFFFF0000 */ +#define DAINTMSK_OEPM DAINTMSK_OEPM_Msk // OUT EP interrupt mask bits */ /******************** Bit definition for OTG register ********************/ #define CHNUM_Pos (0U) -#define CHNUM_Msk (0xFUL << CHNUM_Pos) /*!< 0x0000000F */ -#define CHNUM CHNUM_Msk /*!< Channel number */ -#define CHNUM_0 (0x1UL << CHNUM_Pos) /*!< 0x00000001 */ -#define CHNUM_1 (0x2UL << CHNUM_Pos) /*!< 0x00000002 */ -#define CHNUM_2 (0x4UL << CHNUM_Pos) /*!< 0x00000004 */ -#define CHNUM_3 (0x8UL << CHNUM_Pos) /*!< 0x00000008 */ +#define CHNUM_Msk (0xFUL << CHNUM_Pos) // 0x0000000F */ +#define CHNUM CHNUM_Msk // Channel number */ +#define CHNUM_0 (0x1UL << CHNUM_Pos) // 0x00000001 */ +#define CHNUM_1 (0x2UL << CHNUM_Pos) // 0x00000002 */ +#define CHNUM_2 (0x4UL << CHNUM_Pos) // 0x00000004 */ +#define CHNUM_3 (0x8UL << CHNUM_Pos) // 0x00000008 */ #define BCNT_Pos (4U) -#define BCNT_Msk (0x7FFUL << BCNT_Pos) /*!< 0x00007FF0 */ -#define BCNT BCNT_Msk /*!< Byte count */ +#define BCNT_Msk (0x7FFUL << BCNT_Pos) // 0x00007FF0 */ +#define BCNT BCNT_Msk // Byte count */ #define DPID_Pos (15U) -#define DPID_Msk (0x3UL << DPID_Pos) /*!< 0x00018000 */ -#define DPID DPID_Msk /*!< Data PID */ -#define DPID_0 (0x1UL << DPID_Pos) /*!< 0x00008000 */ -#define DPID_1 (0x2UL << DPID_Pos) /*!< 0x00010000 */ +#define DPID_Msk (0x3UL << DPID_Pos) // 0x00018000 */ +#define DPID DPID_Msk // Data PID */ +#define DPID_0 (0x1UL << DPID_Pos) // 0x00008000 */ +#define DPID_1 (0x2UL << DPID_Pos) // 0x00010000 */ #define PKTSTS_Pos (17U) -#define PKTSTS_Msk (0xFUL << PKTSTS_Pos) /*!< 0x001E0000 */ -#define PKTSTS PKTSTS_Msk /*!< Packet status */ -#define PKTSTS_0 (0x1UL << PKTSTS_Pos) /*!< 0x00020000 */ -#define PKTSTS_1 (0x2UL << PKTSTS_Pos) /*!< 0x00040000 */ -#define PKTSTS_2 (0x4UL << PKTSTS_Pos) /*!< 0x00080000 */ -#define PKTSTS_3 (0x8UL << PKTSTS_Pos) /*!< 0x00100000 */ +#define PKTSTS_Msk (0xFUL << PKTSTS_Pos) // 0x001E0000 */ +#define PKTSTS PKTSTS_Msk // Packet status */ +#define PKTSTS_0 (0x1UL << PKTSTS_Pos) // 0x00020000 */ +#define PKTSTS_1 (0x2UL << PKTSTS_Pos) // 0x00040000 */ +#define PKTSTS_2 (0x4UL << PKTSTS_Pos) // 0x00080000 */ +#define PKTSTS_3 (0x8UL << PKTSTS_Pos) // 0x00100000 */ #define EPNUM_Pos (0U) -#define EPNUM_Msk (0xFUL << EPNUM_Pos) /*!< 0x0000000F */ -#define EPNUM EPNUM_Msk /*!< Endpoint number */ -#define EPNUM_0 (0x1UL << EPNUM_Pos) /*!< 0x00000001 */ -#define EPNUM_1 (0x2UL << EPNUM_Pos) /*!< 0x00000002 */ -#define EPNUM_2 (0x4UL << EPNUM_Pos) /*!< 0x00000004 */ -#define EPNUM_3 (0x8UL << EPNUM_Pos) /*!< 0x00000008 */ +#define EPNUM_Msk (0xFUL << EPNUM_Pos) // 0x0000000F */ +#define EPNUM EPNUM_Msk // Endpoint number */ +#define EPNUM_0 (0x1UL << EPNUM_Pos) // 0x00000001 */ +#define EPNUM_1 (0x2UL << EPNUM_Pos) // 0x00000002 */ +#define EPNUM_2 (0x4UL << EPNUM_Pos) // 0x00000004 */ +#define EPNUM_3 (0x8UL << EPNUM_Pos) // 0x00000008 */ #define FRMNUM_Pos (21U) -#define FRMNUM_Msk (0xFUL << FRMNUM_Pos) /*!< 0x01E00000 */ -#define FRMNUM FRMNUM_Msk /*!< Frame number */ -#define FRMNUM_0 (0x1UL << FRMNUM_Pos) /*!< 0x00200000 */ -#define FRMNUM_1 (0x2UL << FRMNUM_Pos) /*!< 0x00400000 */ -#define FRMNUM_2 (0x4UL << FRMNUM_Pos) /*!< 0x00800000 */ -#define FRMNUM_3 (0x8UL << FRMNUM_Pos) /*!< 0x01000000 */ +#define FRMNUM_Msk (0xFUL << FRMNUM_Pos) // 0x01E00000 */ +#define FRMNUM FRMNUM_Msk // Frame number */ +#define FRMNUM_0 (0x1UL << FRMNUM_Pos) // 0x00200000 */ +#define FRMNUM_1 (0x2UL << FRMNUM_Pos) // 0x00400000 */ +#define FRMNUM_2 (0x4UL << FRMNUM_Pos) // 0x00800000 */ +#define FRMNUM_3 (0x8UL << FRMNUM_Pos) // 0x01000000 */ /******************** Bit definition for GRXFSIZ register ********************/ #define GRXFSIZ_RXFD_Pos (0U) -#define GRXFSIZ_RXFD_Msk (0xFFFFUL << GRXFSIZ_RXFD_Pos) /*!< 0x0000FFFF */ -#define GRXFSIZ_RXFD GRXFSIZ_RXFD_Msk /*!< RxFIFO depth */ +#define GRXFSIZ_RXFD_Msk (0xFFFFUL << GRXFSIZ_RXFD_Pos) // 0x0000FFFF */ +#define GRXFSIZ_RXFD GRXFSIZ_RXFD_Msk // RxFIFO depth */ /******************** Bit definition for DVBUSDIS register ********************/ #define DVBUSDIS_VBUSDT_Pos (0U) -#define DVBUSDIS_VBUSDT_Msk (0xFFFFUL << DVBUSDIS_VBUSDT_Pos) /*!< 0x0000FFFF */ -#define DVBUSDIS_VBUSDT DVBUSDIS_VBUSDT_Msk /*!< Device VBUS discharge time */ +#define DVBUSDIS_VBUSDT_Msk (0xFFFFUL << DVBUSDIS_VBUSDT_Pos) // 0x0000FFFF */ +#define DVBUSDIS_VBUSDT DVBUSDIS_VBUSDT_Msk // Device VBUS discharge time */ /******************** Bit definition for OTG register ********************/ #define NPTXFSA_Pos (0U) -#define NPTXFSA_Msk (0xFFFFUL << NPTXFSA_Pos) /*!< 0x0000FFFF */ -#define NPTXFSA NPTXFSA_Msk /*!< Nonperiodic transmit RAM start address */ +#define NPTXFSA_Msk (0xFFFFUL << NPTXFSA_Pos) // 0x0000FFFF */ +#define NPTXFSA NPTXFSA_Msk // Nonperiodic transmit RAM start address */ #define NPTXFD_Pos (16U) -#define NPTXFD_Msk (0xFFFFUL << NPTXFD_Pos) /*!< 0xFFFF0000 */ -#define NPTXFD NPTXFD_Msk /*!< Nonperiodic TxFIFO depth */ +#define NPTXFD_Msk (0xFFFFUL << NPTXFD_Pos) // 0xFFFF0000 */ +#define NPTXFD NPTXFD_Msk // Nonperiodic TxFIFO depth */ #define TX0FSA_Pos (0U) -#define TX0FSA_Msk (0xFFFFUL << TX0FSA_Pos) /*!< 0x0000FFFF */ -#define TX0FSA TX0FSA_Msk /*!< Endpoint 0 transmit RAM start address */ +#define TX0FSA_Msk (0xFFFFUL << TX0FSA_Pos) // 0x0000FFFF */ +#define TX0FSA TX0FSA_Msk // Endpoint 0 transmit RAM start address */ #define TX0FD_Pos (16U) -#define TX0FD_Msk (0xFFFFUL << TX0FD_Pos) /*!< 0xFFFF0000 */ -#define TX0FD TX0FD_Msk /*!< Endpoint 0 TxFIFO depth */ +#define TX0FD_Msk (0xFFFFUL << TX0FD_Pos) // 0xFFFF0000 */ +#define TX0FD TX0FD_Msk // Endpoint 0 TxFIFO depth */ /******************** Bit definition for DVBUSPULSE register ********************/ #define DVBUSPULSE_DVBUSP_Pos (0U) -#define DVBUSPULSE_DVBUSP_Msk (0xFFFUL << DVBUSPULSE_DVBUSP_Pos) /*!< 0x00000FFF */ -#define DVBUSPULSE_DVBUSP DVBUSPULSE_DVBUSP_Msk /*!< Device VBUS pulsing time */ +#define DVBUSPULSE_DVBUSP_Msk (0xFFFUL << DVBUSPULSE_DVBUSP_Pos) // 0x00000FFF */ +#define DVBUSPULSE_DVBUSP DVBUSPULSE_DVBUSP_Msk // Device VBUS pulsing time */ /******************** Bit definition for GNPTXSTS register ********************/ #define GNPTXSTS_NPTXFSAV_Pos (0U) -#define GNPTXSTS_NPTXFSAV_Msk (0xFFFFUL << GNPTXSTS_NPTXFSAV_Pos) /*!< 0x0000FFFF */ -#define GNPTXSTS_NPTXFSAV GNPTXSTS_NPTXFSAV_Msk /*!< Nonperiodic TxFIFO space available */ +#define GNPTXSTS_NPTXFSAV_Msk (0xFFFFUL << GNPTXSTS_NPTXFSAV_Pos) // 0x0000FFFF */ +#define GNPTXSTS_NPTXFSAV GNPTXSTS_NPTXFSAV_Msk // Nonperiodic TxFIFO space available */ #define GNPTXSTS_NPTQXSAV_Pos (16U) -#define GNPTXSTS_NPTQXSAV_Msk (0xFFUL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00FF0000 */ -#define GNPTXSTS_NPTQXSAV GNPTXSTS_NPTQXSAV_Msk /*!< Nonperiodic transmit request queue space available */ -#define GNPTXSTS_NPTQXSAV_0 (0x01UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00010000 */ -#define GNPTXSTS_NPTQXSAV_1 (0x02UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00020000 */ -#define GNPTXSTS_NPTQXSAV_2 (0x04UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00040000 */ -#define GNPTXSTS_NPTQXSAV_3 (0x08UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00080000 */ -#define GNPTXSTS_NPTQXSAV_4 (0x10UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00100000 */ -#define GNPTXSTS_NPTQXSAV_5 (0x20UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00200000 */ -#define GNPTXSTS_NPTQXSAV_6 (0x40UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00400000 */ -#define GNPTXSTS_NPTQXSAV_7 (0x80UL << GNPTXSTS_NPTQXSAV_Pos) /*!< 0x00800000 */ +#define GNPTXSTS_NPTQXSAV_Msk (0xFFUL << GNPTXSTS_NPTQXSAV_Pos) // 0x00FF0000 */ +#define GNPTXSTS_NPTQXSAV GNPTXSTS_NPTQXSAV_Msk // Nonperiodic transmit request queue space available */ +#define GNPTXSTS_NPTQXSAV_0 (0x01UL << GNPTXSTS_NPTQXSAV_Pos) // 0x00010000 */ +#define GNPTXSTS_NPTQXSAV_1 (0x02UL << GNPTXSTS_NPTQXSAV_Pos) // 0x00020000 */ +#define GNPTXSTS_NPTQXSAV_2 (0x04UL << GNPTXSTS_NPTQXSAV_Pos) // 0x00040000 */ +#define GNPTXSTS_NPTQXSAV_3 (0x08UL << GNPTXSTS_NPTQXSAV_Pos) // 0x00080000 */ +#define GNPTXSTS_NPTQXSAV_4 (0x10UL << GNPTXSTS_NPTQXSAV_Pos) // 0x00100000 */ +#define GNPTXSTS_NPTQXSAV_5 (0x20UL << GNPTXSTS_NPTQXSAV_Pos) // 0x00200000 */ +#define GNPTXSTS_NPTQXSAV_6 (0x40UL << GNPTXSTS_NPTQXSAV_Pos) // 0x00400000 */ +#define GNPTXSTS_NPTQXSAV_7 (0x80UL << GNPTXSTS_NPTQXSAV_Pos) // 0x00800000 */ #define GNPTXSTS_NPTXQTOP_Pos (24U) -#define GNPTXSTS_NPTXQTOP_Msk (0x7FUL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x7F000000 */ -#define GNPTXSTS_NPTXQTOP GNPTXSTS_NPTXQTOP_Msk /*!< Top of the nonperiodic transmit request queue */ -#define GNPTXSTS_NPTXQTOP_0 (0x01UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x01000000 */ -#define GNPTXSTS_NPTXQTOP_1 (0x02UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x02000000 */ -#define GNPTXSTS_NPTXQTOP_2 (0x04UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x04000000 */ -#define GNPTXSTS_NPTXQTOP_3 (0x08UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x08000000 */ -#define GNPTXSTS_NPTXQTOP_4 (0x10UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x10000000 */ -#define GNPTXSTS_NPTXQTOP_5 (0x20UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x20000000 */ -#define GNPTXSTS_NPTXQTOP_6 (0x40UL << GNPTXSTS_NPTXQTOP_Pos) /*!< 0x40000000 */ +#define GNPTXSTS_NPTXQTOP_Msk (0x7FUL << GNPTXSTS_NPTXQTOP_Pos) // 0x7F000000 */ +#define GNPTXSTS_NPTXQTOP GNPTXSTS_NPTXQTOP_Msk // Top of the nonperiodic transmit request queue */ +#define GNPTXSTS_NPTXQTOP_0 (0x01UL << GNPTXSTS_NPTXQTOP_Pos) // 0x01000000 */ +#define GNPTXSTS_NPTXQTOP_1 (0x02UL << GNPTXSTS_NPTXQTOP_Pos) // 0x02000000 */ +#define GNPTXSTS_NPTXQTOP_2 (0x04UL << GNPTXSTS_NPTXQTOP_Pos) // 0x04000000 */ +#define GNPTXSTS_NPTXQTOP_3 (0x08UL << GNPTXSTS_NPTXQTOP_Pos) // 0x08000000 */ +#define GNPTXSTS_NPTXQTOP_4 (0x10UL << GNPTXSTS_NPTXQTOP_Pos) // 0x10000000 */ +#define GNPTXSTS_NPTXQTOP_5 (0x20UL << GNPTXSTS_NPTXQTOP_Pos) // 0x20000000 */ +#define GNPTXSTS_NPTXQTOP_6 (0x40UL << GNPTXSTS_NPTXQTOP_Pos) // 0x40000000 */ /******************** Bit definition for DTHRCTL register ********************/ #define DTHRCTL_NONISOTHREN_Pos (0U) -#define DTHRCTL_NONISOTHREN_Msk (0x1UL << DTHRCTL_NONISOTHREN_Pos) /*!< 0x00000001 */ -#define DTHRCTL_NONISOTHREN DTHRCTL_NONISOTHREN_Msk /*!< Nonisochronous IN endpoints threshold enable */ +#define DTHRCTL_NONISOTHREN_Msk (0x1UL << DTHRCTL_NONISOTHREN_Pos) // 0x00000001 */ +#define DTHRCTL_NONISOTHREN DTHRCTL_NONISOTHREN_Msk // Nonisochronous IN endpoints threshold enable */ #define DTHRCTL_ISOTHREN_Pos (1U) -#define DTHRCTL_ISOTHREN_Msk (0x1UL << DTHRCTL_ISOTHREN_Pos) /*!< 0x00000002 */ -#define DTHRCTL_ISOTHREN DTHRCTL_ISOTHREN_Msk /*!< ISO IN endpoint threshold enable */ +#define DTHRCTL_ISOTHREN_Msk (0x1UL << DTHRCTL_ISOTHREN_Pos) // 0x00000002 */ +#define DTHRCTL_ISOTHREN DTHRCTL_ISOTHREN_Msk // ISO IN endpoint threshold enable */ #define DTHRCTL_TXTHRLEN_Pos (2U) -#define DTHRCTL_TXTHRLEN_Msk (0x1FFUL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x000007FC */ -#define DTHRCTL_TXTHRLEN DTHRCTL_TXTHRLEN_Msk /*!< Transmit threshold length */ -#define DTHRCTL_TXTHRLEN_0 (0x001UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000004 */ -#define DTHRCTL_TXTHRLEN_1 (0x002UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000008 */ -#define DTHRCTL_TXTHRLEN_2 (0x004UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000010 */ -#define DTHRCTL_TXTHRLEN_3 (0x008UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000020 */ -#define DTHRCTL_TXTHRLEN_4 (0x010UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000040 */ -#define DTHRCTL_TXTHRLEN_5 (0x020UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000080 */ -#define DTHRCTL_TXTHRLEN_6 (0x040UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000100 */ -#define DTHRCTL_TXTHRLEN_7 (0x080UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000200 */ -#define DTHRCTL_TXTHRLEN_8 (0x100UL << DTHRCTL_TXTHRLEN_Pos) /*!< 0x00000400 */ +#define DTHRCTL_TXTHRLEN_Msk (0x1FFUL << DTHRCTL_TXTHRLEN_Pos) // 0x000007FC */ +#define DTHRCTL_TXTHRLEN DTHRCTL_TXTHRLEN_Msk // Transmit threshold length */ +#define DTHRCTL_TXTHRLEN_0 (0x001UL << DTHRCTL_TXTHRLEN_Pos) // 0x00000004 */ +#define DTHRCTL_TXTHRLEN_1 (0x002UL << DTHRCTL_TXTHRLEN_Pos) // 0x00000008 */ +#define DTHRCTL_TXTHRLEN_2 (0x004UL << DTHRCTL_TXTHRLEN_Pos) // 0x00000010 */ +#define DTHRCTL_TXTHRLEN_3 (0x008UL << DTHRCTL_TXTHRLEN_Pos) // 0x00000020 */ +#define DTHRCTL_TXTHRLEN_4 (0x010UL << DTHRCTL_TXTHRLEN_Pos) // 0x00000040 */ +#define DTHRCTL_TXTHRLEN_5 (0x020UL << DTHRCTL_TXTHRLEN_Pos) // 0x00000080 */ +#define DTHRCTL_TXTHRLEN_6 (0x040UL << DTHRCTL_TXTHRLEN_Pos) // 0x00000100 */ +#define DTHRCTL_TXTHRLEN_7 (0x080UL << DTHRCTL_TXTHRLEN_Pos) // 0x00000200 */ +#define DTHRCTL_TXTHRLEN_8 (0x100UL << DTHRCTL_TXTHRLEN_Pos) // 0x00000400 */ #define DTHRCTL_RXTHREN_Pos (16U) -#define DTHRCTL_RXTHREN_Msk (0x1UL << DTHRCTL_RXTHREN_Pos) /*!< 0x00010000 */ -#define DTHRCTL_RXTHREN DTHRCTL_RXTHREN_Msk /*!< Receive threshold enable */ +#define DTHRCTL_RXTHREN_Msk (0x1UL << DTHRCTL_RXTHREN_Pos) // 0x00010000 */ +#define DTHRCTL_RXTHREN DTHRCTL_RXTHREN_Msk // Receive threshold enable */ #define DTHRCTL_RXTHRLEN_Pos (17U) -#define DTHRCTL_RXTHRLEN_Msk (0x1FFUL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x03FE0000 */ -#define DTHRCTL_RXTHRLEN DTHRCTL_RXTHRLEN_Msk /*!< Receive threshold length */ -#define DTHRCTL_RXTHRLEN_0 (0x001UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00020000 */ -#define DTHRCTL_RXTHRLEN_1 (0x002UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00040000 */ -#define DTHRCTL_RXTHRLEN_2 (0x004UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00080000 */ -#define DTHRCTL_RXTHRLEN_3 (0x008UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00100000 */ -#define DTHRCTL_RXTHRLEN_4 (0x010UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00200000 */ -#define DTHRCTL_RXTHRLEN_5 (0x020UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00400000 */ -#define DTHRCTL_RXTHRLEN_6 (0x040UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x00800000 */ -#define DTHRCTL_RXTHRLEN_7 (0x080UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x01000000 */ -#define DTHRCTL_RXTHRLEN_8 (0x100UL << DTHRCTL_RXTHRLEN_Pos) /*!< 0x02000000 */ +#define DTHRCTL_RXTHRLEN_Msk (0x1FFUL << DTHRCTL_RXTHRLEN_Pos) // 0x03FE0000 */ +#define DTHRCTL_RXTHRLEN DTHRCTL_RXTHRLEN_Msk // Receive threshold length */ +#define DTHRCTL_RXTHRLEN_0 (0x001UL << DTHRCTL_RXTHRLEN_Pos) // 0x00020000 */ +#define DTHRCTL_RXTHRLEN_1 (0x002UL << DTHRCTL_RXTHRLEN_Pos) // 0x00040000 */ +#define DTHRCTL_RXTHRLEN_2 (0x004UL << DTHRCTL_RXTHRLEN_Pos) // 0x00080000 */ +#define DTHRCTL_RXTHRLEN_3 (0x008UL << DTHRCTL_RXTHRLEN_Pos) // 0x00100000 */ +#define DTHRCTL_RXTHRLEN_4 (0x010UL << DTHRCTL_RXTHRLEN_Pos) // 0x00200000 */ +#define DTHRCTL_RXTHRLEN_5 (0x020UL << DTHRCTL_RXTHRLEN_Pos) // 0x00400000 */ +#define DTHRCTL_RXTHRLEN_6 (0x040UL << DTHRCTL_RXTHRLEN_Pos) // 0x00800000 */ +#define DTHRCTL_RXTHRLEN_7 (0x080UL << DTHRCTL_RXTHRLEN_Pos) // 0x01000000 */ +#define DTHRCTL_RXTHRLEN_8 (0x100UL << DTHRCTL_RXTHRLEN_Pos) // 0x02000000 */ #define DTHRCTL_ARPEN_Pos (27U) -#define DTHRCTL_ARPEN_Msk (0x1UL << DTHRCTL_ARPEN_Pos) /*!< 0x08000000 */ -#define DTHRCTL_ARPEN DTHRCTL_ARPEN_Msk /*!< Arbiter parking enable */ +#define DTHRCTL_ARPEN_Msk (0x1UL << DTHRCTL_ARPEN_Pos) // 0x08000000 */ +#define DTHRCTL_ARPEN DTHRCTL_ARPEN_Msk // Arbiter parking enable */ /******************** Bit definition for DIEPEMPMSK register ********************/ #define DIEPEMPMSK_INEPTXFEM_Pos (0U) -#define DIEPEMPMSK_INEPTXFEM_Msk (0xFFFFUL << DIEPEMPMSK_INEPTXFEM_Pos) /*!< 0x0000FFFF */ -#define DIEPEMPMSK_INEPTXFEM DIEPEMPMSK_INEPTXFEM_Msk /*!< IN EP Tx FIFO empty interrupt mask bits */ +#define DIEPEMPMSK_INEPTXFEM_Msk (0xFFFFUL << DIEPEMPMSK_INEPTXFEM_Pos) // 0x0000FFFF */ +#define DIEPEMPMSK_INEPTXFEM DIEPEMPMSK_INEPTXFEM_Msk // IN EP Tx FIFO empty interrupt mask bits */ /******************** Bit definition for DEACHINT register ********************/ #define DEACHINT_IEP1INT_Pos (1U) -#define DEACHINT_IEP1INT_Msk (0x1UL << DEACHINT_IEP1INT_Pos) /*!< 0x00000002 */ -#define DEACHINT_IEP1INT DEACHINT_IEP1INT_Msk /*!< IN endpoint 1interrupt bit */ +#define DEACHINT_IEP1INT_Msk (0x1UL << DEACHINT_IEP1INT_Pos) // 0x00000002 */ +#define DEACHINT_IEP1INT DEACHINT_IEP1INT_Msk // IN endpoint 1interrupt bit */ #define DEACHINT_OEP1INT_Pos (17U) -#define DEACHINT_OEP1INT_Msk (0x1UL << DEACHINT_OEP1INT_Pos) /*!< 0x00020000 */ -#define DEACHINT_OEP1INT DEACHINT_OEP1INT_Msk /*!< OUT endpoint 1 interrupt bit */ +#define DEACHINT_OEP1INT_Msk (0x1UL << DEACHINT_OEP1INT_Pos) // 0x00020000 */ +#define DEACHINT_OEP1INT DEACHINT_OEP1INT_Msk // OUT endpoint 1 interrupt bit */ /******************** Bit definition for GCCFG register ********************/ #define GCCFG_DCDET_Pos (0U) -#define GCCFG_DCDET_Msk (0x1UL << GCCFG_DCDET_Pos) /*!< 0x00000001 */ -#define GCCFG_DCDET GCCFG_DCDET_Msk /*!< Data contact detection (DCD) status */ +#define GCCFG_DCDET_Msk (0x1UL << GCCFG_DCDET_Pos) // 0x00000001 */ +#define GCCFG_DCDET GCCFG_DCDET_Msk // Data contact detection (DCD) status */ #define GCCFG_PDET_Pos (1U) -#define GCCFG_PDET_Msk (0x1UL << GCCFG_PDET_Pos) /*!< 0x00000002 */ -#define GCCFG_PDET GCCFG_PDET_Msk /*!< Primary detection (PD) status */ +#define GCCFG_PDET_Msk (0x1UL << GCCFG_PDET_Pos) // 0x00000002 */ +#define GCCFG_PDET GCCFG_PDET_Msk // Primary detection (PD) status */ #define GCCFG_SDET_Pos (2U) -#define GCCFG_SDET_Msk (0x1UL << GCCFG_SDET_Pos) /*!< 0x00000004 */ -#define GCCFG_SDET GCCFG_SDET_Msk /*!< Secondary detection (SD) status */ +#define GCCFG_SDET_Msk (0x1UL << GCCFG_SDET_Pos) // 0x00000004 */ +#define GCCFG_SDET GCCFG_SDET_Msk // Secondary detection (SD) status */ #define GCCFG_PS2DET_Pos (3U) -#define GCCFG_PS2DET_Msk (0x1UL << GCCFG_PS2DET_Pos) /*!< 0x00000008 */ -#define GCCFG_PS2DET GCCFG_PS2DET_Msk /*!< DM pull-up detection status */ +#define GCCFG_PS2DET_Msk (0x1UL << GCCFG_PS2DET_Pos) // 0x00000008 */ +#define GCCFG_PS2DET GCCFG_PS2DET_Msk // DM pull-up detection status */ #define GCCFG_PWRDWN_Pos (16U) -#define GCCFG_PWRDWN_Msk (0x1UL << GCCFG_PWRDWN_Pos) /*!< 0x00010000 */ -#define GCCFG_PWRDWN GCCFG_PWRDWN_Msk /*!< Power down */ +#define GCCFG_PWRDWN_Msk (0x1UL << GCCFG_PWRDWN_Pos) // 0x00010000 */ +#define GCCFG_PWRDWN GCCFG_PWRDWN_Msk // Power down */ #define GCCFG_BCDEN_Pos (17U) -#define GCCFG_BCDEN_Msk (0x1UL << GCCFG_BCDEN_Pos) /*!< 0x00020000 */ -#define GCCFG_BCDEN GCCFG_BCDEN_Msk /*!< Battery charging detector (BCD) enable */ +#define GCCFG_BCDEN_Msk (0x1UL << GCCFG_BCDEN_Pos) // 0x00020000 */ +#define GCCFG_BCDEN GCCFG_BCDEN_Msk // Battery charging detector (BCD) enable */ #define GCCFG_DCDEN_Pos (18U) -#define GCCFG_DCDEN_Msk (0x1UL << GCCFG_DCDEN_Pos) /*!< 0x00040000 */ -#define GCCFG_DCDEN GCCFG_DCDEN_Msk /*!< Data contact detection (DCD) mode enable*/ +#define GCCFG_DCDEN_Msk (0x1UL << GCCFG_DCDEN_Pos) // 0x00040000 */ +#define GCCFG_DCDEN GCCFG_DCDEN_Msk // Data contact detection (DCD) mode enable*/ #define GCCFG_PDEN_Pos (19U) -#define GCCFG_PDEN_Msk (0x1UL << GCCFG_PDEN_Pos) /*!< 0x00080000 */ -#define GCCFG_PDEN GCCFG_PDEN_Msk /*!< Primary detection (PD) mode enable*/ +#define GCCFG_PDEN_Msk (0x1UL << GCCFG_PDEN_Pos) // 0x00080000 */ +#define GCCFG_PDEN GCCFG_PDEN_Msk // Primary detection (PD) mode enable*/ #define GCCFG_SDEN_Pos (20U) -#define GCCFG_SDEN_Msk (0x1UL << GCCFG_SDEN_Pos) /*!< 0x00100000 */ -#define GCCFG_SDEN GCCFG_SDEN_Msk /*!< Secondary detection (SD) mode enable */ +#define GCCFG_SDEN_Msk (0x1UL << GCCFG_SDEN_Pos) // 0x00100000 */ +#define GCCFG_SDEN GCCFG_SDEN_Msk // Secondary detection (SD) mode enable */ #define GCCFG_VBDEN_Pos (21U) -#define GCCFG_VBDEN_Msk (0x1UL << GCCFG_VBDEN_Pos) /*!< 0x00200000 */ -#define GCCFG_VBDEN GCCFG_VBDEN_Msk /*!< VBUS mode enable */ +#define GCCFG_VBDEN_Msk (0x1UL << GCCFG_VBDEN_Pos) // 0x00200000 */ +#define GCCFG_VBDEN GCCFG_VBDEN_Msk // VBUS mode enable */ #define GCCFG_OTGIDEN_Pos (22U) -#define GCCFG_OTGIDEN_Msk (0x1UL << GCCFG_OTGIDEN_Pos) /*!< 0x00400000 */ -#define GCCFG_OTGIDEN GCCFG_OTGIDEN_Msk /*!< OTG Id enable */ +#define GCCFG_OTGIDEN_Msk (0x1UL << GCCFG_OTGIDEN_Pos) // 0x00400000 */ +#define GCCFG_OTGIDEN GCCFG_OTGIDEN_Msk // OTG Id enable */ #define GCCFG_PHYHSEN_Pos (23U) -#define GCCFG_PHYHSEN_Msk (0x1UL << GCCFG_PHYHSEN_Pos) /*!< 0x00800000 */ -#define GCCFG_PHYHSEN GCCFG_PHYHSEN_Msk /*!< HS PHY enable */ +#define GCCFG_PHYHSEN_Msk (0x1UL << GCCFG_PHYHSEN_Pos) // 0x00800000 */ +#define GCCFG_PHYHSEN GCCFG_PHYHSEN_Msk // HS PHY enable */ /******************** Bit definition for DEACHINTMSK register ********************/ #define DEACHINTMSK_IEP1INTM_Pos (1U) -#define DEACHINTMSK_IEP1INTM_Msk (0x1UL << DEACHINTMSK_IEP1INTM_Pos) /*!< 0x00000002 */ -#define DEACHINTMSK_IEP1INTM DEACHINTMSK_IEP1INTM_Msk /*!< IN Endpoint 1 interrupt mask bit */ +#define DEACHINTMSK_IEP1INTM_Msk (0x1UL << DEACHINTMSK_IEP1INTM_Pos) // 0x00000002 */ +#define DEACHINTMSK_IEP1INTM DEACHINTMSK_IEP1INTM_Msk // IN Endpoint 1 interrupt mask bit */ #define DEACHINTMSK_OEP1INTM_Pos (17U) -#define DEACHINTMSK_OEP1INTM_Msk (0x1UL << DEACHINTMSK_OEP1INTM_Pos) /*!< 0x00020000 */ -#define DEACHINTMSK_OEP1INTM DEACHINTMSK_OEP1INTM_Msk /*!< OUT Endpoint 1 interrupt mask bit */ +#define DEACHINTMSK_OEP1INTM_Msk (0x1UL << DEACHINTMSK_OEP1INTM_Pos) // 0x00020000 */ +#define DEACHINTMSK_OEP1INTM DEACHINTMSK_OEP1INTM_Msk // OUT Endpoint 1 interrupt mask bit */ /******************** Bit definition for CID register ********************/ #define CID_PRODUCT_ID_Pos (0U) -#define CID_PRODUCT_ID_Msk (0xFFFFFFFFUL << CID_PRODUCT_ID_Pos) /*!< 0xFFFFFFFF */ -#define CID_PRODUCT_ID CID_PRODUCT_ID_Msk /*!< Product ID field */ +#define CID_PRODUCT_ID_Msk (0xFFFFFFFFUL << CID_PRODUCT_ID_Pos) // 0xFFFFFFFF */ +#define CID_PRODUCT_ID CID_PRODUCT_ID_Msk // Product ID field */ /******************** Bit definition for GLPMCFG register ********************/ #define GLPMCFG_LPMEN_Pos (0U) -#define GLPMCFG_LPMEN_Msk (0x1UL << GLPMCFG_LPMEN_Pos) /*!< 0x00000001 */ -#define GLPMCFG_LPMEN GLPMCFG_LPMEN_Msk /*!< LPM support enable */ +#define GLPMCFG_LPMEN_Msk (0x1UL << GLPMCFG_LPMEN_Pos) // 0x00000001 */ +#define GLPMCFG_LPMEN GLPMCFG_LPMEN_Msk // LPM support enable */ #define GLPMCFG_LPMACK_Pos (1U) -#define GLPMCFG_LPMACK_Msk (0x1UL << GLPMCFG_LPMACK_Pos) /*!< 0x00000002 */ -#define GLPMCFG_LPMACK GLPMCFG_LPMACK_Msk /*!< LPM Token acknowledge enable */ +#define GLPMCFG_LPMACK_Msk (0x1UL << GLPMCFG_LPMACK_Pos) // 0x00000002 */ +#define GLPMCFG_LPMACK GLPMCFG_LPMACK_Msk // LPM Token acknowledge enable */ #define GLPMCFG_BESL_Pos (2U) -#define GLPMCFG_BESL_Msk (0xFUL << GLPMCFG_BESL_Pos) /*!< 0x0000003C */ -#define GLPMCFG_BESL GLPMCFG_BESL_Msk /*!< BESL value received with last ACKed LPM Token */ +#define GLPMCFG_BESL_Msk (0xFUL << GLPMCFG_BESL_Pos) // 0x0000003C */ +#define GLPMCFG_BESL GLPMCFG_BESL_Msk // BESL value received with last ACKed LPM Token */ #define GLPMCFG_REMWAKE_Pos (6U) -#define GLPMCFG_REMWAKE_Msk (0x1UL << GLPMCFG_REMWAKE_Pos) /*!< 0x00000040 */ -#define GLPMCFG_REMWAKE GLPMCFG_REMWAKE_Msk /*!< bRemoteWake value received with last ACKed LPM Token */ +#define GLPMCFG_REMWAKE_Msk (0x1UL << GLPMCFG_REMWAKE_Pos) // 0x00000040 */ +#define GLPMCFG_REMWAKE GLPMCFG_REMWAKE_Msk // bRemoteWake value received with last ACKed LPM Token */ #define GLPMCFG_L1SSEN_Pos (7U) -#define GLPMCFG_L1SSEN_Msk (0x1UL << GLPMCFG_L1SSEN_Pos) /*!< 0x00000080 */ -#define GLPMCFG_L1SSEN GLPMCFG_L1SSEN_Msk /*!< L1 shallow sleep enable */ +#define GLPMCFG_L1SSEN_Msk (0x1UL << GLPMCFG_L1SSEN_Pos) // 0x00000080 */ +#define GLPMCFG_L1SSEN GLPMCFG_L1SSEN_Msk // L1 shallow sleep enable */ #define GLPMCFG_BESLTHRS_Pos (8U) -#define GLPMCFG_BESLTHRS_Msk (0xFUL << GLPMCFG_BESLTHRS_Pos) /*!< 0x00000F00 */ -#define GLPMCFG_BESLTHRS GLPMCFG_BESLTHRS_Msk /*!< BESL threshold */ +#define GLPMCFG_BESLTHRS_Msk (0xFUL << GLPMCFG_BESLTHRS_Pos) // 0x00000F00 */ +#define GLPMCFG_BESLTHRS GLPMCFG_BESLTHRS_Msk // BESL threshold */ #define GLPMCFG_L1DSEN_Pos (12U) -#define GLPMCFG_L1DSEN_Msk (0x1UL << GLPMCFG_L1DSEN_Pos) /*!< 0x00001000 */ -#define GLPMCFG_L1DSEN GLPMCFG_L1DSEN_Msk /*!< L1 deep sleep enable */ +#define GLPMCFG_L1DSEN_Msk (0x1UL << GLPMCFG_L1DSEN_Pos) // 0x00001000 */ +#define GLPMCFG_L1DSEN GLPMCFG_L1DSEN_Msk // L1 deep sleep enable */ #define GLPMCFG_LPMRSP_Pos (13U) -#define GLPMCFG_LPMRSP_Msk (0x3UL << GLPMCFG_LPMRSP_Pos) /*!< 0x00006000 */ -#define GLPMCFG_LPMRSP GLPMCFG_LPMRSP_Msk /*!< LPM response */ +#define GLPMCFG_LPMRSP_Msk (0x3UL << GLPMCFG_LPMRSP_Pos) // 0x00006000 */ +#define GLPMCFG_LPMRSP GLPMCFG_LPMRSP_Msk // LPM response */ #define GLPMCFG_SLPSTS_Pos (15U) -#define GLPMCFG_SLPSTS_Msk (0x1UL << GLPMCFG_SLPSTS_Pos) /*!< 0x00008000 */ -#define GLPMCFG_SLPSTS GLPMCFG_SLPSTS_Msk /*!< Port sleep status */ +#define GLPMCFG_SLPSTS_Msk (0x1UL << GLPMCFG_SLPSTS_Pos) // 0x00008000 */ +#define GLPMCFG_SLPSTS GLPMCFG_SLPSTS_Msk // Port sleep status */ #define GLPMCFG_L1RSMOK_Pos (16U) -#define GLPMCFG_L1RSMOK_Msk (0x1UL << GLPMCFG_L1RSMOK_Pos) /*!< 0x00010000 */ -#define GLPMCFG_L1RSMOK GLPMCFG_L1RSMOK_Msk /*!< Sleep State Resume OK */ +#define GLPMCFG_L1RSMOK_Msk (0x1UL << GLPMCFG_L1RSMOK_Pos) // 0x00010000 */ +#define GLPMCFG_L1RSMOK GLPMCFG_L1RSMOK_Msk // Sleep State Resume OK */ #define GLPMCFG_LPMCHIDX_Pos (17U) -#define GLPMCFG_LPMCHIDX_Msk (0xFUL << GLPMCFG_LPMCHIDX_Pos) /*!< 0x001E0000 */ -#define GLPMCFG_LPMCHIDX GLPMCFG_LPMCHIDX_Msk /*!< LPM Channel Index */ +#define GLPMCFG_LPMCHIDX_Msk (0xFUL << GLPMCFG_LPMCHIDX_Pos) // 0x001E0000 */ +#define GLPMCFG_LPMCHIDX GLPMCFG_LPMCHIDX_Msk // LPM Channel Index */ #define GLPMCFG_LPMRCNT_Pos (21U) -#define GLPMCFG_LPMRCNT_Msk (0x7UL << GLPMCFG_LPMRCNT_Pos) /*!< 0x00E00000 */ -#define GLPMCFG_LPMRCNT GLPMCFG_LPMRCNT_Msk /*!< LPM retry count */ +#define GLPMCFG_LPMRCNT_Msk (0x7UL << GLPMCFG_LPMRCNT_Pos) // 0x00E00000 */ +#define GLPMCFG_LPMRCNT GLPMCFG_LPMRCNT_Msk // LPM retry count */ #define GLPMCFG_SNDLPM_Pos (24U) -#define GLPMCFG_SNDLPM_Msk (0x1UL << GLPMCFG_SNDLPM_Pos) /*!< 0x01000000 */ -#define GLPMCFG_SNDLPM GLPMCFG_SNDLPM_Msk /*!< Send LPM transaction */ +#define GLPMCFG_SNDLPM_Msk (0x1UL << GLPMCFG_SNDLPM_Pos) // 0x01000000 */ +#define GLPMCFG_SNDLPM GLPMCFG_SNDLPM_Msk // Send LPM transaction */ #define GLPMCFG_LPMRCNTSTS_Pos (25U) -#define GLPMCFG_LPMRCNTSTS_Msk (0x7UL << GLPMCFG_LPMRCNTSTS_Pos) /*!< 0x0E000000 */ -#define GLPMCFG_LPMRCNTSTS GLPMCFG_LPMRCNTSTS_Msk /*!< LPM retry count status */ +#define GLPMCFG_LPMRCNTSTS_Msk (0x7UL << GLPMCFG_LPMRCNTSTS_Pos) // 0x0E000000 */ +#define GLPMCFG_LPMRCNTSTS GLPMCFG_LPMRCNTSTS_Msk // LPM retry count status */ #define GLPMCFG_ENBESL_Pos (28U) -#define GLPMCFG_ENBESL_Msk (0x1UL << GLPMCFG_ENBESL_Pos) /*!< 0x10000000 */ -#define GLPMCFG_ENBESL GLPMCFG_ENBESL_Msk /*!< Enable best effort service latency */ +#define GLPMCFG_ENBESL_Msk (0x1UL << GLPMCFG_ENBESL_Pos) // 0x10000000 */ +#define GLPMCFG_ENBESL GLPMCFG_ENBESL_Msk // Enable best effort service latency */ /******************** Bit definition for DIEPEACHMSK1 register ********************/ #define DIEPEACHMSK1_XFRCM_Pos (0U) -#define DIEPEACHMSK1_XFRCM_Msk (0x1UL << DIEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ -#define DIEPEACHMSK1_XFRCM DIEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define DIEPEACHMSK1_XFRCM_Msk (0x1UL << DIEPEACHMSK1_XFRCM_Pos) // 0x00000001 */ +#define DIEPEACHMSK1_XFRCM DIEPEACHMSK1_XFRCM_Msk // Transfer completed interrupt mask */ #define DIEPEACHMSK1_EPDM_Pos (1U) -#define DIEPEACHMSK1_EPDM_Msk (0x1UL << DIEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ -#define DIEPEACHMSK1_EPDM DIEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define DIEPEACHMSK1_EPDM_Msk (0x1UL << DIEPEACHMSK1_EPDM_Pos) // 0x00000002 */ +#define DIEPEACHMSK1_EPDM DIEPEACHMSK1_EPDM_Msk // Endpoint disabled interrupt mask */ #define DIEPEACHMSK1_TOM_Pos (3U) -#define DIEPEACHMSK1_TOM_Msk (0x1UL << DIEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ -#define DIEPEACHMSK1_TOM DIEPEACHMSK1_TOM_Msk /*!< Timeout condition mask (nonisochronous endpoints) */ +#define DIEPEACHMSK1_TOM_Msk (0x1UL << DIEPEACHMSK1_TOM_Pos) // 0x00000008 */ +#define DIEPEACHMSK1_TOM DIEPEACHMSK1_TOM_Msk // Timeout condition mask (nonisochronous endpoints) */ #define DIEPEACHMSK1_ITTXFEMSK_Pos (4U) -#define DIEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << DIEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ -#define DIEPEACHMSK1_ITTXFEMSK DIEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define DIEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << DIEPEACHMSK1_ITTXFEMSK_Pos) // 0x00000010 */ +#define DIEPEACHMSK1_ITTXFEMSK DIEPEACHMSK1_ITTXFEMSK_Msk // IN token received when TxFIFO empty mask */ #define DIEPEACHMSK1_INEPNMM_Pos (5U) -#define DIEPEACHMSK1_INEPNMM_Msk (0x1UL << DIEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ -#define DIEPEACHMSK1_INEPNMM DIEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define DIEPEACHMSK1_INEPNMM_Msk (0x1UL << DIEPEACHMSK1_INEPNMM_Pos) // 0x00000020 */ +#define DIEPEACHMSK1_INEPNMM DIEPEACHMSK1_INEPNMM_Msk // IN token received with EP mismatch mask */ #define DIEPEACHMSK1_INEPNEM_Pos (6U) -#define DIEPEACHMSK1_INEPNEM_Msk (0x1UL << DIEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ -#define DIEPEACHMSK1_INEPNEM DIEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define DIEPEACHMSK1_INEPNEM_Msk (0x1UL << DIEPEACHMSK1_INEPNEM_Pos) // 0x00000040 */ +#define DIEPEACHMSK1_INEPNEM DIEPEACHMSK1_INEPNEM_Msk // IN endpoint NAK effective mask */ #define DIEPEACHMSK1_TXFURM_Pos (8U) -#define DIEPEACHMSK1_TXFURM_Msk (0x1UL << DIEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ -#define DIEPEACHMSK1_TXFURM DIEPEACHMSK1_TXFURM_Msk /*!< FIFO underrun mask */ +#define DIEPEACHMSK1_TXFURM_Msk (0x1UL << DIEPEACHMSK1_TXFURM_Pos) // 0x00000100 */ +#define DIEPEACHMSK1_TXFURM DIEPEACHMSK1_TXFURM_Msk // FIFO underrun mask */ #define DIEPEACHMSK1_BIM_Pos (9U) -#define DIEPEACHMSK1_BIM_Msk (0x1UL << DIEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ -#define DIEPEACHMSK1_BIM DIEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ +#define DIEPEACHMSK1_BIM_Msk (0x1UL << DIEPEACHMSK1_BIM_Pos) // 0x00000200 */ +#define DIEPEACHMSK1_BIM DIEPEACHMSK1_BIM_Msk // BNA interrupt mask */ #define DIEPEACHMSK1_NAKM_Pos (13U) -#define DIEPEACHMSK1_NAKM_Msk (0x1UL << DIEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ -#define DIEPEACHMSK1_NAKM DIEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ +#define DIEPEACHMSK1_NAKM_Msk (0x1UL << DIEPEACHMSK1_NAKM_Pos) // 0x00002000 */ +#define DIEPEACHMSK1_NAKM DIEPEACHMSK1_NAKM_Msk // NAK interrupt mask */ /******************** Bit definition for HPRT register ********************/ #define HPRT_PCSTS_Pos (0U) -#define HPRT_PCSTS_Msk (0x1UL << HPRT_PCSTS_Pos) /*!< 0x00000001 */ -#define HPRT_PCSTS HPRT_PCSTS_Msk /*!< Port connect status */ +#define HPRT_PCSTS_Msk (0x1UL << HPRT_PCSTS_Pos) // 0x00000001 */ +#define HPRT_PCSTS HPRT_PCSTS_Msk // Port connect status */ #define HPRT_PCDET_Pos (1U) -#define HPRT_PCDET_Msk (0x1UL << HPRT_PCDET_Pos) /*!< 0x00000002 */ -#define HPRT_PCDET HPRT_PCDET_Msk /*!< Port connect detected */ +#define HPRT_PCDET_Msk (0x1UL << HPRT_PCDET_Pos) // 0x00000002 */ +#define HPRT_PCDET HPRT_PCDET_Msk // Port connect detected */ #define HPRT_PENA_Pos (2U) -#define HPRT_PENA_Msk (0x1UL << HPRT_PENA_Pos) /*!< 0x00000004 */ -#define HPRT_PENA HPRT_PENA_Msk /*!< Port enable */ +#define HPRT_PENA_Msk (0x1UL << HPRT_PENA_Pos) // 0x00000004 */ +#define HPRT_PENA HPRT_PENA_Msk // Port enable */ #define HPRT_PENCHNG_Pos (3U) -#define HPRT_PENCHNG_Msk (0x1UL << HPRT_PENCHNG_Pos) /*!< 0x00000008 */ -#define HPRT_PENCHNG HPRT_PENCHNG_Msk /*!< Port enable/disable change */ +#define HPRT_PENCHNG_Msk (0x1UL << HPRT_PENCHNG_Pos) // 0x00000008 */ +#define HPRT_PENCHNG HPRT_PENCHNG_Msk // Port enable/disable change */ #define HPRT_POCA_Pos (4U) -#define HPRT_POCA_Msk (0x1UL << HPRT_POCA_Pos) /*!< 0x00000010 */ -#define HPRT_POCA HPRT_POCA_Msk /*!< Port overcurrent active */ +#define HPRT_POCA_Msk (0x1UL << HPRT_POCA_Pos) // 0x00000010 */ +#define HPRT_POCA HPRT_POCA_Msk // Port overcurrent active */ #define HPRT_POCCHNG_Pos (5U) -#define HPRT_POCCHNG_Msk (0x1UL << HPRT_POCCHNG_Pos) /*!< 0x00000020 */ -#define HPRT_POCCHNG HPRT_POCCHNG_Msk /*!< Port overcurrent change */ +#define HPRT_POCCHNG_Msk (0x1UL << HPRT_POCCHNG_Pos) // 0x00000020 */ +#define HPRT_POCCHNG HPRT_POCCHNG_Msk // Port overcurrent change */ #define HPRT_PRES_Pos (6U) -#define HPRT_PRES_Msk (0x1UL << HPRT_PRES_Pos) /*!< 0x00000040 */ -#define HPRT_PRES HPRT_PRES_Msk /*!< Port resume */ +#define HPRT_PRES_Msk (0x1UL << HPRT_PRES_Pos) // 0x00000040 */ +#define HPRT_PRES HPRT_PRES_Msk // Port resume */ #define HPRT_PSUSP_Pos (7U) -#define HPRT_PSUSP_Msk (0x1UL << HPRT_PSUSP_Pos) /*!< 0x00000080 */ -#define HPRT_PSUSP HPRT_PSUSP_Msk /*!< Port suspend */ +#define HPRT_PSUSP_Msk (0x1UL << HPRT_PSUSP_Pos) // 0x00000080 */ +#define HPRT_PSUSP HPRT_PSUSP_Msk // Port suspend */ #define HPRT_PRST_Pos (8U) -#define HPRT_PRST_Msk (0x1UL << HPRT_PRST_Pos) /*!< 0x00000100 */ -#define HPRT_PRST HPRT_PRST_Msk /*!< Port reset */ +#define HPRT_PRST_Msk (0x1UL << HPRT_PRST_Pos) // 0x00000100 */ +#define HPRT_PRST HPRT_PRST_Msk // Port reset */ #define HPRT_PLSTS_Pos (10U) -#define HPRT_PLSTS_Msk (0x3UL << HPRT_PLSTS_Pos) /*!< 0x00000C00 */ -#define HPRT_PLSTS HPRT_PLSTS_Msk /*!< Port line status */ -#define HPRT_PLSTS_0 (0x1UL << HPRT_PLSTS_Pos) /*!< 0x00000400 */ -#define HPRT_PLSTS_1 (0x2UL << HPRT_PLSTS_Pos) /*!< 0x00000800 */ +#define HPRT_PLSTS_Msk (0x3UL << HPRT_PLSTS_Pos) // 0x00000C00 */ +#define HPRT_PLSTS HPRT_PLSTS_Msk // Port line status */ +#define HPRT_PLSTS_0 (0x1UL << HPRT_PLSTS_Pos) // 0x00000400 */ +#define HPRT_PLSTS_1 (0x2UL << HPRT_PLSTS_Pos) // 0x00000800 */ #define HPRT_PPWR_Pos (12U) -#define HPRT_PPWR_Msk (0x1UL << HPRT_PPWR_Pos) /*!< 0x00001000 */ -#define HPRT_PPWR HPRT_PPWR_Msk /*!< Port power */ +#define HPRT_PPWR_Msk (0x1UL << HPRT_PPWR_Pos) // 0x00001000 */ +#define HPRT_PPWR HPRT_PPWR_Msk // Port power */ #define HPRT_PTCTL_Pos (13U) -#define HPRT_PTCTL_Msk (0xFUL << HPRT_PTCTL_Pos) /*!< 0x0001E000 */ -#define HPRT_PTCTL HPRT_PTCTL_Msk /*!< Port test control */ -#define HPRT_PTCTL_0 (0x1UL << HPRT_PTCTL_Pos) /*!< 0x00002000 */ -#define HPRT_PTCTL_1 (0x2UL << HPRT_PTCTL_Pos) /*!< 0x00004000 */ -#define HPRT_PTCTL_2 (0x4UL << HPRT_PTCTL_Pos) /*!< 0x00008000 */ -#define HPRT_PTCTL_3 (0x8UL << HPRT_PTCTL_Pos) /*!< 0x00010000 */ +#define HPRT_PTCTL_Msk (0xFUL << HPRT_PTCTL_Pos) // 0x0001E000 */ +#define HPRT_PTCTL HPRT_PTCTL_Msk // Port test control */ +#define HPRT_PTCTL_0 (0x1UL << HPRT_PTCTL_Pos) // 0x00002000 */ +#define HPRT_PTCTL_1 (0x2UL << HPRT_PTCTL_Pos) // 0x00004000 */ +#define HPRT_PTCTL_2 (0x4UL << HPRT_PTCTL_Pos) // 0x00008000 */ +#define HPRT_PTCTL_3 (0x8UL << HPRT_PTCTL_Pos) // 0x00010000 */ #define HPRT_PSPD_Pos (17U) -#define HPRT_PSPD_Msk (0x3UL << HPRT_PSPD_Pos) /*!< 0x00060000 */ -#define HPRT_PSPD HPRT_PSPD_Msk /*!< Port speed */ -#define HPRT_PSPD_0 (0x1UL << HPRT_PSPD_Pos) /*!< 0x00020000 */ -#define HPRT_PSPD_1 (0x2UL << HPRT_PSPD_Pos) /*!< 0x00040000 */ +#define HPRT_PSPD_Msk (0x3UL << HPRT_PSPD_Pos) // 0x00060000 */ +#define HPRT_PSPD HPRT_PSPD_Msk // Port speed */ +#define HPRT_PSPD_0 (0x1UL << HPRT_PSPD_Pos) // 0x00020000 */ +#define HPRT_PSPD_1 (0x2UL << HPRT_PSPD_Pos) // 0x00040000 */ /******************** Bit definition for DOEPEACHMSK1 register ********************/ #define DOEPEACHMSK1_XFRCM_Pos (0U) -#define DOEPEACHMSK1_XFRCM_Msk (0x1UL << DOEPEACHMSK1_XFRCM_Pos) /*!< 0x00000001 */ -#define DOEPEACHMSK1_XFRCM DOEPEACHMSK1_XFRCM_Msk /*!< Transfer completed interrupt mask */ +#define DOEPEACHMSK1_XFRCM_Msk (0x1UL << DOEPEACHMSK1_XFRCM_Pos) // 0x00000001 */ +#define DOEPEACHMSK1_XFRCM DOEPEACHMSK1_XFRCM_Msk // Transfer completed interrupt mask */ #define DOEPEACHMSK1_EPDM_Pos (1U) -#define DOEPEACHMSK1_EPDM_Msk (0x1UL << DOEPEACHMSK1_EPDM_Pos) /*!< 0x00000002 */ -#define DOEPEACHMSK1_EPDM DOEPEACHMSK1_EPDM_Msk /*!< Endpoint disabled interrupt mask */ +#define DOEPEACHMSK1_EPDM_Msk (0x1UL << DOEPEACHMSK1_EPDM_Pos) // 0x00000002 */ +#define DOEPEACHMSK1_EPDM DOEPEACHMSK1_EPDM_Msk // Endpoint disabled interrupt mask */ #define DOEPEACHMSK1_TOM_Pos (3U) -#define DOEPEACHMSK1_TOM_Msk (0x1UL << DOEPEACHMSK1_TOM_Pos) /*!< 0x00000008 */ -#define DOEPEACHMSK1_TOM DOEPEACHMSK1_TOM_Msk /*!< Timeout condition mask */ +#define DOEPEACHMSK1_TOM_Msk (0x1UL << DOEPEACHMSK1_TOM_Pos) // 0x00000008 */ +#define DOEPEACHMSK1_TOM DOEPEACHMSK1_TOM_Msk // Timeout condition mask */ #define DOEPEACHMSK1_ITTXFEMSK_Pos (4U) -#define DOEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << DOEPEACHMSK1_ITTXFEMSK_Pos) /*!< 0x00000010 */ -#define DOEPEACHMSK1_ITTXFEMSK DOEPEACHMSK1_ITTXFEMSK_Msk /*!< IN token received when TxFIFO empty mask */ +#define DOEPEACHMSK1_ITTXFEMSK_Msk (0x1UL << DOEPEACHMSK1_ITTXFEMSK_Pos) // 0x00000010 */ +#define DOEPEACHMSK1_ITTXFEMSK DOEPEACHMSK1_ITTXFEMSK_Msk // IN token received when TxFIFO empty mask */ #define DOEPEACHMSK1_INEPNMM_Pos (5U) -#define DOEPEACHMSK1_INEPNMM_Msk (0x1UL << DOEPEACHMSK1_INEPNMM_Pos) /*!< 0x00000020 */ -#define DOEPEACHMSK1_INEPNMM DOEPEACHMSK1_INEPNMM_Msk /*!< IN token received with EP mismatch mask */ +#define DOEPEACHMSK1_INEPNMM_Msk (0x1UL << DOEPEACHMSK1_INEPNMM_Pos) // 0x00000020 */ +#define DOEPEACHMSK1_INEPNMM DOEPEACHMSK1_INEPNMM_Msk // IN token received with EP mismatch mask */ #define DOEPEACHMSK1_INEPNEM_Pos (6U) -#define DOEPEACHMSK1_INEPNEM_Msk (0x1UL << DOEPEACHMSK1_INEPNEM_Pos) /*!< 0x00000040 */ -#define DOEPEACHMSK1_INEPNEM DOEPEACHMSK1_INEPNEM_Msk /*!< IN endpoint NAK effective mask */ +#define DOEPEACHMSK1_INEPNEM_Msk (0x1UL << DOEPEACHMSK1_INEPNEM_Pos) // 0x00000040 */ +#define DOEPEACHMSK1_INEPNEM DOEPEACHMSK1_INEPNEM_Msk // IN endpoint NAK effective mask */ #define DOEPEACHMSK1_TXFURM_Pos (8U) -#define DOEPEACHMSK1_TXFURM_Msk (0x1UL << DOEPEACHMSK1_TXFURM_Pos) /*!< 0x00000100 */ -#define DOEPEACHMSK1_TXFURM DOEPEACHMSK1_TXFURM_Msk /*!< OUT packet error mask */ +#define DOEPEACHMSK1_TXFURM_Msk (0x1UL << DOEPEACHMSK1_TXFURM_Pos) // 0x00000100 */ +#define DOEPEACHMSK1_TXFURM DOEPEACHMSK1_TXFURM_Msk // OUT packet error mask */ #define DOEPEACHMSK1_BIM_Pos (9U) -#define DOEPEACHMSK1_BIM_Msk (0x1UL << DOEPEACHMSK1_BIM_Pos) /*!< 0x00000200 */ -#define DOEPEACHMSK1_BIM DOEPEACHMSK1_BIM_Msk /*!< BNA interrupt mask */ +#define DOEPEACHMSK1_BIM_Msk (0x1UL << DOEPEACHMSK1_BIM_Pos) // 0x00000200 */ +#define DOEPEACHMSK1_BIM DOEPEACHMSK1_BIM_Msk // BNA interrupt mask */ #define DOEPEACHMSK1_BERRM_Pos (12U) -#define DOEPEACHMSK1_BERRM_Msk (0x1UL << DOEPEACHMSK1_BERRM_Pos) /*!< 0x00001000 */ -#define DOEPEACHMSK1_BERRM DOEPEACHMSK1_BERRM_Msk /*!< Bubble error interrupt mask */ +#define DOEPEACHMSK1_BERRM_Msk (0x1UL << DOEPEACHMSK1_BERRM_Pos) // 0x00001000 */ +#define DOEPEACHMSK1_BERRM DOEPEACHMSK1_BERRM_Msk // Bubble error interrupt mask */ #define DOEPEACHMSK1_NAKM_Pos (13U) -#define DOEPEACHMSK1_NAKM_Msk (0x1UL << DOEPEACHMSK1_NAKM_Pos) /*!< 0x00002000 */ -#define DOEPEACHMSK1_NAKM DOEPEACHMSK1_NAKM_Msk /*!< NAK interrupt mask */ +#define DOEPEACHMSK1_NAKM_Msk (0x1UL << DOEPEACHMSK1_NAKM_Pos) // 0x00002000 */ +#define DOEPEACHMSK1_NAKM DOEPEACHMSK1_NAKM_Msk // NAK interrupt mask */ #define DOEPEACHMSK1_NYETM_Pos (14U) -#define DOEPEACHMSK1_NYETM_Msk (0x1UL << DOEPEACHMSK1_NYETM_Pos) /*!< 0x00004000 */ -#define DOEPEACHMSK1_NYETM DOEPEACHMSK1_NYETM_Msk /*!< NYET interrupt mask */ +#define DOEPEACHMSK1_NYETM_Msk (0x1UL << DOEPEACHMSK1_NYETM_Pos) // 0x00004000 */ +#define DOEPEACHMSK1_NYETM DOEPEACHMSK1_NYETM_Msk // NYET interrupt mask */ /******************** Bit definition for HPTXFSIZ register ********************/ #define HPTXFSIZ_PTXSA_Pos (0U) -#define HPTXFSIZ_PTXSA_Msk (0xFFFFUL << HPTXFSIZ_PTXSA_Pos) /*!< 0x0000FFFF */ -#define HPTXFSIZ_PTXSA HPTXFSIZ_PTXSA_Msk /*!< Host periodic TxFIFO start address */ +#define HPTXFSIZ_PTXSA_Msk (0xFFFFUL << HPTXFSIZ_PTXSA_Pos) // 0x0000FFFF */ +#define HPTXFSIZ_PTXSA HPTXFSIZ_PTXSA_Msk // Host periodic TxFIFO start address */ #define HPTXFSIZ_PTXFD_Pos (16U) -#define HPTXFSIZ_PTXFD_Msk (0xFFFFUL << HPTXFSIZ_PTXFD_Pos) /*!< 0xFFFF0000 */ -#define HPTXFSIZ_PTXFD HPTXFSIZ_PTXFD_Msk /*!< Host periodic TxFIFO depth */ +#define HPTXFSIZ_PTXFD_Msk (0xFFFFUL << HPTXFSIZ_PTXFD_Pos) // 0xFFFF0000 */ +#define HPTXFSIZ_PTXFD HPTXFSIZ_PTXFD_Msk // Host periodic TxFIFO depth */ /******************** Bit definition for DIEPCTL register ********************/ #define DIEPCTL_MPSIZ_Pos (0U) -#define DIEPCTL_MPSIZ_Msk (0x7FFUL << DIEPCTL_MPSIZ_Pos) /*!< 0x000007FF */ -#define DIEPCTL_MPSIZ DIEPCTL_MPSIZ_Msk /*!< Maximum packet size */ +#define DIEPCTL_MPSIZ_Msk (0x7FFUL << DIEPCTL_MPSIZ_Pos) // 0x000007FF */ +#define DIEPCTL_MPSIZ DIEPCTL_MPSIZ_Msk // Maximum packet size */ #define DIEPCTL_USBAEP_Pos (15U) -#define DIEPCTL_USBAEP_Msk (0x1UL << DIEPCTL_USBAEP_Pos) /*!< 0x00008000 */ -#define DIEPCTL_USBAEP DIEPCTL_USBAEP_Msk /*!< USB active endpoint */ +#define DIEPCTL_USBAEP_Msk (0x1UL << DIEPCTL_USBAEP_Pos) // 0x00008000 */ +#define DIEPCTL_USBAEP DIEPCTL_USBAEP_Msk // USB active endpoint */ #define DIEPCTL_EONUM_DPID_Pos (16U) -#define DIEPCTL_EONUM_DPID_Msk (0x1UL << DIEPCTL_EONUM_DPID_Pos) /*!< 0x00010000 */ -#define DIEPCTL_EONUM_DPID DIEPCTL_EONUM_DPID_Msk /*!< Even/odd frame */ +#define DIEPCTL_EONUM_DPID_Msk (0x1UL << DIEPCTL_EONUM_DPID_Pos) // 0x00010000 */ +#define DIEPCTL_EONUM_DPID DIEPCTL_EONUM_DPID_Msk // Even/odd frame */ #define DIEPCTL_NAKSTS_Pos (17U) -#define DIEPCTL_NAKSTS_Msk (0x1UL << DIEPCTL_NAKSTS_Pos) /*!< 0x00020000 */ -#define DIEPCTL_NAKSTS DIEPCTL_NAKSTS_Msk /*!< NAK status */ +#define DIEPCTL_NAKSTS_Msk (0x1UL << DIEPCTL_NAKSTS_Pos) // 0x00020000 */ +#define DIEPCTL_NAKSTS DIEPCTL_NAKSTS_Msk // NAK status */ #define DIEPCTL_EPTYP_Pos (18U) -#define DIEPCTL_EPTYP_Msk (0x3UL << DIEPCTL_EPTYP_Pos) /*!< 0x000C0000 */ -#define DIEPCTL_EPTYP DIEPCTL_EPTYP_Msk /*!< Endpoint type */ -#define DIEPCTL_EPTYP_0 (0x1UL << DIEPCTL_EPTYP_Pos) /*!< 0x00040000 */ -#define DIEPCTL_EPTYP_1 (0x2UL << DIEPCTL_EPTYP_Pos) /*!< 0x00080000 */ +#define DIEPCTL_EPTYP_Msk (0x3UL << DIEPCTL_EPTYP_Pos) // 0x000C0000 */ +#define DIEPCTL_EPTYP DIEPCTL_EPTYP_Msk // Endpoint type */ +#define DIEPCTL_EPTYP_0 (0x1UL << DIEPCTL_EPTYP_Pos) // 0x00040000 */ +#define DIEPCTL_EPTYP_1 (0x2UL << DIEPCTL_EPTYP_Pos) // 0x00080000 */ #define DIEPCTL_STALL_Pos (21U) -#define DIEPCTL_STALL_Msk (0x1UL << DIEPCTL_STALL_Pos) /*!< 0x00200000 */ -#define DIEPCTL_STALL DIEPCTL_STALL_Msk /*!< STALL handshake */ +#define DIEPCTL_STALL_Msk (0x1UL << DIEPCTL_STALL_Pos) // 0x00200000 */ +#define DIEPCTL_STALL DIEPCTL_STALL_Msk // STALL handshake */ #define DIEPCTL_TXFNUM_Pos (22U) -#define DIEPCTL_TXFNUM_Msk (0xFUL << DIEPCTL_TXFNUM_Pos) /*!< 0x03C00000 */ -#define DIEPCTL_TXFNUM DIEPCTL_TXFNUM_Msk /*!< TxFIFO number */ -#define DIEPCTL_TXFNUM_0 (0x1UL << DIEPCTL_TXFNUM_Pos) /*!< 0x00400000 */ -#define DIEPCTL_TXFNUM_1 (0x2UL << DIEPCTL_TXFNUM_Pos) /*!< 0x00800000 */ -#define DIEPCTL_TXFNUM_2 (0x4UL << DIEPCTL_TXFNUM_Pos) /*!< 0x01000000 */ -#define DIEPCTL_TXFNUM_3 (0x8UL << DIEPCTL_TXFNUM_Pos) /*!< 0x02000000 */ +#define DIEPCTL_TXFNUM_Msk (0xFUL << DIEPCTL_TXFNUM_Pos) // 0x03C00000 */ +#define DIEPCTL_TXFNUM DIEPCTL_TXFNUM_Msk // TxFIFO number */ +#define DIEPCTL_TXFNUM_0 (0x1UL << DIEPCTL_TXFNUM_Pos) // 0x00400000 */ +#define DIEPCTL_TXFNUM_1 (0x2UL << DIEPCTL_TXFNUM_Pos) // 0x00800000 */ +#define DIEPCTL_TXFNUM_2 (0x4UL << DIEPCTL_TXFNUM_Pos) // 0x01000000 */ +#define DIEPCTL_TXFNUM_3 (0x8UL << DIEPCTL_TXFNUM_Pos) // 0x02000000 */ #define DIEPCTL_CNAK_Pos (26U) -#define DIEPCTL_CNAK_Msk (0x1UL << DIEPCTL_CNAK_Pos) /*!< 0x04000000 */ -#define DIEPCTL_CNAK DIEPCTL_CNAK_Msk /*!< Clear NAK */ +#define DIEPCTL_CNAK_Msk (0x1UL << DIEPCTL_CNAK_Pos) // 0x04000000 */ +#define DIEPCTL_CNAK DIEPCTL_CNAK_Msk // Clear NAK */ #define DIEPCTL_SNAK_Pos (27U) -#define DIEPCTL_SNAK_Msk (0x1UL << DIEPCTL_SNAK_Pos) /*!< 0x08000000 */ -#define DIEPCTL_SNAK DIEPCTL_SNAK_Msk /*!< Set NAK */ +#define DIEPCTL_SNAK_Msk (0x1UL << DIEPCTL_SNAK_Pos) // 0x08000000 */ +#define DIEPCTL_SNAK DIEPCTL_SNAK_Msk // Set NAK */ #define DIEPCTL_SD0PID_SEVNFRM_Pos (28U) -#define DIEPCTL_SD0PID_SEVNFRM_Msk (0x1UL << DIEPCTL_SD0PID_SEVNFRM_Pos) /*!< 0x10000000 */ -#define DIEPCTL_SD0PID_SEVNFRM DIEPCTL_SD0PID_SEVNFRM_Msk /*!< Set DATA0 PID */ +#define DIEPCTL_SD0PID_SEVNFRM_Msk (0x1UL << DIEPCTL_SD0PID_SEVNFRM_Pos) // 0x10000000 */ +#define DIEPCTL_SD0PID_SEVNFRM DIEPCTL_SD0PID_SEVNFRM_Msk // Set DATA0 PID */ #define DIEPCTL_SODDFRM_Pos (29U) -#define DIEPCTL_SODDFRM_Msk (0x1UL << DIEPCTL_SODDFRM_Pos) /*!< 0x20000000 */ -#define DIEPCTL_SODDFRM DIEPCTL_SODDFRM_Msk /*!< Set odd frame */ +#define DIEPCTL_SODDFRM_Msk (0x1UL << DIEPCTL_SODDFRM_Pos) // 0x20000000 */ +#define DIEPCTL_SODDFRM DIEPCTL_SODDFRM_Msk // Set odd frame */ #define DIEPCTL_EPDIS_Pos (30U) -#define DIEPCTL_EPDIS_Msk (0x1UL << DIEPCTL_EPDIS_Pos) /*!< 0x40000000 */ -#define DIEPCTL_EPDIS DIEPCTL_EPDIS_Msk /*!< Endpoint disable */ +#define DIEPCTL_EPDIS_Msk (0x1UL << DIEPCTL_EPDIS_Pos) // 0x40000000 */ +#define DIEPCTL_EPDIS DIEPCTL_EPDIS_Msk // Endpoint disable */ #define DIEPCTL_EPENA_Pos (31U) -#define DIEPCTL_EPENA_Msk (0x1UL << DIEPCTL_EPENA_Pos) /*!< 0x80000000 */ -#define DIEPCTL_EPENA DIEPCTL_EPENA_Msk /*!< Endpoint enable */ +#define DIEPCTL_EPENA_Msk (0x1UL << DIEPCTL_EPENA_Pos) // 0x80000000 */ +#define DIEPCTL_EPENA DIEPCTL_EPENA_Msk // Endpoint enable */ /******************** Bit definition for HCCHAR register ********************/ #define HCCHAR_MPSIZ_Pos (0U) -#define HCCHAR_MPSIZ_Msk (0x7FFUL << HCCHAR_MPSIZ_Pos) /*!< 0x000007FF */ -#define HCCHAR_MPSIZ HCCHAR_MPSIZ_Msk /*!< Maximum packet size */ +#define HCCHAR_MPSIZ_Msk (0x7FFUL << HCCHAR_MPSIZ_Pos) // 0x000007FF */ +#define HCCHAR_MPSIZ HCCHAR_MPSIZ_Msk // Maximum packet size */ #define HCCHAR_EPNUM_Pos (11U) -#define HCCHAR_EPNUM_Msk (0xFUL << HCCHAR_EPNUM_Pos) /*!< 0x00007800 */ -#define HCCHAR_EPNUM HCCHAR_EPNUM_Msk /*!< Endpoint number */ -#define HCCHAR_EPNUM_0 (0x1UL << HCCHAR_EPNUM_Pos) /*!< 0x00000800 */ -#define HCCHAR_EPNUM_1 (0x2UL << HCCHAR_EPNUM_Pos) /*!< 0x00001000 */ -#define HCCHAR_EPNUM_2 (0x4UL << HCCHAR_EPNUM_Pos) /*!< 0x00002000 */ -#define HCCHAR_EPNUM_3 (0x8UL << HCCHAR_EPNUM_Pos) /*!< 0x00004000 */ +#define HCCHAR_EPNUM_Msk (0xFUL << HCCHAR_EPNUM_Pos) // 0x00007800 */ +#define HCCHAR_EPNUM HCCHAR_EPNUM_Msk // Endpoint number */ +#define HCCHAR_EPNUM_0 (0x1UL << HCCHAR_EPNUM_Pos) // 0x00000800 */ +#define HCCHAR_EPNUM_1 (0x2UL << HCCHAR_EPNUM_Pos) // 0x00001000 */ +#define HCCHAR_EPNUM_2 (0x4UL << HCCHAR_EPNUM_Pos) // 0x00002000 */ +#define HCCHAR_EPNUM_3 (0x8UL << HCCHAR_EPNUM_Pos) // 0x00004000 */ #define HCCHAR_EPDIR_Pos (15U) -#define HCCHAR_EPDIR_Msk (0x1UL << HCCHAR_EPDIR_Pos) /*!< 0x00008000 */ -#define HCCHAR_EPDIR HCCHAR_EPDIR_Msk /*!< Endpoint direction */ +#define HCCHAR_EPDIR_Msk (0x1UL << HCCHAR_EPDIR_Pos) // 0x00008000 */ +#define HCCHAR_EPDIR HCCHAR_EPDIR_Msk // Endpoint direction */ #define HCCHAR_LSDEV_Pos (17U) -#define HCCHAR_LSDEV_Msk (0x1UL << HCCHAR_LSDEV_Pos) /*!< 0x00020000 */ -#define HCCHAR_LSDEV HCCHAR_LSDEV_Msk /*!< Low-speed device */ +#define HCCHAR_LSDEV_Msk (0x1UL << HCCHAR_LSDEV_Pos) // 0x00020000 */ +#define HCCHAR_LSDEV HCCHAR_LSDEV_Msk // Low-speed device */ #define HCCHAR_EPTYP_Pos (18U) -#define HCCHAR_EPTYP_Msk (0x3UL << HCCHAR_EPTYP_Pos) /*!< 0x000C0000 */ -#define HCCHAR_EPTYP HCCHAR_EPTYP_Msk /*!< Endpoint type */ -#define HCCHAR_EPTYP_0 (0x1UL << HCCHAR_EPTYP_Pos) /*!< 0x00040000 */ -#define HCCHAR_EPTYP_1 (0x2UL << HCCHAR_EPTYP_Pos) /*!< 0x00080000 */ +#define HCCHAR_EPTYP_Msk (0x3UL << HCCHAR_EPTYP_Pos) // 0x000C0000 */ +#define HCCHAR_EPTYP HCCHAR_EPTYP_Msk // Endpoint type */ +#define HCCHAR_EPTYP_0 (0x1UL << HCCHAR_EPTYP_Pos) // 0x00040000 */ +#define HCCHAR_EPTYP_1 (0x2UL << HCCHAR_EPTYP_Pos) // 0x00080000 */ #define HCCHAR_MC_Pos (20U) -#define HCCHAR_MC_Msk (0x3UL << HCCHAR_MC_Pos) /*!< 0x00300000 */ -#define HCCHAR_MC HCCHAR_MC_Msk /*!< Multi Count (MC) / Error Count (EC) */ -#define HCCHAR_MC_0 (0x1UL << HCCHAR_MC_Pos) /*!< 0x00100000 */ -#define HCCHAR_MC_1 (0x2UL << HCCHAR_MC_Pos) /*!< 0x00200000 */ +#define HCCHAR_MC_Msk (0x3UL << HCCHAR_MC_Pos) // 0x00300000 */ +#define HCCHAR_MC HCCHAR_MC_Msk // Multi Count (MC) / Error Count (EC) */ +#define HCCHAR_MC_0 (0x1UL << HCCHAR_MC_Pos) // 0x00100000 */ +#define HCCHAR_MC_1 (0x2UL << HCCHAR_MC_Pos) // 0x00200000 */ #define HCCHAR_DAD_Pos (22U) -#define HCCHAR_DAD_Msk (0x7FUL << HCCHAR_DAD_Pos) /*!< 0x1FC00000 */ -#define HCCHAR_DAD HCCHAR_DAD_Msk /*!< Device address */ -#define HCCHAR_DAD_0 (0x01UL << HCCHAR_DAD_Pos) /*!< 0x00400000 */ -#define HCCHAR_DAD_1 (0x02UL << HCCHAR_DAD_Pos) /*!< 0x00800000 */ -#define HCCHAR_DAD_2 (0x04UL << HCCHAR_DAD_Pos) /*!< 0x01000000 */ -#define HCCHAR_DAD_3 (0x08UL << HCCHAR_DAD_Pos) /*!< 0x02000000 */ -#define HCCHAR_DAD_4 (0x10UL << HCCHAR_DAD_Pos) /*!< 0x04000000 */ -#define HCCHAR_DAD_5 (0x20UL << HCCHAR_DAD_Pos) /*!< 0x08000000 */ -#define HCCHAR_DAD_6 (0x40UL << HCCHAR_DAD_Pos) /*!< 0x10000000 */ +#define HCCHAR_DAD_Msk (0x7FUL << HCCHAR_DAD_Pos) // 0x1FC00000 */ +#define HCCHAR_DAD HCCHAR_DAD_Msk // Device address */ +#define HCCHAR_DAD_0 (0x01UL << HCCHAR_DAD_Pos) // 0x00400000 */ +#define HCCHAR_DAD_1 (0x02UL << HCCHAR_DAD_Pos) // 0x00800000 */ +#define HCCHAR_DAD_2 (0x04UL << HCCHAR_DAD_Pos) // 0x01000000 */ +#define HCCHAR_DAD_3 (0x08UL << HCCHAR_DAD_Pos) // 0x02000000 */ +#define HCCHAR_DAD_4 (0x10UL << HCCHAR_DAD_Pos) // 0x04000000 */ +#define HCCHAR_DAD_5 (0x20UL << HCCHAR_DAD_Pos) // 0x08000000 */ +#define HCCHAR_DAD_6 (0x40UL << HCCHAR_DAD_Pos) // 0x10000000 */ #define HCCHAR_ODDFRM_Pos (29U) -#define HCCHAR_ODDFRM_Msk (0x1UL << HCCHAR_ODDFRM_Pos) /*!< 0x20000000 */ -#define HCCHAR_ODDFRM HCCHAR_ODDFRM_Msk /*!< Odd frame */ +#define HCCHAR_ODDFRM_Msk (0x1UL << HCCHAR_ODDFRM_Pos) // 0x20000000 */ +#define HCCHAR_ODDFRM HCCHAR_ODDFRM_Msk // Odd frame */ #define HCCHAR_CHDIS_Pos (30U) -#define HCCHAR_CHDIS_Msk (0x1UL << HCCHAR_CHDIS_Pos) /*!< 0x40000000 */ -#define HCCHAR_CHDIS HCCHAR_CHDIS_Msk /*!< Channel disable */ +#define HCCHAR_CHDIS_Msk (0x1UL << HCCHAR_CHDIS_Pos) // 0x40000000 */ +#define HCCHAR_CHDIS HCCHAR_CHDIS_Msk // Channel disable */ #define HCCHAR_CHENA_Pos (31U) -#define HCCHAR_CHENA_Msk (0x1UL << HCCHAR_CHENA_Pos) /*!< 0x80000000 */ -#define HCCHAR_CHENA HCCHAR_CHENA_Msk /*!< Channel enable */ +#define HCCHAR_CHENA_Msk (0x1UL << HCCHAR_CHENA_Pos) // 0x80000000 */ +#define HCCHAR_CHENA HCCHAR_CHENA_Msk // Channel enable */ /******************** Bit definition for HCSPLT register ********************/ #define HCSPLT_PRTADDR_Pos (0U) -#define HCSPLT_PRTADDR_Msk (0x7FUL << HCSPLT_PRTADDR_Pos) /*!< 0x0000007F */ -#define HCSPLT_PRTADDR HCSPLT_PRTADDR_Msk /*!< Port address */ -#define HCSPLT_PRTADDR_0 (0x01UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000001 */ -#define HCSPLT_PRTADDR_1 (0x02UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000002 */ -#define HCSPLT_PRTADDR_2 (0x04UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000004 */ -#define HCSPLT_PRTADDR_3 (0x08UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000008 */ -#define HCSPLT_PRTADDR_4 (0x10UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000010 */ -#define HCSPLT_PRTADDR_5 (0x20UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000020 */ -#define HCSPLT_PRTADDR_6 (0x40UL << HCSPLT_PRTADDR_Pos) /*!< 0x00000040 */ +#define HCSPLT_PRTADDR_Msk (0x7FUL << HCSPLT_PRTADDR_Pos) // 0x0000007F */ +#define HCSPLT_PRTADDR HCSPLT_PRTADDR_Msk // Port address */ +#define HCSPLT_PRTADDR_0 (0x01UL << HCSPLT_PRTADDR_Pos) // 0x00000001 */ +#define HCSPLT_PRTADDR_1 (0x02UL << HCSPLT_PRTADDR_Pos) // 0x00000002 */ +#define HCSPLT_PRTADDR_2 (0x04UL << HCSPLT_PRTADDR_Pos) // 0x00000004 */ +#define HCSPLT_PRTADDR_3 (0x08UL << HCSPLT_PRTADDR_Pos) // 0x00000008 */ +#define HCSPLT_PRTADDR_4 (0x10UL << HCSPLT_PRTADDR_Pos) // 0x00000010 */ +#define HCSPLT_PRTADDR_5 (0x20UL << HCSPLT_PRTADDR_Pos) // 0x00000020 */ +#define HCSPLT_PRTADDR_6 (0x40UL << HCSPLT_PRTADDR_Pos) // 0x00000040 */ #define HCSPLT_HUBADDR_Pos (7U) -#define HCSPLT_HUBADDR_Msk (0x7FUL << HCSPLT_HUBADDR_Pos) /*!< 0x00003F80 */ -#define HCSPLT_HUBADDR HCSPLT_HUBADDR_Msk /*!< Hub address */ -#define HCSPLT_HUBADDR_0 (0x01UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000080 */ -#define HCSPLT_HUBADDR_1 (0x02UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000100 */ -#define HCSPLT_HUBADDR_2 (0x04UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000200 */ -#define HCSPLT_HUBADDR_3 (0x08UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000400 */ -#define HCSPLT_HUBADDR_4 (0x10UL << HCSPLT_HUBADDR_Pos) /*!< 0x00000800 */ -#define HCSPLT_HUBADDR_5 (0x20UL << HCSPLT_HUBADDR_Pos) /*!< 0x00001000 */ -#define HCSPLT_HUBADDR_6 (0x40UL << HCSPLT_HUBADDR_Pos) /*!< 0x00002000 */ +#define HCSPLT_HUBADDR_Msk (0x7FUL << HCSPLT_HUBADDR_Pos) // 0x00003F80 */ +#define HCSPLT_HUBADDR HCSPLT_HUBADDR_Msk // Hub address */ +#define HCSPLT_HUBADDR_0 (0x01UL << HCSPLT_HUBADDR_Pos) // 0x00000080 */ +#define HCSPLT_HUBADDR_1 (0x02UL << HCSPLT_HUBADDR_Pos) // 0x00000100 */ +#define HCSPLT_HUBADDR_2 (0x04UL << HCSPLT_HUBADDR_Pos) // 0x00000200 */ +#define HCSPLT_HUBADDR_3 (0x08UL << HCSPLT_HUBADDR_Pos) // 0x00000400 */ +#define HCSPLT_HUBADDR_4 (0x10UL << HCSPLT_HUBADDR_Pos) // 0x00000800 */ +#define HCSPLT_HUBADDR_5 (0x20UL << HCSPLT_HUBADDR_Pos) // 0x00001000 */ +#define HCSPLT_HUBADDR_6 (0x40UL << HCSPLT_HUBADDR_Pos) // 0x00002000 */ #define HCSPLT_XACTPOS_Pos (14U) -#define HCSPLT_XACTPOS_Msk (0x3UL << HCSPLT_XACTPOS_Pos) /*!< 0x0000C000 */ -#define HCSPLT_XACTPOS HCSPLT_XACTPOS_Msk /*!< XACTPOS */ -#define HCSPLT_XACTPOS_0 (0x1UL << HCSPLT_XACTPOS_Pos) /*!< 0x00004000 */ -#define HCSPLT_XACTPOS_1 (0x2UL << HCSPLT_XACTPOS_Pos) /*!< 0x00008000 */ +#define HCSPLT_XACTPOS_Msk (0x3UL << HCSPLT_XACTPOS_Pos) // 0x0000C000 */ +#define HCSPLT_XACTPOS HCSPLT_XACTPOS_Msk // XACTPOS */ +#define HCSPLT_XACTPOS_0 (0x1UL << HCSPLT_XACTPOS_Pos) // 0x00004000 */ +#define HCSPLT_XACTPOS_1 (0x2UL << HCSPLT_XACTPOS_Pos) // 0x00008000 */ #define HCSPLT_COMPLSPLT_Pos (16U) -#define HCSPLT_COMPLSPLT_Msk (0x1UL << HCSPLT_COMPLSPLT_Pos) /*!< 0x00010000 */ -#define HCSPLT_COMPLSPLT HCSPLT_COMPLSPLT_Msk /*!< Do complete split */ +#define HCSPLT_COMPLSPLT_Msk (0x1UL << HCSPLT_COMPLSPLT_Pos) // 0x00010000 */ +#define HCSPLT_COMPLSPLT HCSPLT_COMPLSPLT_Msk // Do complete split */ #define HCSPLT_SPLITEN_Pos (31U) -#define HCSPLT_SPLITEN_Msk (0x1UL << HCSPLT_SPLITEN_Pos) /*!< 0x80000000 */ -#define HCSPLT_SPLITEN HCSPLT_SPLITEN_Msk /*!< Split enable */ +#define HCSPLT_SPLITEN_Msk (0x1UL << HCSPLT_SPLITEN_Pos) // 0x80000000 */ +#define HCSPLT_SPLITEN HCSPLT_SPLITEN_Msk // Split enable */ /******************** Bit definition for HCINT register ********************/ #define HCINT_XFRC_Pos (0U) -#define HCINT_XFRC_Msk (0x1UL << HCINT_XFRC_Pos) /*!< 0x00000001 */ -#define HCINT_XFRC HCINT_XFRC_Msk /*!< Transfer completed */ +#define HCINT_XFRC_Msk (0x1UL << HCINT_XFRC_Pos) // 0x00000001 */ +#define HCINT_XFRC HCINT_XFRC_Msk // Transfer completed */ #define HCINT_CHH_Pos (1U) -#define HCINT_CHH_Msk (0x1UL << HCINT_CHH_Pos) /*!< 0x00000002 */ -#define HCINT_CHH HCINT_CHH_Msk /*!< Channel halted */ +#define HCINT_CHH_Msk (0x1UL << HCINT_CHH_Pos) // 0x00000002 */ +#define HCINT_CHH HCINT_CHH_Msk // Channel halted */ #define HCINT_AHBERR_Pos (2U) -#define HCINT_AHBERR_Msk (0x1UL << HCINT_AHBERR_Pos) /*!< 0x00000004 */ -#define HCINT_AHBERR HCINT_AHBERR_Msk /*!< AHB error */ +#define HCINT_AHBERR_Msk (0x1UL << HCINT_AHBERR_Pos) // 0x00000004 */ +#define HCINT_AHBERR HCINT_AHBERR_Msk // AHB error */ #define HCINT_STALL_Pos (3U) -#define HCINT_STALL_Msk (0x1UL << HCINT_STALL_Pos) /*!< 0x00000008 */ -#define HCINT_STALL HCINT_STALL_Msk /*!< STALL response received interrupt */ +#define HCINT_STALL_Msk (0x1UL << HCINT_STALL_Pos) // 0x00000008 */ +#define HCINT_STALL HCINT_STALL_Msk // STALL response received interrupt */ #define HCINT_NAK_Pos (4U) -#define HCINT_NAK_Msk (0x1UL << HCINT_NAK_Pos) /*!< 0x00000010 */ -#define HCINT_NAK HCINT_NAK_Msk /*!< NAK response received interrupt */ +#define HCINT_NAK_Msk (0x1UL << HCINT_NAK_Pos) // 0x00000010 */ +#define HCINT_NAK HCINT_NAK_Msk // NAK response received interrupt */ #define HCINT_ACK_Pos (5U) -#define HCINT_ACK_Msk (0x1UL << HCINT_ACK_Pos) /*!< 0x00000020 */ -#define HCINT_ACK HCINT_ACK_Msk /*!< ACK response received/transmitted interrupt */ +#define HCINT_ACK_Msk (0x1UL << HCINT_ACK_Pos) // 0x00000020 */ +#define HCINT_ACK HCINT_ACK_Msk // ACK response received/transmitted interrupt */ #define HCINT_NYET_Pos (6U) -#define HCINT_NYET_Msk (0x1UL << HCINT_NYET_Pos) /*!< 0x00000040 */ -#define HCINT_NYET HCINT_NYET_Msk /*!< Response received interrupt */ +#define HCINT_NYET_Msk (0x1UL << HCINT_NYET_Pos) // 0x00000040 */ +#define HCINT_NYET HCINT_NYET_Msk // Response received interrupt */ #define HCINT_TXERR_Pos (7U) -#define HCINT_TXERR_Msk (0x1UL << HCINT_TXERR_Pos) /*!< 0x00000080 */ -#define HCINT_TXERR HCINT_TXERR_Msk /*!< Transaction error */ +#define HCINT_TXERR_Msk (0x1UL << HCINT_TXERR_Pos) // 0x00000080 */ +#define HCINT_TXERR HCINT_TXERR_Msk // Transaction error */ #define HCINT_BBERR_Pos (8U) -#define HCINT_BBERR_Msk (0x1UL << HCINT_BBERR_Pos) /*!< 0x00000100 */ -#define HCINT_BBERR HCINT_BBERR_Msk /*!< Babble error */ +#define HCINT_BBERR_Msk (0x1UL << HCINT_BBERR_Pos) // 0x00000100 */ +#define HCINT_BBERR HCINT_BBERR_Msk // Babble error */ #define HCINT_FRMOR_Pos (9U) -#define HCINT_FRMOR_Msk (0x1UL << HCINT_FRMOR_Pos) /*!< 0x00000200 */ -#define HCINT_FRMOR HCINT_FRMOR_Msk /*!< Frame overrun */ +#define HCINT_FRMOR_Msk (0x1UL << HCINT_FRMOR_Pos) // 0x00000200 */ +#define HCINT_FRMOR HCINT_FRMOR_Msk // Frame overrun */ #define HCINT_DTERR_Pos (10U) -#define HCINT_DTERR_Msk (0x1UL << HCINT_DTERR_Pos) /*!< 0x00000400 */ -#define HCINT_DTERR HCINT_DTERR_Msk /*!< Data toggle error */ +#define HCINT_DTERR_Msk (0x1UL << HCINT_DTERR_Pos) // 0x00000400 */ +#define HCINT_DTERR HCINT_DTERR_Msk // Data toggle error */ /******************** Bit definition for DIEPINT register ********************/ #define DIEPINT_XFRC_Pos (0U) -#define DIEPINT_XFRC_Msk (0x1UL << DIEPINT_XFRC_Pos) /*!< 0x00000001 */ -#define DIEPINT_XFRC DIEPINT_XFRC_Msk /*!< Transfer completed interrupt */ +#define DIEPINT_XFRC_Msk (0x1UL << DIEPINT_XFRC_Pos) // 0x00000001 */ +#define DIEPINT_XFRC DIEPINT_XFRC_Msk // Transfer completed interrupt */ #define DIEPINT_EPDISD_Pos (1U) -#define DIEPINT_EPDISD_Msk (0x1UL << DIEPINT_EPDISD_Pos) /*!< 0x00000002 */ -#define DIEPINT_EPDISD DIEPINT_EPDISD_Msk /*!< Endpoint disabled interrupt */ +#define DIEPINT_EPDISD_Msk (0x1UL << DIEPINT_EPDISD_Pos) // 0x00000002 */ +#define DIEPINT_EPDISD DIEPINT_EPDISD_Msk // Endpoint disabled interrupt */ #define DIEPINT_AHBERR_Pos (2U) -#define DIEPINT_AHBERR_Msk (0x1UL << DIEPINT_AHBERR_Pos) /*!< 0x00000004 */ -#define DIEPINT_AHBERR DIEPINT_AHBERR_Msk /*!< AHB Error (AHBErr) during an IN transaction */ +#define DIEPINT_AHBERR_Msk (0x1UL << DIEPINT_AHBERR_Pos) // 0x00000004 */ +#define DIEPINT_AHBERR DIEPINT_AHBERR_Msk // AHB Error (AHBErr) during an IN transaction */ #define DIEPINT_TOC_Pos (3U) -#define DIEPINT_TOC_Msk (0x1UL << DIEPINT_TOC_Pos) /*!< 0x00000008 */ -#define DIEPINT_TOC DIEPINT_TOC_Msk /*!< Timeout condition */ +#define DIEPINT_TOC_Msk (0x1UL << DIEPINT_TOC_Pos) // 0x00000008 */ +#define DIEPINT_TOC DIEPINT_TOC_Msk // Timeout condition */ #define DIEPINT_ITTXFE_Pos (4U) -#define DIEPINT_ITTXFE_Msk (0x1UL << DIEPINT_ITTXFE_Pos) /*!< 0x00000010 */ -#define DIEPINT_ITTXFE DIEPINT_ITTXFE_Msk /*!< IN token received when TxFIFO is empty */ +#define DIEPINT_ITTXFE_Msk (0x1UL << DIEPINT_ITTXFE_Pos) // 0x00000010 */ +#define DIEPINT_ITTXFE DIEPINT_ITTXFE_Msk // IN token received when TxFIFO is empty */ #define DIEPINT_INEPNM_Pos (5U) -#define DIEPINT_INEPNM_Msk (0x1UL << DIEPINT_INEPNM_Pos) /*!< 0x00000020 */ -#define DIEPINT_INEPNM DIEPINT_INEPNM_Msk /*!< IN token received with EP mismatch */ +#define DIEPINT_INEPNM_Msk (0x1UL << DIEPINT_INEPNM_Pos) // 0x00000020 */ +#define DIEPINT_INEPNM DIEPINT_INEPNM_Msk // IN token received with EP mismatch */ #define DIEPINT_INEPNE_Pos (6U) -#define DIEPINT_INEPNE_Msk (0x1UL << DIEPINT_INEPNE_Pos) /*!< 0x00000040 */ -#define DIEPINT_INEPNE DIEPINT_INEPNE_Msk /*!< IN endpoint NAK effective */ +#define DIEPINT_INEPNE_Msk (0x1UL << DIEPINT_INEPNE_Pos) // 0x00000040 */ +#define DIEPINT_INEPNE DIEPINT_INEPNE_Msk // IN endpoint NAK effective */ #define DIEPINT_TXFE_Pos (7U) -#define DIEPINT_TXFE_Msk (0x1UL << DIEPINT_TXFE_Pos) /*!< 0x00000080 */ -#define DIEPINT_TXFE DIEPINT_TXFE_Msk /*!< Transmit FIFO empty */ +#define DIEPINT_TXFE_Msk (0x1UL << DIEPINT_TXFE_Pos) // 0x00000080 */ +#define DIEPINT_TXFE DIEPINT_TXFE_Msk // Transmit FIFO empty */ #define DIEPINT_TXFIFOUDRN_Pos (8U) -#define DIEPINT_TXFIFOUDRN_Msk (0x1UL << DIEPINT_TXFIFOUDRN_Pos) /*!< 0x00000100 */ -#define DIEPINT_TXFIFOUDRN DIEPINT_TXFIFOUDRN_Msk /*!< Transmit Fifo Underrun */ +#define DIEPINT_TXFIFOUDRN_Msk (0x1UL << DIEPINT_TXFIFOUDRN_Pos) // 0x00000100 */ +#define DIEPINT_TXFIFOUDRN DIEPINT_TXFIFOUDRN_Msk // Transmit Fifo Underrun */ #define DIEPINT_BNA_Pos (9U) -#define DIEPINT_BNA_Msk (0x1UL << DIEPINT_BNA_Pos) /*!< 0x00000200 */ -#define DIEPINT_BNA DIEPINT_BNA_Msk /*!< Buffer not available interrupt */ +#define DIEPINT_BNA_Msk (0x1UL << DIEPINT_BNA_Pos) // 0x00000200 */ +#define DIEPINT_BNA DIEPINT_BNA_Msk // Buffer not available interrupt */ #define DIEPINT_PKTDRPSTS_Pos (11U) -#define DIEPINT_PKTDRPSTS_Msk (0x1UL << DIEPINT_PKTDRPSTS_Pos) /*!< 0x00000800 */ -#define DIEPINT_PKTDRPSTS DIEPINT_PKTDRPSTS_Msk /*!< Packet dropped status */ +#define DIEPINT_PKTDRPSTS_Msk (0x1UL << DIEPINT_PKTDRPSTS_Pos) // 0x00000800 */ +#define DIEPINT_PKTDRPSTS DIEPINT_PKTDRPSTS_Msk // Packet dropped status */ #define DIEPINT_BERR_Pos (12U) -#define DIEPINT_BERR_Msk (0x1UL << DIEPINT_BERR_Pos) /*!< 0x00001000 */ -#define DIEPINT_BERR DIEPINT_BERR_Msk /*!< Babble error interrupt */ +#define DIEPINT_BERR_Msk (0x1UL << DIEPINT_BERR_Pos) // 0x00001000 */ +#define DIEPINT_BERR DIEPINT_BERR_Msk // Babble error interrupt */ #define DIEPINT_NAK_Pos (13U) -#define DIEPINT_NAK_Msk (0x1UL << DIEPINT_NAK_Pos) /*!< 0x00002000 */ -#define DIEPINT_NAK DIEPINT_NAK_Msk /*!< NAK interrupt */ +#define DIEPINT_NAK_Msk (0x1UL << DIEPINT_NAK_Pos) // 0x00002000 */ +#define DIEPINT_NAK DIEPINT_NAK_Msk // NAK interrupt */ /******************** Bit definition for HCINTMSK register ********************/ #define HCINTMSK_XFRCM_Pos (0U) -#define HCINTMSK_XFRCM_Msk (0x1UL << HCINTMSK_XFRCM_Pos) /*!< 0x00000001 */ -#define HCINTMSK_XFRCM HCINTMSK_XFRCM_Msk /*!< Transfer completed mask */ +#define HCINTMSK_XFRCM_Msk (0x1UL << HCINTMSK_XFRCM_Pos) // 0x00000001 */ +#define HCINTMSK_XFRCM HCINTMSK_XFRCM_Msk // Transfer completed mask */ #define HCINTMSK_CHHM_Pos (1U) -#define HCINTMSK_CHHM_Msk (0x1UL << HCINTMSK_CHHM_Pos) /*!< 0x00000002 */ -#define HCINTMSK_CHHM HCINTMSK_CHHM_Msk /*!< Channel halted mask */ +#define HCINTMSK_CHHM_Msk (0x1UL << HCINTMSK_CHHM_Pos) // 0x00000002 */ +#define HCINTMSK_CHHM HCINTMSK_CHHM_Msk // Channel halted mask */ #define HCINTMSK_AHBERR_Pos (2U) -#define HCINTMSK_AHBERR_Msk (0x1UL << HCINTMSK_AHBERR_Pos) /*!< 0x00000004 */ -#define HCINTMSK_AHBERR HCINTMSK_AHBERR_Msk /*!< AHB error */ +#define HCINTMSK_AHBERR_Msk (0x1UL << HCINTMSK_AHBERR_Pos) // 0x00000004 */ +#define HCINTMSK_AHBERR HCINTMSK_AHBERR_Msk // AHB error */ #define HCINTMSK_STALLM_Pos (3U) -#define HCINTMSK_STALLM_Msk (0x1UL << HCINTMSK_STALLM_Pos) /*!< 0x00000008 */ -#define HCINTMSK_STALLM HCINTMSK_STALLM_Msk /*!< STALL response received interrupt mask */ +#define HCINTMSK_STALLM_Msk (0x1UL << HCINTMSK_STALLM_Pos) // 0x00000008 */ +#define HCINTMSK_STALLM HCINTMSK_STALLM_Msk // STALL response received interrupt mask */ #define HCINTMSK_NAKM_Pos (4U) -#define HCINTMSK_NAKM_Msk (0x1UL << HCINTMSK_NAKM_Pos) /*!< 0x00000010 */ -#define HCINTMSK_NAKM HCINTMSK_NAKM_Msk /*!< NAK response received interrupt mask */ +#define HCINTMSK_NAKM_Msk (0x1UL << HCINTMSK_NAKM_Pos) // 0x00000010 */ +#define HCINTMSK_NAKM HCINTMSK_NAKM_Msk // NAK response received interrupt mask */ #define HCINTMSK_ACKM_Pos (5U) -#define HCINTMSK_ACKM_Msk (0x1UL << HCINTMSK_ACKM_Pos) /*!< 0x00000020 */ -#define HCINTMSK_ACKM HCINTMSK_ACKM_Msk /*!< ACK response received/transmitted interrupt mask */ +#define HCINTMSK_ACKM_Msk (0x1UL << HCINTMSK_ACKM_Pos) // 0x00000020 */ +#define HCINTMSK_ACKM HCINTMSK_ACKM_Msk // ACK response received/transmitted interrupt mask */ #define HCINTMSK_NYET_Pos (6U) -#define HCINTMSK_NYET_Msk (0x1UL << HCINTMSK_NYET_Pos) /*!< 0x00000040 */ -#define HCINTMSK_NYET HCINTMSK_NYET_Msk /*!< response received interrupt mask */ +#define HCINTMSK_NYET_Msk (0x1UL << HCINTMSK_NYET_Pos) // 0x00000040 */ +#define HCINTMSK_NYET HCINTMSK_NYET_Msk // response received interrupt mask */ #define HCINTMSK_TXERRM_Pos (7U) -#define HCINTMSK_TXERRM_Msk (0x1UL << HCINTMSK_TXERRM_Pos) /*!< 0x00000080 */ -#define HCINTMSK_TXERRM HCINTMSK_TXERRM_Msk /*!< Transaction error mask */ +#define HCINTMSK_TXERRM_Msk (0x1UL << HCINTMSK_TXERRM_Pos) // 0x00000080 */ +#define HCINTMSK_TXERRM HCINTMSK_TXERRM_Msk // Transaction error mask */ #define HCINTMSK_BBERRM_Pos (8U) -#define HCINTMSK_BBERRM_Msk (0x1UL << HCINTMSK_BBERRM_Pos) /*!< 0x00000100 */ -#define HCINTMSK_BBERRM HCINTMSK_BBERRM_Msk /*!< Babble error mask */ +#define HCINTMSK_BBERRM_Msk (0x1UL << HCINTMSK_BBERRM_Pos) // 0x00000100 */ +#define HCINTMSK_BBERRM HCINTMSK_BBERRM_Msk // Babble error mask */ #define HCINTMSK_FRMORM_Pos (9U) -#define HCINTMSK_FRMORM_Msk (0x1UL << HCINTMSK_FRMORM_Pos) /*!< 0x00000200 */ -#define HCINTMSK_FRMORM HCINTMSK_FRMORM_Msk /*!< Frame overrun mask */ +#define HCINTMSK_FRMORM_Msk (0x1UL << HCINTMSK_FRMORM_Pos) // 0x00000200 */ +#define HCINTMSK_FRMORM HCINTMSK_FRMORM_Msk // Frame overrun mask */ #define HCINTMSK_DTERRM_Pos (10U) -#define HCINTMSK_DTERRM_Msk (0x1UL << HCINTMSK_DTERRM_Pos) /*!< 0x00000400 */ -#define HCINTMSK_DTERRM HCINTMSK_DTERRM_Msk /*!< Data toggle error mask */ +#define HCINTMSK_DTERRM_Msk (0x1UL << HCINTMSK_DTERRM_Pos) // 0x00000400 */ +#define HCINTMSK_DTERRM HCINTMSK_DTERRM_Msk // Data toggle error mask */ /******************** Bit definition for DIEPTSIZ register ********************/ #define DIEPTSIZ_XFRSIZ_Pos (0U) -#define DIEPTSIZ_XFRSIZ_Msk (0x7FFFFUL << DIEPTSIZ_XFRSIZ_Pos) /*!< 0x0007FFFF */ -#define DIEPTSIZ_XFRSIZ DIEPTSIZ_XFRSIZ_Msk /*!< Transfer size */ +#define DIEPTSIZ_XFRSIZ_Msk (0x7FFFFUL << DIEPTSIZ_XFRSIZ_Pos) // 0x0007FFFF */ +#define DIEPTSIZ_XFRSIZ DIEPTSIZ_XFRSIZ_Msk // Transfer size */ #define DIEPTSIZ_PKTCNT_Pos (19U) -#define DIEPTSIZ_PKTCNT_Msk (0x3FFUL << DIEPTSIZ_PKTCNT_Pos) /*!< 0x1FF80000 */ -#define DIEPTSIZ_PKTCNT DIEPTSIZ_PKTCNT_Msk /*!< Packet count */ +#define DIEPTSIZ_PKTCNT_Msk (0x3FFUL << DIEPTSIZ_PKTCNT_Pos) // 0x1FF80000 */ +#define DIEPTSIZ_PKTCNT DIEPTSIZ_PKTCNT_Msk // Packet count */ #define DIEPTSIZ_MULCNT_Pos (29U) -#define DIEPTSIZ_MULCNT_Msk (0x3UL << DIEPTSIZ_MULCNT_Pos) /*!< 0x60000000 */ -#define DIEPTSIZ_MULCNT DIEPTSIZ_MULCNT_Msk /*!< Packet count */ +#define DIEPTSIZ_MULCNT_Msk (0x3UL << DIEPTSIZ_MULCNT_Pos) // 0x60000000 */ +#define DIEPTSIZ_MULCNT DIEPTSIZ_MULCNT_Msk // Packet count */ /******************** Bit definition for HCTSIZ register ********************/ #define HCTSIZ_XFRSIZ_Pos (0U) -#define HCTSIZ_XFRSIZ_Msk (0x7FFFFUL << HCTSIZ_XFRSIZ_Pos) /*!< 0x0007FFFF */ -#define HCTSIZ_XFRSIZ HCTSIZ_XFRSIZ_Msk /*!< Transfer size */ +#define HCTSIZ_XFRSIZ_Msk (0x7FFFFUL << HCTSIZ_XFRSIZ_Pos) // 0x0007FFFF */ +#define HCTSIZ_XFRSIZ HCTSIZ_XFRSIZ_Msk // Transfer size */ #define HCTSIZ_PKTCNT_Pos (19U) -#define HCTSIZ_PKTCNT_Msk (0x3FFUL << HCTSIZ_PKTCNT_Pos) /*!< 0x1FF80000 */ -#define HCTSIZ_PKTCNT HCTSIZ_PKTCNT_Msk /*!< Packet count */ +#define HCTSIZ_PKTCNT_Msk (0x3FFUL << HCTSIZ_PKTCNT_Pos) // 0x1FF80000 */ +#define HCTSIZ_PKTCNT HCTSIZ_PKTCNT_Msk // Packet count */ #define HCTSIZ_DOPING_Pos (31U) -#define HCTSIZ_DOPING_Msk (0x1UL << HCTSIZ_DOPING_Pos) /*!< 0x80000000 */ -#define HCTSIZ_DOPING HCTSIZ_DOPING_Msk /*!< Do PING */ +#define HCTSIZ_DOPING_Msk (0x1UL << HCTSIZ_DOPING_Pos) // 0x80000000 */ +#define HCTSIZ_DOPING HCTSIZ_DOPING_Msk // Do PING */ #define HCTSIZ_DPID_Pos (29U) -#define HCTSIZ_DPID_Msk (0x3UL << HCTSIZ_DPID_Pos) /*!< 0x60000000 */ -#define HCTSIZ_DPID HCTSIZ_DPID_Msk /*!< Data PID */ -#define HCTSIZ_DPID_0 (0x1UL << HCTSIZ_DPID_Pos) /*!< 0x20000000 */ -#define HCTSIZ_DPID_1 (0x2UL << HCTSIZ_DPID_Pos) /*!< 0x40000000 */ +#define HCTSIZ_DPID_Msk (0x3UL << HCTSIZ_DPID_Pos) // 0x60000000 */ +#define HCTSIZ_DPID HCTSIZ_DPID_Msk // Data PID */ +#define HCTSIZ_DPID_0 (0x1UL << HCTSIZ_DPID_Pos) // 0x20000000 */ +#define HCTSIZ_DPID_1 (0x2UL << HCTSIZ_DPID_Pos) // 0x40000000 */ /******************** Bit definition for DIEPDMA register ********************/ #define DIEPDMA_DMAADDR_Pos (0U) -#define DIEPDMA_DMAADDR_Msk (0xFFFFFFFFUL << DIEPDMA_DMAADDR_Pos) /*!< 0xFFFFFFFF */ -#define DIEPDMA_DMAADDR DIEPDMA_DMAADDR_Msk /*!< DMA address */ +#define DIEPDMA_DMAADDR_Msk (0xFFFFFFFFUL << DIEPDMA_DMAADDR_Pos) // 0xFFFFFFFF */ +#define DIEPDMA_DMAADDR DIEPDMA_DMAADDR_Msk // DMA address */ /******************** Bit definition for HCDMA register ********************/ #define HCDMA_DMAADDR_Pos (0U) -#define HCDMA_DMAADDR_Msk (0xFFFFFFFFUL << HCDMA_DMAADDR_Pos) /*!< 0xFFFFFFFF */ -#define HCDMA_DMAADDR HCDMA_DMAADDR_Msk /*!< DMA address */ +#define HCDMA_DMAADDR_Msk (0xFFFFFFFFUL << HCDMA_DMAADDR_Pos) // 0xFFFFFFFF */ +#define HCDMA_DMAADDR HCDMA_DMAADDR_Msk // DMA address */ /******************** Bit definition for DTXFSTS register ********************/ #define DTXFSTS_INEPTFSAV_Pos (0U) -#define DTXFSTS_INEPTFSAV_Msk (0xFFFFUL << DTXFSTS_INEPTFSAV_Pos) /*!< 0x0000FFFF */ -#define DTXFSTS_INEPTFSAV DTXFSTS_INEPTFSAV_Msk /*!< IN endpoint TxFIFO space available */ +#define DTXFSTS_INEPTFSAV_Msk (0xFFFFUL << DTXFSTS_INEPTFSAV_Pos) // 0x0000FFFF */ +#define DTXFSTS_INEPTFSAV DTXFSTS_INEPTFSAV_Msk // IN endpoint TxFIFO space available */ /******************** Bit definition for DIEPTXF register ********************/ #define DIEPTXF_INEPTXSA_Pos (0U) -#define DIEPTXF_INEPTXSA_Msk (0xFFFFUL << DIEPTXF_INEPTXSA_Pos) /*!< 0x0000FFFF */ -#define DIEPTXF_INEPTXSA DIEPTXF_INEPTXSA_Msk /*!< IN endpoint FIFOx transmit RAM start address */ +#define DIEPTXF_INEPTXSA_Msk (0xFFFFUL << DIEPTXF_INEPTXSA_Pos) // 0x0000FFFF */ +#define DIEPTXF_INEPTXSA DIEPTXF_INEPTXSA_Msk // IN endpoint FIFOx transmit RAM start address */ #define DIEPTXF_INEPTXFD_Pos (16U) -#define DIEPTXF_INEPTXFD_Msk (0xFFFFUL << DIEPTXF_INEPTXFD_Pos) /*!< 0xFFFF0000 */ -#define DIEPTXF_INEPTXFD DIEPTXF_INEPTXFD_Msk /*!< IN endpoint TxFIFO depth */ +#define DIEPTXF_INEPTXFD_Msk (0xFFFFUL << DIEPTXF_INEPTXFD_Pos) // 0xFFFF0000 */ +#define DIEPTXF_INEPTXFD DIEPTXF_INEPTXFD_Msk // IN endpoint TxFIFO depth */ /******************** Bit definition for DOEPCTL register ********************/ #define DOEPCTL_MPSIZ_Pos (0U) -#define DOEPCTL_MPSIZ_Msk (0x7FFUL << DOEPCTL_MPSIZ_Pos) /*!< 0x000007FF */ -#define DOEPCTL_MPSIZ DOEPCTL_MPSIZ_Msk /*!< Maximum packet size */ /*! Date: Tue, 26 Oct 2021 11:11:46 +0700 Subject: [PATCH 21/51] more rename --- src/portable/synopsys/dwc2/dcd_dwc2.c | 189 +++++++++++------------- src/portable/synopsys/dwc2/dwc2_esp32.h | 2 +- src/portable/synopsys/dwc2/dwc2_gd32.h | 2 +- src/portable/synopsys/dwc2/dwc2_stm32.h | 2 +- src/portable/synopsys/dwc2/dwc2_type.h | 8 +- 5 files changed, 97 insertions(+), 106 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index b98bd0055..c0bf655f4 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -51,8 +51,7 @@ // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ -#define CORE_REG(_port) ((dwc2_core_t*) DWC2_REG_BASE) -#define DEVICE_REG(_port) CORE_REG(_port) //((dwc2_core_t*) (DWC2_REG_BASE + DWC2_DEVICE_BASE)) +#define DWC2_REG(_port) ((dwc2_regs_t*) DWC2_REG_BASE) #define EPIN_REG(_port) ((dwc2_epin_t*) (DWC2_REG_BASE + DWC2_IN_ENDPOINT_BASE)) #define EPOUT_REG(_port) ((dwc2_epout_t*) (DWC2_REG_BASE + DWC2_OUT_ENDPOINT_BASE)) #define FIFO_BASE(_port, _x) ((volatile uint32_t*) (DWC2_REG_BASE + DWC2_FIFO_BASE + (_x) * DWC2_FIFO_SIZE)) @@ -98,7 +97,7 @@ static void update_grxfsiz(uint8_t rhport) { (void) rhport; - dwc2_core_t * core = CORE_REG(rhport); + dwc2_regs_t * core = DWC2_REG(rhport); // Determine largest EP size for RX FIFO uint16_t max_epsize = 0; @@ -116,8 +115,7 @@ static void bus_reset(uint8_t rhport) { (void) rhport; - dwc2_core_t * core = CORE_REG(rhport); - dwc2_core_t * dev = DEVICE_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); @@ -125,7 +123,7 @@ static void bus_reset(uint8_t rhport) _out_ep_closed = false; // clear device address - dev->dcfg &= ~DCFG_DAD_Msk; + dwc2->dcfg &= ~DCFG_DAD_Msk; // 1. NAK for all OUT endpoints for(uint8_t n = 0; n < DWC2_EP_MAX; n++) { @@ -133,9 +131,9 @@ static void bus_reset(uint8_t rhport) } // 2. Un-mask interrupt bits - dev->daintmsk = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); - dev->doepmsk = DOEPMSK_STUPM | DOEPMSK_XFRCM; - dev->diepmsk = DIEPMSK_TOM | DIEPMSK_XFRCM; + dwc2->daintmsk = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); + dwc2->doepmsk = DOEPMSK_STUPM | DOEPMSK_XFRCM; + dwc2->diepmsk = DIEPMSK_TOM | DIEPMSK_XFRCM; // "USB Data FIFOs" section in reference manual // Peripheral FIFO architecture @@ -187,12 +185,12 @@ static void bus_reset(uint8_t rhport) // are enabled at least "2 x (Largest-EPsize/4) + 1" are recommended. Maybe provide a macro for application to // overwrite this. - core->grxfsiz = calc_rx_ff_size(TUD_OPT_HIGH_SPEED ? 512 : 64); + dwc2->grxfsiz = calc_rx_ff_size(TUD_OPT_HIGH_SPEED ? 512 : 64); _allocated_fifo_words_tx = 16; // Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) - core->dieptxf0 = (16 << TX0FD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + dwc2->dieptxf0 = (16 << TX0FD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); // Fixed control EP0 size to 64 bytes in_ep[0].DIEPCTL &= ~(0x03 << DIEPCTL_MPSIZ_Pos); @@ -200,15 +198,15 @@ static void bus_reset(uint8_t rhport) out_ep[0].DOEPTSIZ |= (3 << DOEPTSIZ_STUPCNT_Pos); - core->gintmsk |= GINTMSK_OEPINT | GINTMSK_IEPINT; + dwc2->gintmsk |= GINTMSK_OEPINT | GINTMSK_IEPINT; } static tusb_speed_t get_speed(uint8_t rhport) { (void) rhport; - dwc2_core_t * dev = DEVICE_REG(rhport); - uint32_t const enum_spd = (dev->dsts & DSTS_ENUMSPD_Msk) >> DSTS_ENUMSPD_Pos; + dwc2_regs_t * dwc2 = DWC2_REG(rhport); + uint32_t const enum_spd = (dwc2->dsts & DSTS_ENUMSPD_Msk) >> DSTS_ENUMSPD_Pos; return (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL; } @@ -225,11 +223,11 @@ static void set_speed(uint8_t rhport, tusb_speed_t speed) bitvalue = DCD_FULL_SPEED; } - dwc2_core_t * dev = DEVICE_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); // Clear and set speed bits - dev->dcfg &= ~(3 << DCFG_DSPD_Pos); - dev->dcfg |= (bitvalue << DCFG_DSPD_Pos); + dwc2->dcfg &= ~(3 << DCFG_DSPD_Pos); + dwc2->dcfg |= (bitvalue << DCFG_DSPD_Pos); } #if defined(USB_HS_PHYC) @@ -277,7 +275,7 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c { (void) rhport; - dwc2_core_t * dev = DEVICE_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); @@ -301,12 +299,12 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c if ((in_ep[epnum].DIEPCTL & DIEPCTL_EPTYP) == DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) { // Take odd/even bit from frame counter. - uint32_t const odd_frame_now = (dev->dsts & (1u << DSTS_FNSOF_Pos)); + uint32_t const odd_frame_now = (dwc2->dsts & (1u << DSTS_FNSOF_Pos)); in_ep[epnum].DIEPCTL |= (odd_frame_now ? DIEPCTL_SD0PID_SEVNFRM_Msk : DIEPCTL_SODDFRM_Msk); } // Enable fifo empty interrupt only if there are something to put in the fifo. if(total_bytes != 0) { - dev->diepempmsk |= (1 << epnum); + dwc2->diepempmsk |= (1 << epnum); } } else { // A full OUT transfer (multiple packets, possibly) triggers XFRC. @@ -318,7 +316,7 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c if ((out_ep[epnum].DOEPCTL & DOEPCTL_EPTYP) == DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) { // Take odd/even bit from frame counter. - uint32_t const odd_frame_now = (dev->dsts & (1u << DSTS_FNSOF_Pos)); + uint32_t const odd_frame_now = (dwc2->dsts & (1u << DSTS_FNSOF_Pos)); out_ep[epnum].DOEPCTL |= (odd_frame_now ? DOEPCTL_SD0PID_SEVNFRM_Msk : DOEPCTL_SODDFRM_Msk); } } @@ -331,7 +329,7 @@ void dcd_init (uint8_t rhport) { // Programming model begins in the last section of the chapter on the USB // peripheral in each Reference Manual. - dwc2_core_t * core = CORE_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); // check GSNPSID @@ -341,23 +339,23 @@ void dcd_init (uint8_t rhport) // On selected MCUs HS port1 can be used with external PHY via ULPI interface #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED // deactivate internal PHY - core->gccfg &= ~GCCFG_PWRDWN; + dwc2->gccfg &= ~GCCFG_PWRDWN; // Init The UTMI Interface - core->gusbcfg &= ~(GUSBCFG_TSDPS | GUSBCFG_ULPIFSLS | GUSBCFG_PHYSEL); + dwc2->gusbcfg &= ~(GUSBCFG_TSDPS | GUSBCFG_ULPIFSLS | GUSBCFG_PHYSEL); // Select default internal VBUS Indicator and Drive for ULPI - core->gusbcfg &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI); + dwc2->gusbcfg &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI); #else - core->gusbcfg |= GUSBCFG_PHYSEL; + dwc2->gusbcfg |= GUSBCFG_PHYSEL; #endif #if defined(USB_HS_PHYC) // Highspeed with embedded UTMI PHYC // Select UTMI Interface - core->gusbcfg &= ~GUSBCFG_ULPI_UTMI_SEL; - core->gccfg |= GCCFG_PHYHSEN; + dwc2->gusbcfg &= ~GUSBCFG_ULPI_UTMI_SEL; + dwc2->gccfg |= GCCFG_PHYHSEN; // Enables control of a High Speed USB PHY USB_HS_PHYCInit(); @@ -365,42 +363,40 @@ void dcd_init (uint8_t rhport) } else { // Enable internal PHY - core->gusbcfg |= GUSBCFG_PHYSEL; + dwc2->gusbcfg |= GUSBCFG_PHYSEL; } // Reset core after selecting PHYst // Wait AHB IDLE, reset then wait until it is cleared - while ((core->grstctl & GRSTCTL_AHBIDL) == 0U) {} - core->grstctl |= GRSTCTL_CSRST; - while ((core->grstctl & GRSTCTL_CSRST) == GRSTCTL_CSRST) {} + while ((dwc2->grstctl & GRSTCTL_AHBIDL) == 0U) {} + dwc2->grstctl |= GRSTCTL_CSRST; + while ((dwc2->grstctl & GRSTCTL_CSRST) == GRSTCTL_CSRST) {} // Restart PHY clock *((volatile uint32_t *)(DWC2_REG_BASE + DWC2_PCGCCTL_BASE)) = 0; // Clear all interrupts - core->gintsts |= core->gintsts; + dwc2->gintsts |= dwc2->gintsts; // Required as part of core initialization. // TODO: How should mode mismatch be handled? It will cause // the core to stop working/require reset. - core->gintmsk |= GINTMSK_OTGINT | GINTMSK_MMISM; - - dwc2_core_t * dev = DEVICE_REG(rhport); + dwc2->gintmsk |= GINTMSK_OTGINT | GINTMSK_MMISM; // If USB host misbehaves during status portion of control xfer // (non zero-length packet), send STALL back and discard. - dev->dcfg |= DCFG_NZLSOHSK; + dwc2->dcfg |= DCFG_NZLSOHSK; set_speed(rhport, TUD_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL); // Enable internal USB transceiver, unless using HS core (port 1) with external PHY. - if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) core->gccfg |= GCCFG_PWRDWN; + if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) dwc2->gccfg |= GCCFG_PWRDWN; - core->gintmsk |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_USBSUSPM | + dwc2->gintmsk |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_USBSUSPM | GINTMSK_WUIM | GINTMSK_RXFLVLM; // Enable global interrupt - core->gahbcfg |= GAHBCFG_GINT; + dwc2->gahbcfg |= GAHBCFG_GINT; dcd_connect(rhport); } @@ -417,8 +413,8 @@ void dcd_int_disable (uint8_t rhport) void dcd_set_address (uint8_t rhport, uint8_t dev_addr) { - dwc2_core_t * dev = DEVICE_REG(rhport); - dev->dcfg = (dev->dcfg & ~DCFG_DAD_Msk) | (dev_addr << DCFG_DAD_Pos); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); + dwc2->dcfg = (dwc2->dcfg & ~DCFG_DAD_Msk) | (dev_addr << DCFG_DAD_Pos); // Response with status after changing device address dcd_edpt_xfer(rhport, tu_edpt_addr(0, TUSB_DIR_IN), NULL, 0); @@ -428,34 +424,33 @@ void dcd_remote_wakeup(uint8_t rhport) { (void) rhport; - dwc2_core_t * core = CORE_REG(rhport); - dwc2_core_t * dev = DEVICE_REG(rhport); + dwc2_regs_t* dwc2 = DWC2_REG(rhport); // set remote wakeup - dev->dctl |= DCTL_RWUSIG; + dwc2->dctl |= DCTL_RWUSIG; // enable SOF to detect bus resume - core->gintsts = GINTSTS_SOF; - core->gintmsk |= GINTMSK_SOFM; + dwc2->gintsts = GINTSTS_SOF; + dwc2->gintmsk |= GINTMSK_SOFM; // Per specs: remote wakeup signal bit must be clear within 1-15ms dwc2_remote_wakeup_delay(); - dev->dctl &= ~DCTL_RWUSIG; + dwc2->dctl &= ~DCTL_RWUSIG; } void dcd_connect(uint8_t rhport) { (void) rhport; - dwc2_core_t * dev = DEVICE_REG(rhport); - dev->dctl &= ~DCTL_SDIS; + dwc2_regs_t * dwc2 = DWC2_REG(rhport); + dwc2->dctl &= ~DCTL_SDIS; } void dcd_disconnect(uint8_t rhport) { (void) rhport; - dwc2_core_t * dev = DEVICE_REG(rhport); - dev->dctl |= DCTL_SDIS; + dwc2_regs_t * dwc2 = DWC2_REG(rhport); + dwc2->dctl |= DCTL_SDIS; } @@ -467,8 +462,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) { (void) rhport; - dwc2_core_t * core = CORE_REG(rhport); - dwc2_core_t * dev = DEVICE_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); @@ -489,12 +483,12 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) uint16_t const sz = calc_rx_ff_size(4*fifo_size); // If size_rx needs to be extended check if possible and if so enlarge it - if (core->grxfsiz < sz) + if (dwc2->grxfsiz < sz) { TU_ASSERT(sz + _allocated_fifo_words_tx <= DWC2_EP_FIFO_SIZE/4); // Enlarge RX FIFO - core->grxfsiz = sz; + dwc2->grxfsiz = sz; } out_ep[epnum].DOEPCTL |= (1 << DOEPCTL_USBAEP_Pos) | @@ -502,7 +496,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DOEPCTL_SD0PID_SEVNFRM : 0) | (xfer->max_size << DOEPCTL_MPSIZ_Pos); - dev->daintmsk |= (1 << (DAINTMSK_OEPM_Pos + epnum)); + dwc2->daintmsk |= (1 << (DAINTMSK_OEPM_Pos + epnum)); } else { @@ -528,7 +522,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // - IN EP 1 gets FIFO 1, IN EP "n" gets FIFO "n". // Check if free space is available - TU_ASSERT(_allocated_fifo_words_tx + fifo_size + core->grxfsiz <= DWC2_EP_FIFO_SIZE/4); + TU_ASSERT(_allocated_fifo_words_tx + fifo_size + dwc2->grxfsiz <= DWC2_EP_FIFO_SIZE/4); _allocated_fifo_words_tx += fifo_size; @@ -536,7 +530,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // DIEPTXF starts at FIFO #1. // Both TXFD and TXSA are in unit of 32-bit words. - core->dieptxf[epnum - 1] = (fifo_size << DIEPTXF_INEPTXFD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + dwc2->dieptxf[epnum - 1] = (fifo_size << DIEPTXF_INEPTXFD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); in_ep[epnum].DIEPCTL |= (1 << DIEPCTL_USBAEP_Pos) | (epnum << DIEPCTL_TXFNUM_Pos) | @@ -544,7 +538,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DIEPCTL_SD0PID_SEVNFRM : 0) | (xfer->max_size << DIEPCTL_MPSIZ_Pos); - dev->daintmsk |= (1 << (DAINTMSK_IEPM_Pos + epnum)); + dwc2->daintmsk |= (1 << (DAINTMSK_IEPM_Pos + epnum)); } return true; @@ -555,13 +549,12 @@ void dcd_edpt_close_all (uint8_t rhport) { (void) rhport; -// dwc2_core_t * core = CORE_REG(rhport); - dwc2_core_t * dev = DEVICE_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); // Disable non-control interrupt - dev->daintmsk = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); + dwc2->daintmsk = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); for(uint8_t n = 1; n < DWC2_EP_MAX; n++) { @@ -642,8 +635,7 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) { (void) rhport; - dwc2_core_t * core = CORE_REG(rhport); - dwc2_core_t * dev = DEVICE_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); @@ -671,9 +663,9 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) } // Flush the FIFO, and wait until we have confirmed it cleared. - core->grstctl |= (epnum << GRSTCTL_TXFNUM_Pos); - core->grstctl |= GRSTCTL_TXFFLSH; - while ( (core->grstctl & GRSTCTL_TXFFLSH_Msk) != 0 ) {} + dwc2->grstctl |= (epnum << GRSTCTL_TXFNUM_Pos); + dwc2->grstctl |= GRSTCTL_TXFFLSH; + while ( (dwc2->grstctl & GRSTCTL_TXFFLSH_Msk) != 0 ) {} } else { @@ -688,8 +680,8 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) // Simpler to use polling here, we don't use the "B"OUTNAKEFF interrupt // anyway, and it can't be cleared by user code. If this while loop never // finishes, we have bigger problems than just the stack. - dev->dctl |= DCTL_SGONAK; - while ( (core->gintsts & GINTSTS_BOUTNAKEFF_Msk) == 0 ) {} + dwc2->dctl |= DCTL_SGONAK; + while ( (dwc2->gintsts & GINTSTS_BOUTNAKEFF_Msk) == 0 ) {} // Ditto here- disable the endpoint. out_ep[epnum].DOEPCTL |= DOEPCTL_EPDIS | (stall ? DOEPCTL_STALL : 0); @@ -698,7 +690,7 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) out_ep[epnum].DOEPINT = DOEPINT_EPDISD; // Allow other OUT endpoints to keep receiving. - dev->dctl |= DCTL_CGONAK; + dwc2->dctl |= DCTL_CGONAK; } } } @@ -708,7 +700,7 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) */ void dcd_edpt_close (uint8_t rhport, uint8_t ep_addr) { - dwc2_core_t * core = CORE_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const dir = tu_edpt_dir(ep_addr); @@ -720,8 +712,8 @@ void dcd_edpt_close (uint8_t rhport, uint8_t ep_addr) if (dir == TUSB_DIR_IN) { - uint16_t const fifo_size = (core->dieptxf[epnum - 1] & DIEPTXF_INEPTXFD_Msk) >> DIEPTXF_INEPTXFD_Pos; - uint16_t const fifo_start = (core->dieptxf[epnum - 1] & DIEPTXF_INEPTXSA_Msk) >> DIEPTXF_INEPTXSA_Pos; + uint16_t const fifo_size = (dwc2->dieptxf[epnum - 1] & DIEPTXF_INEPTXFD_Msk) >> DIEPTXF_INEPTXFD_Pos; + uint16_t const fifo_start = (dwc2->dieptxf[epnum - 1] & DIEPTXF_INEPTXSA_Msk) >> DIEPTXF_INEPTXSA_Pos; // For now only the last opened endpoint can be closed without fuss. TU_ASSERT(fifo_start == DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx,); _allocated_fifo_words_tx -= fifo_size; @@ -832,11 +824,11 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, u } static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { - dwc2_core_t * core = CORE_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); volatile uint32_t * rx_fifo = FIFO_BASE(rhport, 0); // Pop control word off FIFO - uint32_t ctl_word = core->grxstsp; + uint32_t ctl_word = dwc2->grxstsp; uint8_t pktsts = (ctl_word & GRXSTSP_PKTSTS_Msk) >> GRXSTSP_PKTSTS_Pos; uint8_t epnum = (ctl_word & GRXSTSP_EPNUM_Msk) >> GRXSTSP_EPNUM_Pos; uint16_t bcnt = (ctl_word & GRXSTSP_BCNT_Msk) >> GRXSTSP_BCNT_Pos; @@ -896,7 +888,7 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { } } -static void handle_epout_ints (uint8_t rhport, dwc2_core_t *dev, dwc2_epout_t *out_ep) +static void handle_epout_ints (uint8_t rhport, dwc2_regs_t *dwc2, dwc2_epout_t *out_ep) { // DAINT for a given EP clears when DOEPINTx is cleared. // OEPINT will be cleared when DAINT's out bits are cleared. @@ -904,7 +896,7 @@ static void handle_epout_ints (uint8_t rhport, dwc2_core_t *dev, dwc2_epout_t *o { xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_OUT); - if ( dev->daint & (1 << (DAINT_OEPINT_Pos + n)) ) + if ( dwc2->daint & (1 << (DAINT_OEPINT_Pos + n)) ) { // SETUP packet Setup Phase done. if ( out_ep[n].DOEPINT & DOEPINT_STUP ) @@ -933,14 +925,14 @@ static void handle_epout_ints (uint8_t rhport, dwc2_core_t *dev, dwc2_epout_t *o } } -static void handle_epin_ints(uint8_t rhport, dwc2_core_t * dev, dwc2_epin_t * in_ep) { +static void handle_epin_ints(uint8_t rhport, dwc2_regs_t * dwc2, dwc2_epin_t * in_ep) { // DAINT for a given EP clears when DIEPINTx is cleared. // IEPINT will be cleared when DAINT's out bits are cleared. for ( uint8_t n = 0; n < DWC2_EP_MAX; n++ ) { xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_IN); - if ( dev->daint & (1 << (DAINT_IEPINT_Pos + n)) ) + if ( dwc2->daint & (1 << (DAINT_IEPINT_Pos + n)) ) { // IN XFER complete (entire xfer). if ( in_ep[n].DIEPINT & DIEPINT_XFRC ) @@ -957,7 +949,7 @@ static void handle_epin_ints(uint8_t rhport, dwc2_core_t * dev, dwc2_epin_t * in } // XFER FIFO empty - if ( (in_ep[n].DIEPINT & DIEPINT_TXFE) && (dev->diepempmsk & (1 << n)) ) + if ( (in_ep[n].DIEPINT & DIEPINT_TXFE) && (dwc2->diepempmsk & (1 << n)) ) { // DIEPINT's TXFE bit is read-only, software cannot clear it. // It will only be cleared by hardware when written bytes is more than @@ -996,7 +988,7 @@ static void handle_epin_ints(uint8_t rhport, dwc2_core_t * dev, dwc2_epin_t * in // Turn off TXFE if all bytes are written. if (((in_ep[n].DIEPTSIZ & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos) == 0) { - dev->diepempmsk &= ~(1 << n); + dwc2->diepempmsk &= ~(1 << n); } } } @@ -1005,17 +997,16 @@ static void handle_epin_ints(uint8_t rhport, dwc2_core_t * dev, dwc2_epin_t * in void dcd_int_handler(uint8_t rhport) { - dwc2_core_t * core = CORE_REG(rhport); - dwc2_core_t * dev = DEVICE_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); - uint32_t const int_status = core->gintsts & core->gintmsk; + uint32_t const int_status = dwc2->gintsts & dwc2->gintmsk; if(int_status & GINTSTS_USBRST) { // USBRST is start of reset. - core->gintsts = GINTSTS_USBRST; + dwc2->gintsts = GINTSTS_USBRST; bus_reset(rhport); } @@ -1023,23 +1014,23 @@ void dcd_int_handler(uint8_t rhport) { // ENUMDNE is the end of reset where speed of the link is detected - core->gintsts = GINTSTS_ENUMDNE; + dwc2->gintsts = GINTSTS_ENUMDNE; tusb_speed_t const speed = get_speed(rhport); - dwc2_set_turnaround(core, speed); + dwc2_set_turnaround(dwc2, speed); dcd_event_bus_reset(rhport, speed, true); } if(int_status & GINTSTS_USBSUSP) { - core->gintsts = GINTSTS_USBSUSP; + dwc2->gintsts = GINTSTS_USBSUSP; dcd_event_bus_signal(rhport, DCD_EVENT_SUSPEND, true); } if(int_status & GINTSTS_WKUINT) { - core->gintsts = GINTSTS_WKUINT; + dwc2->gintsts = GINTSTS_WKUINT; dcd_event_bus_signal(rhport, DCD_EVENT_RESUME, true); } @@ -1049,22 +1040,22 @@ void dcd_int_handler(uint8_t rhport) if(int_status & GINTSTS_OTGINT) { // OTG INT bit is read-only - uint32_t const otg_int = core->gotgint; + uint32_t const otg_int = dwc2->gotgint; if (otg_int & GOTGINT_SEDET) { dcd_event_bus_signal(rhport, DCD_EVENT_UNPLUGGED, true); } - core->gotgint = otg_int; + dwc2->gotgint = otg_int; } if(int_status & GINTSTS_SOF) { - core->gotgint = GINTSTS_SOF; + dwc2->gotgint = GINTSTS_SOF; // Disable SOF interrupt since currently only used for remote wakeup detection - core->gintmsk &= ~GINTMSK_SOFM; + dwc2->gintmsk &= ~GINTMSK_SOFM; dcd_event_bus_signal(rhport, DCD_EVENT_SOF, true); } @@ -1075,13 +1066,13 @@ void dcd_int_handler(uint8_t rhport) // RXFLVL bit is read-only // Mask out RXFLVL while reading data from FIFO - core->gintmsk &= ~GINTMSK_RXFLVLM; + dwc2->gintmsk &= ~GINTMSK_RXFLVLM; // Loop until all available packets were handled do { handle_rxflvl_ints(rhport, out_ep); - } while(core->gotgint & GINTSTS_RXFLVL); + } while(dwc2->gotgint & GINTSTS_RXFLVL); // Manage RX FIFO size if (_out_ep_closed) @@ -1092,21 +1083,21 @@ void dcd_int_handler(uint8_t rhport) _out_ep_closed = false; } - core->gintmsk |= GINTMSK_RXFLVLM; + dwc2->gintmsk |= GINTMSK_RXFLVLM; } // OUT endpoint interrupt handling. if(int_status & GINTSTS_OEPINT) { // OEPINT is read-only - handle_epout_ints(rhport, dev, out_ep); + handle_epout_ints(rhport, dwc2, out_ep); } // IN endpoint interrupt handling. if(int_status & GINTSTS_IEPINT) { // IEPINT bit read-only - handle_epin_ints(rhport, dev, in_ep); + handle_epin_ints(rhport, dwc2, in_ep); } // // Check for Incomplete isochronous IN transfer diff --git a/src/portable/synopsys/dwc2/dwc2_esp32.h b/src/portable/synopsys/dwc2/dwc2_esp32.h index 5e544673d..d73ec0504 100644 --- a/src/portable/synopsys/dwc2/dwc2_esp32.h +++ b/src/portable/synopsys/dwc2/dwc2_esp32.h @@ -67,7 +67,7 @@ static inline void dwc2_remote_wakeup_delay(void) vTaskDelay(pdMS_TO_TICKS(1)); } -static inline void dwc2_set_turnaround(dwc2_core_t * core, tusb_speed_t speed) +static inline void dwc2_set_turnaround(dwc2_regs_t * core, tusb_speed_t speed) { (void) core; (void) speed; diff --git a/src/portable/synopsys/dwc2/dwc2_gd32.h b/src/portable/synopsys/dwc2/dwc2_gd32.h index db1fb89fd..f0c7cfb38 100644 --- a/src/portable/synopsys/dwc2/dwc2_gd32.h +++ b/src/portable/synopsys/dwc2/dwc2_gd32.h @@ -76,7 +76,7 @@ static inline void dwc2_remote_wakeup_delay(void) while ( count-- ) __asm volatile ("nop"); } -static inline void dwc2_set_turnaround(dwc2_core_t * core, tusb_speed_t speed) +static inline void dwc2_set_turnaround(dwc2_regs_t * core, tusb_speed_t speed) { (void) core; (void) speed; diff --git a/src/portable/synopsys/dwc2/dwc2_stm32.h b/src/portable/synopsys/dwc2/dwc2_stm32.h index d2ad8abb7..5a0071563 100644 --- a/src/portable/synopsys/dwc2/dwc2_stm32.h +++ b/src/portable/synopsys/dwc2/dwc2_stm32.h @@ -113,7 +113,7 @@ static inline void dwc2_remote_wakeup_delay(void) } // Set turn-around timeout according to link speed -static inline void dwc2_set_turnaround(dwc2_core_t * core, tusb_speed_t speed) +static inline void dwc2_set_turnaround(dwc2_regs_t * core, tusb_speed_t speed) { core->gusbcfg &= ~GUSBCFG_TRDT; diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index b83ac67f9..23d724366 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -134,11 +134,11 @@ union { //------------- Device OUT Endpoint -------------// -} dwc2_core_t; +} dwc2_regs_t; -TU_VERIFY_STATIC(offsetof(dwc2_core_t, hcfg ) == 0x0400, "incorrect size"); -TU_VERIFY_STATIC(offsetof(dwc2_core_t, channel) == 0x0500, "incorrect size"); -TU_VERIFY_STATIC(offsetof(dwc2_core_t, dcfg ) == 0x0800, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, hcfg ) == 0x0400, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, channel) == 0x0500, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, dcfg ) == 0x0800, "incorrect size"); // Endpoint IN typedef struct From 3755814f570b8803fad63b727f1f194aeca9e796 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 Oct 2021 11:49:59 +0700 Subject: [PATCH 22/51] add epin, epout to dwc2 regs --- src/portable/synopsys/dwc2/dcd_dwc2.c | 101 ++++++++++++------------ src/portable/synopsys/dwc2/dwc2_esp32.h | 4 +- src/portable/synopsys/dwc2/dwc2_gd32.h | 4 +- src/portable/synopsys/dwc2/dwc2_stm32.h | 4 +- src/portable/synopsys/dwc2/dwc2_type.h | 83 ++++++++++--------- 5 files changed, 98 insertions(+), 98 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index c0bf655f4..468ce520f 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -31,6 +31,7 @@ #include "device/dcd_attr.h" + #if TUSB_OPT_DEVICE_ENABLED && \ ( defined(DCD_ATTR_DWC2_STM32) || TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3, OPT_MCU_GD32VF103) ) @@ -52,8 +53,8 @@ //--------------------------------------------------------------------+ #define DWC2_REG(_port) ((dwc2_regs_t*) DWC2_REG_BASE) -#define EPIN_REG(_port) ((dwc2_epin_t*) (DWC2_REG_BASE + DWC2_IN_ENDPOINT_BASE)) -#define EPOUT_REG(_port) ((dwc2_epout_t*) (DWC2_REG_BASE + DWC2_OUT_ENDPOINT_BASE)) +#define EPIN_REG(_port) (DWC2_REG(_port)->epin) +#define EPOUT_REG(_port) (DWC2_REG(_port)->epout) #define FIFO_BASE(_port, _x) ((volatile uint32_t*) (DWC2_REG_BASE + DWC2_FIFO_BASE + (_x) * DWC2_FIFO_SIZE)) enum @@ -127,7 +128,7 @@ static void bus_reset(uint8_t rhport) // 1. NAK for all OUT endpoints for(uint8_t n = 0; n < DWC2_EP_MAX; n++) { - out_ep[n].DOEPCTL |= DOEPCTL_SNAK; + out_ep[n].doepctl |= DOEPCTL_SNAK; } // 2. Un-mask interrupt bits @@ -193,10 +194,10 @@ static void bus_reset(uint8_t rhport) dwc2->dieptxf0 = (16 << TX0FD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); // Fixed control EP0 size to 64 bytes - in_ep[0].DIEPCTL &= ~(0x03 << DIEPCTL_MPSIZ_Pos); + in_ep[0].diepctl &= ~(0x03 << DIEPCTL_MPSIZ_Pos); xfer_status[0][TUSB_DIR_OUT].max_size = xfer_status[0][TUSB_DIR_IN].max_size = 64; - out_ep[0].DOEPTSIZ |= (3 << DOEPTSIZ_STUPCNT_Pos); + out_ep[0].doeptsiz |= (3 << DOEPTSIZ_STUPCNT_Pos); dwc2->gintmsk |= GINTMSK_OEPINT | GINTMSK_IEPINT; } @@ -290,17 +291,17 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c // IN and OUT endpoint xfers are interrupt-driven, we just schedule them here. if(dir == TUSB_DIR_IN) { // A full IN transfer (multiple packets, possibly) triggers XFRC. - in_ep[epnum].DIEPTSIZ = (num_packets << DIEPTSIZ_PKTCNT_Pos) | + in_ep[epnum].dieptsiz = (num_packets << DIEPTSIZ_PKTCNT_Pos) | ((total_bytes << DIEPTSIZ_XFRSIZ_Pos) & DIEPTSIZ_XFRSIZ_Msk); - in_ep[epnum].DIEPCTL |= DIEPCTL_EPENA | DIEPCTL_CNAK; + in_ep[epnum].diepctl |= DIEPCTL_EPENA | DIEPCTL_CNAK; // For ISO endpoint set correct odd/even bit for next frame. - if ((in_ep[epnum].DIEPCTL & DIEPCTL_EPTYP) == DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) + if ((in_ep[epnum].diepctl & DIEPCTL_EPTYP) == DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) { // Take odd/even bit from frame counter. uint32_t const odd_frame_now = (dwc2->dsts & (1u << DSTS_FNSOF_Pos)); - in_ep[epnum].DIEPCTL |= (odd_frame_now ? DIEPCTL_SD0PID_SEVNFRM_Msk : DIEPCTL_SODDFRM_Msk); + in_ep[epnum].diepctl |= (odd_frame_now ? DIEPCTL_SD0PID_SEVNFRM_Msk : DIEPCTL_SODDFRM_Msk); } // Enable fifo empty interrupt only if there are something to put in the fifo. if(total_bytes != 0) { @@ -308,16 +309,16 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c } } else { // A full OUT transfer (multiple packets, possibly) triggers XFRC. - out_ep[epnum].DOEPTSIZ &= ~(DOEPTSIZ_PKTCNT_Msk | DOEPTSIZ_XFRSIZ); - out_ep[epnum].DOEPTSIZ |= (num_packets << DOEPTSIZ_PKTCNT_Pos) | + out_ep[epnum].doeptsiz &= ~(DOEPTSIZ_PKTCNT_Msk | DOEPTSIZ_XFRSIZ); + out_ep[epnum].doeptsiz |= (num_packets << DOEPTSIZ_PKTCNT_Pos) | ((total_bytes << DOEPTSIZ_XFRSIZ_Pos) & DOEPTSIZ_XFRSIZ_Msk); - out_ep[epnum].DOEPCTL |= DOEPCTL_EPENA | DOEPCTL_CNAK; - if ((out_ep[epnum].DOEPCTL & DOEPCTL_EPTYP) == DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) + out_ep[epnum].doepctl |= DOEPCTL_EPENA | DOEPCTL_CNAK; + if ((out_ep[epnum].doepctl & DOEPCTL_EPTYP) == DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) { // Take odd/even bit from frame counter. uint32_t const odd_frame_now = (dwc2->dsts & (1u << DSTS_FNSOF_Pos)); - out_ep[epnum].DOEPCTL |= (odd_frame_now ? DOEPCTL_SD0PID_SEVNFRM_Msk : DOEPCTL_SODDFRM_Msk); + out_ep[epnum].doepctl |= (odd_frame_now ? DOEPCTL_SD0PID_SEVNFRM_Msk : DOEPCTL_SODDFRM_Msk); } } } @@ -403,12 +404,12 @@ void dcd_init (uint8_t rhport) void dcd_int_enable (uint8_t rhport) { - dcd_dwc2_int_enable(rhport); + dwc2_dcd_int_enable(rhport); } void dcd_int_disable (uint8_t rhport) { - dcd_dwc2_int_disable(rhport); + dwc2_dcd_int_disable(rhport); } void dcd_set_address (uint8_t rhport, uint8_t dev_addr) @@ -491,7 +492,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) dwc2->grxfsiz = sz; } - out_ep[epnum].DOEPCTL |= (1 << DOEPCTL_USBAEP_Pos) | + out_ep[epnum].doepctl |= (1 << DOEPCTL_USBAEP_Pos) | (desc_edpt->bmAttributes.xfer << DOEPCTL_EPTYP_Pos) | (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DOEPCTL_SD0PID_SEVNFRM : 0) | (xfer->max_size << DOEPCTL_MPSIZ_Pos); @@ -532,7 +533,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // Both TXFD and TXSA are in unit of 32-bit words. dwc2->dieptxf[epnum - 1] = (fifo_size << DIEPTXF_INEPTXFD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); - in_ep[epnum].DIEPCTL |= (1 << DIEPCTL_USBAEP_Pos) | + in_ep[epnum].diepctl |= (1 << DIEPCTL_USBAEP_Pos) | (epnum << DIEPCTL_TXFNUM_Pos) | (desc_edpt->bmAttributes.xfer << DIEPCTL_EPTYP_Pos) | (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DIEPCTL_SD0PID_SEVNFRM : 0) | @@ -559,11 +560,11 @@ void dcd_edpt_close_all (uint8_t rhport) for(uint8_t n = 1; n < DWC2_EP_MAX; n++) { // disable OUT endpoint - out_ep[n].DOEPCTL = 0; + out_ep[n].doepctl = 0; xfer_status[n][TUSB_DIR_OUT].max_size = 0; // disable IN endpoint - in_ep[n].DIEPCTL = 0; + in_ep[n].diepctl = 0; xfer_status[n][TUSB_DIR_IN].max_size = 0; } @@ -645,21 +646,21 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) if ( dir == TUSB_DIR_IN ) { // Only disable currently enabled non-control endpoint - if ( (epnum == 0) || !(in_ep[epnum].DIEPCTL & DIEPCTL_EPENA) ) + if ( (epnum == 0) || !(in_ep[epnum].diepctl & DIEPCTL_EPENA) ) { - in_ep[epnum].DIEPCTL |= DIEPCTL_SNAK | (stall ? DIEPCTL_STALL : 0); + in_ep[epnum].diepctl |= DIEPCTL_SNAK | (stall ? DIEPCTL_STALL : 0); } else { // Stop transmitting packets and NAK IN xfers. - in_ep[epnum].DIEPCTL |= DIEPCTL_SNAK; - while ( (in_ep[epnum].DIEPINT & DIEPINT_INEPNE) == 0 ) {} + in_ep[epnum].diepctl |= DIEPCTL_SNAK; + while ( (in_ep[epnum].diepint & DIEPINT_INEPNE) == 0 ) {} // Disable the endpoint. - in_ep[epnum].DIEPCTL |= DIEPCTL_EPDIS | (stall ? DIEPCTL_STALL : 0); - while ( (in_ep[epnum].DIEPINT & DIEPINT_EPDISD_Msk) == 0 ) {} + in_ep[epnum].diepctl |= DIEPCTL_EPDIS | (stall ? DIEPCTL_STALL : 0); + while ( (in_ep[epnum].diepint & DIEPINT_EPDISD_Msk) == 0 ) {} - in_ep[epnum].DIEPINT = DIEPINT_EPDISD; + in_ep[epnum].diepint = DIEPINT_EPDISD; } // Flush the FIFO, and wait until we have confirmed it cleared. @@ -670,9 +671,9 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) else { // Only disable currently enabled non-control endpoint - if ( (epnum == 0) || !(out_ep[epnum].DOEPCTL & DOEPCTL_EPENA) ) + if ( (epnum == 0) || !(out_ep[epnum].doepctl & DOEPCTL_EPENA) ) { - out_ep[epnum].DOEPCTL |= stall ? DOEPCTL_STALL : 0; + out_ep[epnum].doepctl |= stall ? DOEPCTL_STALL : 0; } else { @@ -684,10 +685,10 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) while ( (dwc2->gintsts & GINTSTS_BOUTNAKEFF_Msk) == 0 ) {} // Ditto here- disable the endpoint. - out_ep[epnum].DOEPCTL |= DOEPCTL_EPDIS | (stall ? DOEPCTL_STALL : 0); - while ( (out_ep[epnum].DOEPINT & DOEPINT_EPDISD_Msk) == 0 ) {} + out_ep[epnum].doepctl |= DOEPCTL_EPDIS | (stall ? DOEPCTL_STALL : 0); + while ( (out_ep[epnum].doepint & DOEPINT_EPDISD_Msk) == 0 ) {} - out_ep[epnum].DOEPINT = DOEPINT_EPDISD; + out_ep[epnum].doepint = DOEPINT_EPDISD; // Allow other OUT endpoints to keep receiving. dwc2->dctl |= DCTL_CGONAK; @@ -742,13 +743,13 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) // Clear stall and reset data toggle if ( dir == TUSB_DIR_IN ) { - in_ep[epnum].DIEPCTL &= ~DIEPCTL_STALL; - in_ep[epnum].DIEPCTL |= DIEPCTL_SD0PID_SEVNFRM; + in_ep[epnum].diepctl &= ~DIEPCTL_STALL; + in_ep[epnum].diepctl |= DIEPCTL_SD0PID_SEVNFRM; } else { - out_ep[epnum].DOEPCTL &= ~DOEPCTL_STALL; - out_ep[epnum].DOEPCTL |= DOEPCTL_SD0PID_SEVNFRM; + out_ep[epnum].doepctl &= ~DOEPCTL_STALL; + out_ep[epnum].doepctl |= DOEPCTL_SD0PID_SEVNFRM; } } @@ -859,7 +860,7 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { // Truncate transfer length in case of short packet if(bcnt < xfer->max_size) { - xfer->total_len -= (out_ep[epnum].DOEPTSIZ & DOEPTSIZ_XFRSIZ_Msk) >> DOEPTSIZ_XFRSIZ_Pos; + xfer->total_len -= (out_ep[epnum].doeptsiz & DOEPTSIZ_XFRSIZ_Msk) >> DOEPTSIZ_XFRSIZ_Pos; if(epnum == 0) { xfer->total_len -= ep0_pending[TUSB_DIR_OUT]; ep0_pending[TUSB_DIR_OUT] = 0; @@ -872,7 +873,7 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { break; case 0x04: // Setup packet done (Interrupt) - out_ep[epnum].DOEPTSIZ |= (3 << DOEPTSIZ_STUPCNT_Pos); + out_ep[epnum].doeptsiz |= (3 << DOEPTSIZ_STUPCNT_Pos); break; case 0x06: // Setup packet recvd @@ -899,16 +900,16 @@ static void handle_epout_ints (uint8_t rhport, dwc2_regs_t *dwc2, dwc2_epout_t * if ( dwc2->daint & (1 << (DAINT_OEPINT_Pos + n)) ) { // SETUP packet Setup Phase done. - if ( out_ep[n].DOEPINT & DOEPINT_STUP ) + if ( out_ep[n].doepint & DOEPINT_STUP ) { - out_ep[n].DOEPINT = DOEPINT_STUP; + out_ep[n].doepint = DOEPINT_STUP; dcd_event_setup_received(rhport, (uint8_t*) &_setup_packet[0], true); } // OUT XFER complete - if ( out_ep[n].DOEPINT & DOEPINT_XFRC ) + if ( out_ep[n].doepint & DOEPINT_XFRC ) { - out_ep[n].DOEPINT = DOEPINT_XFRC; + out_ep[n].doepint = DOEPINT_XFRC; // EP0 can only handle one packet if ( (n == 0) && ep0_pending[TUSB_DIR_OUT] ) @@ -935,9 +936,9 @@ static void handle_epin_ints(uint8_t rhport, dwc2_regs_t * dwc2, dwc2_epin_t * i if ( dwc2->daint & (1 << (DAINT_IEPINT_Pos + n)) ) { // IN XFER complete (entire xfer). - if ( in_ep[n].DIEPINT & DIEPINT_XFRC ) + if ( in_ep[n].diepint & DIEPINT_XFRC ) { - in_ep[n].DIEPINT = DIEPINT_XFRC; + in_ep[n].diepint = DIEPINT_XFRC; // EP0 can only handle one packet if((n == 0) && ep0_pending[TUSB_DIR_IN]) { @@ -949,26 +950,26 @@ static void handle_epin_ints(uint8_t rhport, dwc2_regs_t * dwc2, dwc2_epin_t * i } // XFER FIFO empty - if ( (in_ep[n].DIEPINT & DIEPINT_TXFE) && (dwc2->diepempmsk & (1 << n)) ) + if ( (in_ep[n].diepint & DIEPINT_TXFE) && (dwc2->diepempmsk & (1 << n)) ) { - // DIEPINT's TXFE bit is read-only, software cannot clear it. + // diepint's TXFE bit is read-only, software cannot clear it. // It will only be cleared by hardware when written bytes is more than // - 64 bytes or // - Half of TX FIFO size (configured by DIEPTXF) - uint16_t remaining_packets = (in_ep[n].DIEPTSIZ & DIEPTSIZ_PKTCNT_Msk) >> DIEPTSIZ_PKTCNT_Pos; + uint16_t remaining_packets = (in_ep[n].dieptsiz & DIEPTSIZ_PKTCNT_Msk) >> DIEPTSIZ_PKTCNT_Pos; // Process every single packet (only whole packets can be written to fifo) for(uint16_t i = 0; i < remaining_packets; i++) { - uint16_t const remaining_bytes = (in_ep[n].DIEPTSIZ & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos; + uint16_t const remaining_bytes = (in_ep[n].dieptsiz & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos; // Packet can not be larger than ep max size uint16_t const packet_size = tu_min16(remaining_bytes, xfer->max_size); // It's only possible to write full packets into FIFO. Therefore DTXFSTS register of current // EP has to be checked if the buffer can take another WHOLE packet - if(packet_size > ((in_ep[n].DTXFSTS & DTXFSTS_INEPTFSAV_Msk) << 2)) break; + if(packet_size > ((in_ep[n].dtxfsts & DTXFSTS_INEPTFSAV_Msk) << 2)) break; // Push packet to Tx-FIFO if (xfer->ff) @@ -986,7 +987,7 @@ static void handle_epin_ints(uint8_t rhport, dwc2_regs_t * dwc2, dwc2_epin_t * i } // Turn off TXFE if all bytes are written. - if (((in_ep[n].DIEPTSIZ & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos) == 0) + if (((in_ep[n].dieptsiz & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos) == 0) { dwc2->diepempmsk &= ~(1 << n); } diff --git a/src/portable/synopsys/dwc2/dwc2_esp32.h b/src/portable/synopsys/dwc2/dwc2_esp32.h index d73ec0504..b8a040041 100644 --- a/src/portable/synopsys/dwc2/dwc2_esp32.h +++ b/src/portable/synopsys/dwc2/dwc2_esp32.h @@ -50,13 +50,13 @@ static void dcd_int_handler_wrap(void* arg) dcd_int_handler(0); } -static inline void dcd_dwc2_int_enable (uint8_t rhport) +static inline void dwc2_dcd_int_enable (uint8_t rhport) { (void) rhport; esp_intr_alloc(ETS_USB_INTR_SOURCE, ESP_INTR_FLAG_LOWMED, dcd_int_handler_wrap, NULL, &usb_ih); } -static inline void dcd_dwc2_int_disable (uint8_t rhport) +static inline void dwc2_dcd_int_disable (uint8_t rhport) { (void) rhport; esp_intr_free(usb_ih); diff --git a/src/portable/synopsys/dwc2/dwc2_gd32.h b/src/portable/synopsys/dwc2/dwc2_gd32.h index f0c7cfb38..de3ccb3b0 100644 --- a/src/portable/synopsys/dwc2/dwc2_gd32.h +++ b/src/portable/synopsys/dwc2/dwc2_gd32.h @@ -55,14 +55,14 @@ static inline void __eclic_disable_interrupt (uint32_t irq){ } TU_ATTR_ALWAYS_INLINE -static inline void dcd_dwc2_int_enable(uint8_t rhport) +static inline void dwc2_dcd_int_enable(uint8_t rhport) { (void) rhport; __eclic_enable_interrupt(RHPORT_IRQn); } TU_ATTR_ALWAYS_INLINE -static inline void dcd_dwc2_int_disable (uint8_t rhport) +static inline void dwc2_dcd_int_disable (uint8_t rhport) { (void) rhport; __eclic_disable_interrupt(RHPORT_IRQn); diff --git a/src/portable/synopsys/dwc2/dwc2_stm32.h b/src/portable/synopsys/dwc2/dwc2_stm32.h index 5a0071563..236936d66 100644 --- a/src/portable/synopsys/dwc2/dwc2_stm32.h +++ b/src/portable/synopsys/dwc2/dwc2_stm32.h @@ -91,14 +91,14 @@ extern uint32_t SystemCoreClock; TU_ATTR_ALWAYS_INLINE -static inline void dcd_dwc2_int_enable(uint8_t rhport) +static inline void dwc2_dcd_int_enable(uint8_t rhport) { (void) rhport; NVIC_EnableIRQ(RHPORT_IRQn); } TU_ATTR_ALWAYS_INLINE -static inline void dcd_dwc2_int_disable (uint8_t rhport) +static inline void dwc2_dcd_int_disable (uint8_t rhport) { (void) rhport; NVIC_DisableIRQ(RHPORT_IRQn); diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 23d724366..8f011d642 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -40,16 +40,41 @@ typedef struct // Host Channel typedef struct { - volatile uint32_t hcchar; // 500 + 20n Host Channel Characteristics Register - volatile uint32_t hcsplt; // 504 + 20n Host Channel Split Control Register - volatile uint32_t hcint; // 508 + 20n Host Channel Interrupt Register - volatile uint32_t hcintmsk; // 50C + 20n Host Channel Interrupt Mask Register - volatile uint32_t hctsiz; // 510 + 20n Host Channel Transfer Size Register - volatile uint32_t hcdma; // 514 + 20n Host Channel DMA Address Register - uint32_t reserved518; // 518 + 20n - volatile uint32_t hcdmab; // 51C + 20n Host Channel DMA Address Register + volatile uint32_t hcchar; // 500 + 20*ch Host Channel Characteristics Register + volatile uint32_t hcsplt; // 504 + 20*ch Host Channel Split Control Register + volatile uint32_t hcint; // 508 + 20*ch Host Channel Interrupt Register + volatile uint32_t hcintmsk; // 50C + 20*ch Host Channel Interrupt Mask Register + volatile uint32_t hctsiz; // 510 + 20*ch Host Channel Transfer Size Register + volatile uint32_t hcdma; // 514 + 20*ch Host Channel DMA Address Register + uint32_t reserved518; // 518 + 20*ch + volatile uint32_t hcdmab; // 51C + 20*ch Host Channel DMA Address Register } dwc2_channel_t; +// Endpoint IN +typedef struct +{ + volatile uint32_t diepctl; // 900 + 20*ep Device IN Endpoint Control + uint32_t reserved04; // 904 + volatile uint32_t diepint; // 908 + 20*ep Device IN Endpoint Interrupt + uint32_t reserved0c; // 90C + volatile uint32_t dieptsiz; // 910 + 20*ep Device IN Endpoint Transfer Size + volatile uint32_t diepdma; // 914 + 20*ep Device IN Endpoint DMA Address + volatile uint32_t dtxfsts; // 918 + 20*ep Device IN Endpoint Tx FIFO Status + uint32_t reserved1c; // 91C +} dwc2_epin_t; + +// Endpoint OUT +typedef struct +{ + volatile uint32_t doepctl; // B00 + 20*ep Device OUT Endpoint Control + uint32_t reserved04; // B04 + volatile uint32_t doepint; // B08 + 20*ep Device OUT Endpoint Interrupt + uint32_t reserved0c; // B0C + volatile uint32_t doeptsiz; // B10 + 20*ep Device OUT Endpoint Transfer Size + volatile uint32_t doepdma; // B14 + 20*ep Device OUT Endpoint DMA Address + uint32_t reserved18[2]; // B18..B1C +} dwc2_epout_t; + typedef struct { //------------- Core Global -------------// @@ -123,48 +148,22 @@ union { volatile uint32_t dvbuspulse; // 82C Device VBUS Pulsing Time Register volatile uint32_t dthrctl; // 830 Device threshold Control volatile uint32_t diepempmsk; // 834 Device IN Endpoint FIFO Empty Interrupt Mask - volatile uint32_t deachint; // 838 Device Each Endpoint Interrupt volatile uint32_t deachmsk; // 83C Device Each Endpoint Interrupt msk volatile uint32_t diepeachmsk[16]; // 840..87C Device Each IN Endpoint mask volatile uint32_t doepeachmsk[16]; // 880..8BC Device Each OUT Endpoint mask uint32_t reserved8c0[16]; // 8C0..8FC - //------------- Device IN Endpoint -------------// - - - //------------- Device OUT Endpoint -------------// + //------------- Device Endpoint -------------// + dwc2_epin_t epin[16]; // 900..AFC IN Endpoints + dwc2_epout_t epout[16]; // B00..CFC OUT Endpoints } dwc2_regs_t; -TU_VERIFY_STATIC(offsetof(dwc2_regs_t, hcfg ) == 0x0400, "incorrect size"); -TU_VERIFY_STATIC(offsetof(dwc2_regs_t, channel) == 0x0500, "incorrect size"); -TU_VERIFY_STATIC(offsetof(dwc2_regs_t, dcfg ) == 0x0800, "incorrect size"); - -// Endpoint IN -typedef struct -{ - volatile uint32_t DIEPCTL; // dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; // Reserved 900h + (ep_num * 20h) + 04h */ - volatile uint32_t DIEPINT; // dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; // Reserved 900h + (ep_num * 20h) + 0Ch */ - volatile uint32_t DIEPTSIZ; // IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - volatile uint32_t DIEPDMA; // IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - volatile uint32_t DTXFSTS; // IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; // Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ -} dwc2_epin_t; - -// Endpoint OUT -typedef struct -{ - volatile uint32_t DOEPCTL; // dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; // Reserved B00h + (ep_num * 20h) + 04h */ - volatile uint32_t DOEPINT; // dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; // Reserved B00h + (ep_num * 20h) + 0Ch */ - volatile uint32_t DOEPTSIZ; // dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ - volatile uint32_t DOEPDMA; // dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ - uint32_t Reserved18[2]; // Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ -} dwc2_epout_t; - +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, hcfg ) == 0x400, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, channel) == 0x500, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, dcfg ) == 0x800, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, epin ) == 0x900, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, epout ) == 0xB00, "incorrect size"); //--------------------------------------------------------------------+ // Register Base Address From 5e1a0318004d95c6663e494ade76a0581594391e Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 Oct 2021 12:22:07 +0700 Subject: [PATCH 23/51] complete dwc2 regs struct --- src/portable/synopsys/dwc2/dcd_dwc2.c | 16 ++- src/portable/synopsys/dwc2/dwc2_type.h | 136 +++++++++++++------------ 2 files changed, 80 insertions(+), 72 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 468ce520f..718773a00 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -30,8 +30,6 @@ #include "tusb_option.h" #include "device/dcd_attr.h" - - #if TUSB_OPT_DEVICE_ENABLED && \ ( defined(DCD_ATTR_DWC2_STM32) || TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3, OPT_MCU_GD32VF103) ) @@ -84,7 +82,7 @@ xfer_ctl_t xfer_status[DWC2_EP_MAX][2]; // EP0 transfers are limited to 1 packet - larger sizes has to be split static uint16_t ep0_pending[2]; // Index determines direction as tusb_dir_t type -// TX FIFO RAM allocation so far in words - RX FIFO size is readily available from core->GRXFSIZ +// TX FIFO RAM allocation so far in words - RX FIFO size is readily available from dwc2->grxfsiz static uint16_t _allocated_fifo_words_tx; // TX FIFO size in words (IN EPs) static bool _out_ep_closed; // Flag to check if RX FIFO size needs an update (reduce its size) @@ -98,7 +96,7 @@ static void update_grxfsiz(uint8_t rhport) { (void) rhport; - dwc2_regs_t * core = DWC2_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); // Determine largest EP size for RX FIFO uint16_t max_epsize = 0; @@ -108,7 +106,7 @@ static void update_grxfsiz(uint8_t rhport) } // Update size of RX FIFO - core->grxfsiz = calc_rx_ff_size(max_epsize); + dwc2->grxfsiz = calc_rx_ff_size(max_epsize); } // Setup the control endpoint 0. @@ -340,7 +338,7 @@ void dcd_init (uint8_t rhport) // On selected MCUs HS port1 can be used with external PHY via ULPI interface #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED // deactivate internal PHY - dwc2->gccfg &= ~GCCFG_PWRDWN; + dwc2->stm32_gccfg &= ~GCCFG_PWRDWN; // Init The UTMI Interface dwc2->gusbcfg &= ~(GUSBCFG_TSDPS | GUSBCFG_ULPIFSLS | GUSBCFG_PHYSEL); @@ -356,7 +354,7 @@ void dcd_init (uint8_t rhport) // Select UTMI Interface dwc2->gusbcfg &= ~GUSBCFG_ULPI_UTMI_SEL; - dwc2->gccfg |= GCCFG_PHYHSEN; + dwc2->stm32_gccfg |= GCCFG_PHYHSEN; // Enables control of a High Speed USB PHY USB_HS_PHYCInit(); @@ -374,7 +372,7 @@ void dcd_init (uint8_t rhport) while ((dwc2->grstctl & GRSTCTL_CSRST) == GRSTCTL_CSRST) {} // Restart PHY clock - *((volatile uint32_t *)(DWC2_REG_BASE + DWC2_PCGCCTL_BASE)) = 0; + dwc2->pcgctrl = 0; // Clear all interrupts dwc2->gintsts |= dwc2->gintsts; @@ -391,7 +389,7 @@ void dcd_init (uint8_t rhport) set_speed(rhport, TUD_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL); // Enable internal USB transceiver, unless using HS core (port 1) with external PHY. - if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) dwc2->gccfg |= GCCFG_PWRDWN; + if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) dwc2->stm32_gccfg |= GCCFG_PWRDWN; dwc2->gintmsk |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_USBSUSPM | GINTMSK_WUIM | GINTMSK_RXFLVLM; diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 8f011d642..95d043b86 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -78,42 +78,42 @@ typedef struct typedef struct { //------------- Core Global -------------// - volatile uint32_t gotgctl; // 000 OTG Control and Status Register - volatile uint32_t gotgint; // 004 OTG Interrupt Register - volatile uint32_t gahbcfg; // 008 AHB Configuration Register - volatile uint32_t gusbcfg; // 00c USB Configuration Register - volatile uint32_t grstctl; // 010 Reset Register - volatile uint32_t gintsts; // 014 Interrupt Register - volatile uint32_t gintmsk; // 018 Interrupt Mask Register - volatile uint32_t grxstsr; // 01c Receive Status Debug Read Register - volatile uint32_t grxstsp; // 020 Receive Status Read/Pop Register - volatile uint32_t grxfsiz; // 024 Receive FIFO Size Register + volatile uint32_t gotgctl; // 000 OTG Control and Status Register + volatile uint32_t gotgint; // 004 OTG Interrupt Register + volatile uint32_t gahbcfg; // 008 AHB Configuration Register + volatile uint32_t gusbcfg; // 00c USB Configuration Register + volatile uint32_t grstctl; // 010 Reset Register + volatile uint32_t gintsts; // 014 Interrupt Register + volatile uint32_t gintmsk; // 018 Interrupt Mask Register + volatile uint32_t grxstsr; // 01c Receive Status Debug Read Register + volatile uint32_t grxstsp; // 020 Receive Status Read/Pop Register + volatile uint32_t grxfsiz; // 024 Receive FIFO Size Register union { - volatile uint32_t dieptxf0; // 028 EP0 Tx FIFO Size Register - volatile uint32_t gnptxfsiz; // 028 Non-periodic Transmit FIFO Size Register + volatile uint32_t dieptxf0; // 028 EP0 Tx FIFO Size Register + volatile uint32_t gnptxfsiz; // 028 Non-periodic Transmit FIFO Size Register }; - volatile uint32_t gnptxsts; // 02c Non-periodic Transmit FIFO/Queue Status Register - volatile uint32_t gi2cctl; // 030 I2C Address Register - volatile uint32_t gpvndctl; // 034 PHY Vendor Control Register + volatile uint32_t gnptxsts; // 02c Non-periodic Transmit FIFO/Queue Status Register + volatile uint32_t gi2cctl; // 030 I2C Address Register + volatile uint32_t gpvndctl; // 034 PHY Vendor Control Register union { - volatile uint32_t ggpio; // 038 General Purpose IO Register - volatile uint32_t gccfg; // 038 STM32 General Core Configuration + volatile uint32_t ggpio; // 038 General Purpose IO Register + volatile uint32_t stm32_gccfg; // 038 STM32 General Core Configuration }; - volatile uint32_t guid; // 03C User ID Register - volatile uint32_t gsnpsid; // 040 Synopsys ID Register - volatile uint32_t ghwcfg1; // 044 User Hardware Configuration 1 Register - volatile uint32_t ghwcfg2; // 048 User Hardware Configuration 2 Register - volatile uint32_t ghwcfg3; // 04C User Hardware Configuration 3 Register - volatile uint32_t ghwcfg4; // 050 User Hardware Configuration 4 Register - volatile uint32_t glpmcfg; // 054 Core LPM Configuration Register - volatile uint32_t gpwrdn; // 058 Power Down Register - volatile uint32_t gdfifocfg; // 05C DFIFO Software Configuration Register - volatile uint32_t gadpctl; // 060 ADP Timer, Control and Status Register + volatile uint32_t guid; // 03C User ID Register + volatile uint32_t gsnpsid; // 040 Synopsys ID Register + volatile uint32_t ghwcfg1; // 044 User Hardware Configuration 1 Register + volatile uint32_t ghwcfg2; // 048 User Hardware Configuration 2 Register + volatile uint32_t ghwcfg3; // 04C User Hardware Configuration 3 Register + volatile uint32_t ghwcfg4; // 050 User Hardware Configuration 4 Register + volatile uint32_t glpmcfg; // 054 Core LPM Configuration Register + volatile uint32_t gpwrdn; // 058 Power Down Register + volatile uint32_t gdfifocfg; // 05C DFIFO Software Configuration Register + volatile uint32_t gadpctl; // 060 ADP Timer, Control and Status Register - uint32_t reserved64[39]; // 064..0FF - volatile uint32_t hptxfsiz; // 100 Host Periodic Tx FIFO Size Register - volatile uint32_t dieptxf[15]; // 104..13C Device Periodic Transmit FIFO Size Register - uint32_t reserved140[176]; // 140..3FC + uint32_t reserved64[39]; // 064..0FF + volatile uint32_t hptxfsiz; // 100 Host Periodic Tx FIFO Size Register + volatile uint32_t dieptxf[15]; // 104..13C Device Periodic Transmit FIFO Size Register + uint32_t reserved140[176]; // 140..3FF //------------- Host -------------// volatile uint32_t hcfg; // 400 Host Configuration Register @@ -124,46 +124,56 @@ union { volatile uint32_t haint; // 414 Host All Channels Interrupt Register volatile uint32_t haintmsk; // 418 Host All Channels Interrupt Mask volatile uint32_t hflbaddr; // 41C Host Frame List Base Address Register - uint32_t reserved420[8]; // 420..43C + uint32_t reserved420[8]; // 420..43F volatile uint32_t hprt; // 440 Host Port Control and Status - uint32_t reserved444[47]; // 444..4FC + uint32_t reserved444[47]; // 444..4FF //------------- Host Channel -------------// - dwc2_channel_t channel[16]; // 500..6FC Host Channels 0-15 + dwc2_channel_t channel[16]; // 500..6FF Host Channels 0-15 + uint32_t reserved700[64]; // 700..7FF - uint32_t reserved700[64]; // 700..7FC - - //------------- Device -------------// - volatile uint32_t dcfg; // 800 Device Configuration Register - volatile uint32_t dctl; // 804 Device Control Register - volatile uint32_t dsts; // 808 Device Status Register (RO) - uint32_t reserved80c; // 80C - volatile uint32_t diepmsk; // 810 Device IN Endpoint Interrupt Mask - volatile uint32_t doepmsk; // 814 Device OUT Endpoint Interrupt Mask - volatile uint32_t daint; // 818 Device All Endpoints Interrupt - volatile uint32_t daintmsk; // 81C Device All Endpoints Interrupt Mask - volatile uint32_t dtknqr1; // 820 Device IN token sequence learning queue read register1 - volatile uint32_t dtknqr2; // 824 Device IN token sequence learning queue read register2 - volatile uint32_t dvbusdis; // 828 Device VBUS Discharge Time Register - volatile uint32_t dvbuspulse; // 82C Device VBUS Pulsing Time Register - volatile uint32_t dthrctl; // 830 Device threshold Control - volatile uint32_t diepempmsk; // 834 Device IN Endpoint FIFO Empty Interrupt Mask - volatile uint32_t deachint; // 838 Device Each Endpoint Interrupt - volatile uint32_t deachmsk; // 83C Device Each Endpoint Interrupt msk - volatile uint32_t diepeachmsk[16]; // 840..87C Device Each IN Endpoint mask - volatile uint32_t doepeachmsk[16]; // 880..8BC Device Each OUT Endpoint mask - uint32_t reserved8c0[16]; // 8C0..8FC + //------------- Device -------------// + volatile uint32_t dcfg; // 800 Device Configuration Register + volatile uint32_t dctl; // 804 Device Control Register + volatile uint32_t dsts; // 808 Device Status Register (RO) + uint32_t reserved80c; // 80C + volatile uint32_t diepmsk; // 810 Device IN Endpoint Interrupt Mask + volatile uint32_t doepmsk; // 814 Device OUT Endpoint Interrupt Mask + volatile uint32_t daint; // 818 Device All Endpoints Interrupt + volatile uint32_t daintmsk; // 81C Device All Endpoints Interrupt Mask + volatile uint32_t dtknqr1; // 820 Device IN token sequence learning queue read register1 + volatile uint32_t dtknqr2; // 824 Device IN token sequence learning queue read register2 + volatile uint32_t dvbusdis; // 828 Device VBUS Discharge Time Register + volatile uint32_t dvbuspulse; // 82C Device VBUS Pulsing Time Register + volatile uint32_t dthrctl; // 830 Device threshold Control + volatile uint32_t diepempmsk; // 834 Device IN Endpoint FIFO Empty Interrupt Mask + volatile uint32_t deachint; // 838 Device Each Endpoint Interrupt + volatile uint32_t deachmsk; // 83C Device Each Endpoint Interrupt msk + volatile uint32_t diepeachmsk[16]; // 840..87C Device Each IN Endpoint mask + volatile uint32_t doepeachmsk[16]; // 880..8BF Device Each OUT Endpoint mask + uint32_t reserved8c0[16]; // 8C0..8FF //------------- Device Endpoint -------------// - dwc2_epin_t epin[16]; // 900..AFC IN Endpoints - dwc2_epout_t epout[16]; // B00..CFC OUT Endpoints + dwc2_epin_t epin[16]; // 900..AFF IN Endpoints + dwc2_epout_t epout[16]; // B00..CFF OUT Endpoints + uint32_t reservedd00[64]; // D00..DFF + + //------------- Power Clock -------------// + volatile uint32_t pcgctrl; // E00 Power and Clock Gating Control + volatile uint32_t pcgcctl1; // E04 + uint32_t reservede08[126]; // E08..FFF + + //------------- FIFOs -------------// + volatile uint32_t fifo[16][0x400]; // 1000..FFFF Endpoint FIFO } dwc2_regs_t; -TU_VERIFY_STATIC(offsetof(dwc2_regs_t, hcfg ) == 0x400, "incorrect size"); -TU_VERIFY_STATIC(offsetof(dwc2_regs_t, channel) == 0x500, "incorrect size"); -TU_VERIFY_STATIC(offsetof(dwc2_regs_t, dcfg ) == 0x800, "incorrect size"); -TU_VERIFY_STATIC(offsetof(dwc2_regs_t, epin ) == 0x900, "incorrect size"); -TU_VERIFY_STATIC(offsetof(dwc2_regs_t, epout ) == 0xB00, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, hcfg ) == 0x0400, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, channel) == 0x0500, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, dcfg ) == 0x0800, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, epin ) == 0x0900, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, epout ) == 0x0B00, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, pcgctrl) == 0x0E00, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); //--------------------------------------------------------------------+ // Register Base Address From 34844c90610763a91c421bc889ffe4a9d988e14a Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 Oct 2021 12:53:29 +0700 Subject: [PATCH 24/51] use dwc2->fifo[] --- src/portable/synopsys/dwc2/dcd_dwc2.c | 14 ++++++++------ src/portable/synopsys/dwc2/dwc2_type.h | 1 + 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 718773a00..1909f45fd 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -53,7 +53,6 @@ #define DWC2_REG(_port) ((dwc2_regs_t*) DWC2_REG_BASE) #define EPIN_REG(_port) (DWC2_REG(_port)->epin) #define EPOUT_REG(_port) (DWC2_REG(_port)->epout) -#define FIFO_BASE(_port, _x) ((volatile uint32_t*) (DWC2_REG_BASE + DWC2_FIFO_BASE + (_x) * DWC2_FIFO_SIZE)) enum { @@ -758,7 +757,8 @@ static void read_fifo_packet(uint8_t rhport, uint8_t * dst, uint16_t len) { (void) rhport; - volatile uint32_t * rx_fifo = FIFO_BASE(rhport, 0); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); + volatile uint32_t * rx_fifo = dwc2->fifo[0]; // Reading full available 32 bit words from fifo uint16_t full_words = len >> 2; @@ -794,7 +794,8 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, u { (void) rhport; - volatile uint32_t * tx_fifo = FIFO_BASE(rhport, fifo_num); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); + volatile uint32_t * tx_fifo = dwc2->fifo[fifo_num]; // Pushing full available 32 bit words to fifo uint16_t full_words = len >> 2; @@ -822,9 +823,10 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, u } } -static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) { +static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) +{ dwc2_regs_t * dwc2 = DWC2_REG(rhport); - volatile uint32_t * rx_fifo = FIFO_BASE(rhport, 0); + volatile uint32_t * rx_fifo = dwc2->fifo[0]; // Pop control word off FIFO uint32_t ctl_word = dwc2->grxstsp; @@ -972,7 +974,7 @@ static void handle_epin_ints(uint8_t rhport, dwc2_regs_t * dwc2, dwc2_epin_t * i // Push packet to Tx-FIFO if (xfer->ff) { - volatile uint32_t * tx_fifo = FIFO_BASE(rhport, n); + volatile uint32_t * tx_fifo = dwc2->fifo[n]; tu_fifo_read_n_const_addr_full_words(xfer->ff, (void *)(uintptr_t) tx_fifo, packet_size); } else diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 95d043b86..5669aa88d 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -164,6 +164,7 @@ union { uint32_t reservede08[126]; // E08..FFF //------------- FIFOs -------------// + // Word-accessed only using first pointer since it auto shift volatile uint32_t fifo[16][0x400]; // 1000..FFFF Endpoint FIFO } dwc2_regs_t; From e7655a75673fd444f39185feb4a9a0edf8ac07fe Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 Oct 2021 13:02:26 +0700 Subject: [PATCH 25/51] update the access epout --- src/portable/synopsys/dwc2/dcd_dwc2.c | 85 +++++++++++++-------------- 1 file changed, 41 insertions(+), 44 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 1909f45fd..11040a6cd 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -52,7 +52,6 @@ #define DWC2_REG(_port) ((dwc2_regs_t*) DWC2_REG_BASE) #define EPIN_REG(_port) (DWC2_REG(_port)->epin) -#define EPOUT_REG(_port) (DWC2_REG(_port)->epout) enum { @@ -114,8 +113,6 @@ static void bus_reset(uint8_t rhport) (void) rhport; dwc2_regs_t * dwc2 = DWC2_REG(rhport); - dwc2_epout_t * out_ep = EPOUT_REG(rhport); - dwc2_epin_t * in_ep = EPIN_REG(rhport); tu_memclr(xfer_status, sizeof(xfer_status)); _out_ep_closed = false; @@ -125,7 +122,7 @@ static void bus_reset(uint8_t rhport) // 1. NAK for all OUT endpoints for(uint8_t n = 0; n < DWC2_EP_MAX; n++) { - out_ep[n].doepctl |= DOEPCTL_SNAK; + dwc2->epout[n].doepctl |= DOEPCTL_SNAK; } // 2. Un-mask interrupt bits @@ -191,10 +188,10 @@ static void bus_reset(uint8_t rhport) dwc2->dieptxf0 = (16 << TX0FD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); // Fixed control EP0 size to 64 bytes - in_ep[0].diepctl &= ~(0x03 << DIEPCTL_MPSIZ_Pos); + dwc2->epin[0].diepctl &= ~(0x03 << DIEPCTL_MPSIZ_Pos); xfer_status[0][TUSB_DIR_OUT].max_size = xfer_status[0][TUSB_DIR_IN].max_size = 64; - out_ep[0].doeptsiz |= (3 << DOEPTSIZ_STUPCNT_Pos); + dwc2->epout[0].doeptsiz |= (3 << DOEPTSIZ_STUPCNT_Pos); dwc2->gintmsk |= GINTMSK_OEPINT | GINTMSK_IEPINT; } @@ -274,48 +271,52 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c (void) rhport; dwc2_regs_t * dwc2 = DWC2_REG(rhport); - dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); // EP0 is limited to one packet each xfer // We use multiple transaction of xfer->max_size length to get a whole transfer done - if(epnum == 0) { - xfer_ctl_t * const xfer = XFER_CTL_BASE(epnum, dir); + if ( epnum == 0 ) + { + xfer_ctl_t *const xfer = XFER_CTL_BASE(epnum, dir); total_bytes = tu_min16(ep0_pending[dir], xfer->max_size); ep0_pending[dir] -= total_bytes; } // IN and OUT endpoint xfers are interrupt-driven, we just schedule them here. - if(dir == TUSB_DIR_IN) { + if ( dir == TUSB_DIR_IN ) + { // A full IN transfer (multiple packets, possibly) triggers XFRC. in_ep[epnum].dieptsiz = (num_packets << DIEPTSIZ_PKTCNT_Pos) | - ((total_bytes << DIEPTSIZ_XFRSIZ_Pos) & DIEPTSIZ_XFRSIZ_Msk); + ((total_bytes << DIEPTSIZ_XFRSIZ_Pos) & DIEPTSIZ_XFRSIZ_Msk); in_ep[epnum].diepctl |= DIEPCTL_EPENA | DIEPCTL_CNAK; // For ISO endpoint set correct odd/even bit for next frame. - if ((in_ep[epnum].diepctl & DIEPCTL_EPTYP) == DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) + if ( (in_ep[epnum].diepctl & DIEPCTL_EPTYP) == DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1 ) { // Take odd/even bit from frame counter. uint32_t const odd_frame_now = (dwc2->dsts & (1u << DSTS_FNSOF_Pos)); in_ep[epnum].diepctl |= (odd_frame_now ? DIEPCTL_SD0PID_SEVNFRM_Msk : DIEPCTL_SODDFRM_Msk); } // Enable fifo empty interrupt only if there are something to put in the fifo. - if(total_bytes != 0) { + if ( total_bytes != 0 ) + { dwc2->diepempmsk |= (1 << epnum); } - } else { + } + else + { // A full OUT transfer (multiple packets, possibly) triggers XFRC. - out_ep[epnum].doeptsiz &= ~(DOEPTSIZ_PKTCNT_Msk | DOEPTSIZ_XFRSIZ); - out_ep[epnum].doeptsiz |= (num_packets << DOEPTSIZ_PKTCNT_Pos) | - ((total_bytes << DOEPTSIZ_XFRSIZ_Pos) & DOEPTSIZ_XFRSIZ_Msk); + dwc2->epout[epnum].doeptsiz &= ~(DOEPTSIZ_PKTCNT_Msk | DOEPTSIZ_XFRSIZ); + dwc2->epout[epnum].doeptsiz |= (num_packets << DOEPTSIZ_PKTCNT_Pos) | + ((total_bytes << DOEPTSIZ_XFRSIZ_Pos) & DOEPTSIZ_XFRSIZ_Msk); - out_ep[epnum].doepctl |= DOEPCTL_EPENA | DOEPCTL_CNAK; - if ((out_ep[epnum].doepctl & DOEPCTL_EPTYP) == DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1) + dwc2->epout[epnum].doepctl |= DOEPCTL_EPENA | DOEPCTL_CNAK; + if ( (dwc2->epout[epnum].doepctl & DOEPCTL_EPTYP) == DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1 ) { // Take odd/even bit from frame counter. uint32_t const odd_frame_now = (dwc2->dsts & (1u << DSTS_FNSOF_Pos)); - out_ep[epnum].doepctl |= (odd_frame_now ? DOEPCTL_SD0PID_SEVNFRM_Msk : DOEPCTL_SODDFRM_Msk); + dwc2->epout[epnum].doepctl |= (odd_frame_now ? DOEPCTL_SD0PID_SEVNFRM_Msk : DOEPCTL_SODDFRM_Msk); } } } @@ -461,7 +462,6 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) (void) rhport; dwc2_regs_t * dwc2 = DWC2_REG(rhport); - dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); uint8_t const epnum = tu_edpt_number(desc_edpt->bEndpointAddress); @@ -489,7 +489,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) dwc2->grxfsiz = sz; } - out_ep[epnum].doepctl |= (1 << DOEPCTL_USBAEP_Pos) | + dwc2->epout[epnum].doepctl |= (1 << DOEPCTL_USBAEP_Pos) | (desc_edpt->bmAttributes.xfer << DOEPCTL_EPTYP_Pos) | (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DOEPCTL_SD0PID_SEVNFRM : 0) | (xfer->max_size << DOEPCTL_MPSIZ_Pos); @@ -548,7 +548,6 @@ void dcd_edpt_close_all (uint8_t rhport) (void) rhport; dwc2_regs_t * dwc2 = DWC2_REG(rhport); - dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); // Disable non-control interrupt @@ -557,7 +556,7 @@ void dcd_edpt_close_all (uint8_t rhport) for(uint8_t n = 1; n < DWC2_EP_MAX; n++) { // disable OUT endpoint - out_ep[n].doepctl = 0; + dwc2->epout[n].doepctl = 0; xfer_status[n][TUSB_DIR_OUT].max_size = 0; // disable IN endpoint @@ -634,7 +633,6 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) (void) rhport; dwc2_regs_t * dwc2 = DWC2_REG(rhport); - dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); @@ -668,9 +666,9 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) else { // Only disable currently enabled non-control endpoint - if ( (epnum == 0) || !(out_ep[epnum].doepctl & DOEPCTL_EPENA) ) + if ( (epnum == 0) || !(dwc2->epout[epnum].doepctl & DOEPCTL_EPENA) ) { - out_ep[epnum].doepctl |= stall ? DOEPCTL_STALL : 0; + dwc2->epout[epnum].doepctl |= stall ? DOEPCTL_STALL : 0; } else { @@ -682,10 +680,10 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) while ( (dwc2->gintsts & GINTSTS_BOUTNAKEFF_Msk) == 0 ) {} // Ditto here- disable the endpoint. - out_ep[epnum].doepctl |= DOEPCTL_EPDIS | (stall ? DOEPCTL_STALL : 0); - while ( (out_ep[epnum].doepint & DOEPINT_EPDISD_Msk) == 0 ) {} + dwc2->epout[epnum].doepctl |= DOEPCTL_EPDIS | (stall ? DOEPCTL_STALL : 0); + while ( (dwc2->epout[epnum].doepint & DOEPINT_EPDISD_Msk) == 0 ) {} - out_ep[epnum].doepint = DOEPINT_EPDISD; + dwc2->epout[epnum].doepint = DOEPINT_EPDISD; // Allow other OUT endpoints to keep receiving. dwc2->dctl |= DCTL_CGONAK; @@ -731,7 +729,7 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) { (void) rhport; - dwc2_epout_t * out_ep = EPOUT_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); @@ -745,8 +743,8 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) } else { - out_ep[epnum].doepctl &= ~DOEPCTL_STALL; - out_ep[epnum].doepctl |= DOEPCTL_SD0PID_SEVNFRM; + dwc2->epout[epnum].doepctl &= ~DOEPCTL_STALL; + dwc2->epout[epnum].doepctl |= DOEPCTL_SD0PID_SEVNFRM; } } @@ -823,7 +821,7 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, u } } -static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) +static void handle_rxflvl_ints(uint8_t rhport) { dwc2_regs_t * dwc2 = DWC2_REG(rhport); volatile uint32_t * rx_fifo = dwc2->fifo[0]; @@ -860,7 +858,7 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) // Truncate transfer length in case of short packet if(bcnt < xfer->max_size) { - xfer->total_len -= (out_ep[epnum].doeptsiz & DOEPTSIZ_XFRSIZ_Msk) >> DOEPTSIZ_XFRSIZ_Pos; + xfer->total_len -= (dwc2->epout[epnum].doeptsiz & DOEPTSIZ_XFRSIZ_Msk) >> DOEPTSIZ_XFRSIZ_Pos; if(epnum == 0) { xfer->total_len -= ep0_pending[TUSB_DIR_OUT]; ep0_pending[TUSB_DIR_OUT] = 0; @@ -873,7 +871,7 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) break; case 0x04: // Setup packet done (Interrupt) - out_ep[epnum].doeptsiz |= (3 << DOEPTSIZ_STUPCNT_Pos); + dwc2->epout[epnum].doeptsiz |= (3 << DOEPTSIZ_STUPCNT_Pos); break; case 0x06: // Setup packet recvd @@ -889,7 +887,7 @@ static void handle_rxflvl_ints(uint8_t rhport, dwc2_epout_t * out_ep) } } -static void handle_epout_ints (uint8_t rhport, dwc2_regs_t *dwc2, dwc2_epout_t *out_ep) +static void handle_epout_ints (uint8_t rhport, dwc2_regs_t *dwc2) { // DAINT for a given EP clears when DOEPINTx is cleared. // OEPINT will be cleared when DAINT's out bits are cleared. @@ -900,16 +898,16 @@ static void handle_epout_ints (uint8_t rhport, dwc2_regs_t *dwc2, dwc2_epout_t * if ( dwc2->daint & (1 << (DAINT_OEPINT_Pos + n)) ) { // SETUP packet Setup Phase done. - if ( out_ep[n].doepint & DOEPINT_STUP ) + if ( dwc2->epout[n].doepint & DOEPINT_STUP ) { - out_ep[n].doepint = DOEPINT_STUP; + dwc2->epout[n].doepint = DOEPINT_STUP; dcd_event_setup_received(rhport, (uint8_t*) &_setup_packet[0], true); } // OUT XFER complete - if ( out_ep[n].doepint & DOEPINT_XFRC ) + if ( dwc2->epout[n].doepint & DOEPINT_XFRC ) { - out_ep[n].doepint = DOEPINT_XFRC; + dwc2->epout[n].doepint = DOEPINT_XFRC; // EP0 can only handle one packet if ( (n == 0) && ep0_pending[TUSB_DIR_OUT] ) @@ -999,7 +997,6 @@ static void handle_epin_ints(uint8_t rhport, dwc2_regs_t * dwc2, dwc2_epin_t * i void dcd_int_handler(uint8_t rhport) { dwc2_regs_t * dwc2 = DWC2_REG(rhport); - dwc2_epout_t * out_ep = EPOUT_REG(rhport); dwc2_epin_t * in_ep = EPIN_REG(rhport); uint32_t const int_status = dwc2->gintsts & dwc2->gintmsk; @@ -1072,7 +1069,7 @@ void dcd_int_handler(uint8_t rhport) // Loop until all available packets were handled do { - handle_rxflvl_ints(rhport, out_ep); + handle_rxflvl_ints(rhport); } while(dwc2->gotgint & GINTSTS_RXFLVL); // Manage RX FIFO size @@ -1091,7 +1088,7 @@ void dcd_int_handler(uint8_t rhport) if(int_status & GINTSTS_OEPINT) { // OEPINT is read-only - handle_epout_ints(rhport, dwc2, out_ep); + handle_epout_ints(rhport, dwc2); } // IN endpoint interrupt handling. From de413183d4b02a42dc1df798a1f62fb2d164eb60 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 Oct 2021 13:07:00 +0700 Subject: [PATCH 26/51] use dwc2->epin --- src/portable/synopsys/dwc2/dcd_dwc2.c | 71 +++++++++++++-------------- 1 file changed, 34 insertions(+), 37 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 11040a6cd..ec1dac66c 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -51,7 +51,6 @@ //--------------------------------------------------------------------+ #define DWC2_REG(_port) ((dwc2_regs_t*) DWC2_REG_BASE) -#define EPIN_REG(_port) (DWC2_REG(_port)->epin) enum { @@ -271,7 +270,6 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c (void) rhport; dwc2_regs_t * dwc2 = DWC2_REG(rhport); - dwc2_epin_t * in_ep = EPIN_REG(rhport); // EP0 is limited to one packet each xfer // We use multiple transaction of xfer->max_size length to get a whole transfer done @@ -286,17 +284,17 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c if ( dir == TUSB_DIR_IN ) { // A full IN transfer (multiple packets, possibly) triggers XFRC. - in_ep[epnum].dieptsiz = (num_packets << DIEPTSIZ_PKTCNT_Pos) | + dwc2->epin[epnum].dieptsiz = (num_packets << DIEPTSIZ_PKTCNT_Pos) | ((total_bytes << DIEPTSIZ_XFRSIZ_Pos) & DIEPTSIZ_XFRSIZ_Msk); - in_ep[epnum].diepctl |= DIEPCTL_EPENA | DIEPCTL_CNAK; + dwc2->epin[epnum].diepctl |= DIEPCTL_EPENA | DIEPCTL_CNAK; // For ISO endpoint set correct odd/even bit for next frame. - if ( (in_ep[epnum].diepctl & DIEPCTL_EPTYP) == DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1 ) + if ( (dwc2->epin[epnum].diepctl & DIEPCTL_EPTYP) == DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1 ) { // Take odd/even bit from frame counter. uint32_t const odd_frame_now = (dwc2->dsts & (1u << DSTS_FNSOF_Pos)); - in_ep[epnum].diepctl |= (odd_frame_now ? DIEPCTL_SD0PID_SEVNFRM_Msk : DIEPCTL_SODDFRM_Msk); + dwc2->epin[epnum].diepctl |= (odd_frame_now ? DIEPCTL_SD0PID_SEVNFRM_Msk : DIEPCTL_SODDFRM_Msk); } // Enable fifo empty interrupt only if there are something to put in the fifo. if ( total_bytes != 0 ) @@ -462,7 +460,6 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) (void) rhport; dwc2_regs_t * dwc2 = DWC2_REG(rhport); - dwc2_epin_t * in_ep = EPIN_REG(rhport); uint8_t const epnum = tu_edpt_number(desc_edpt->bEndpointAddress); uint8_t const dir = tu_edpt_dir(desc_edpt->bEndpointAddress); @@ -530,7 +527,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // Both TXFD and TXSA are in unit of 32-bit words. dwc2->dieptxf[epnum - 1] = (fifo_size << DIEPTXF_INEPTXFD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); - in_ep[epnum].diepctl |= (1 << DIEPCTL_USBAEP_Pos) | + dwc2->epin[epnum].diepctl |= (1 << DIEPCTL_USBAEP_Pos) | (epnum << DIEPCTL_TXFNUM_Pos) | (desc_edpt->bmAttributes.xfer << DIEPCTL_EPTYP_Pos) | (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DIEPCTL_SD0PID_SEVNFRM : 0) | @@ -548,7 +545,6 @@ void dcd_edpt_close_all (uint8_t rhport) (void) rhport; dwc2_regs_t * dwc2 = DWC2_REG(rhport); - dwc2_epin_t * in_ep = EPIN_REG(rhport); // Disable non-control interrupt dwc2->daintmsk = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); @@ -560,7 +556,7 @@ void dcd_edpt_close_all (uint8_t rhport) xfer_status[n][TUSB_DIR_OUT].max_size = 0; // disable IN endpoint - in_ep[n].diepctl = 0; + dwc2->epin[n].diepctl = 0; xfer_status[n][TUSB_DIR_IN].max_size = 0; } @@ -633,7 +629,6 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) (void) rhport; dwc2_regs_t * dwc2 = DWC2_REG(rhport); - dwc2_epin_t * in_ep = EPIN_REG(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const dir = tu_edpt_dir(ep_addr); @@ -641,21 +636,21 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) if ( dir == TUSB_DIR_IN ) { // Only disable currently enabled non-control endpoint - if ( (epnum == 0) || !(in_ep[epnum].diepctl & DIEPCTL_EPENA) ) + if ( (epnum == 0) || !(dwc2->epin[epnum].diepctl & DIEPCTL_EPENA) ) { - in_ep[epnum].diepctl |= DIEPCTL_SNAK | (stall ? DIEPCTL_STALL : 0); + dwc2->epin[epnum].diepctl |= DIEPCTL_SNAK | (stall ? DIEPCTL_STALL : 0); } else { // Stop transmitting packets and NAK IN xfers. - in_ep[epnum].diepctl |= DIEPCTL_SNAK; - while ( (in_ep[epnum].diepint & DIEPINT_INEPNE) == 0 ) {} + dwc2->epin[epnum].diepctl |= DIEPCTL_SNAK; + while ( (dwc2->epin[epnum].diepint & DIEPINT_INEPNE) == 0 ) {} // Disable the endpoint. - in_ep[epnum].diepctl |= DIEPCTL_EPDIS | (stall ? DIEPCTL_STALL : 0); - while ( (in_ep[epnum].diepint & DIEPINT_EPDISD_Msk) == 0 ) {} + dwc2->epin[epnum].diepctl |= DIEPCTL_EPDIS | (stall ? DIEPCTL_STALL : 0); + while ( (dwc2->epin[epnum].diepint & DIEPINT_EPDISD_Msk) == 0 ) {} - in_ep[epnum].diepint = DIEPINT_EPDISD; + dwc2->epin[epnum].diepint = DIEPINT_EPDISD; } // Flush the FIFO, and wait until we have confirmed it cleared. @@ -730,7 +725,6 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) (void) rhport; dwc2_regs_t * dwc2 = DWC2_REG(rhport); - dwc2_epin_t * in_ep = EPIN_REG(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const dir = tu_edpt_dir(ep_addr); @@ -738,8 +732,8 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) // Clear stall and reset data toggle if ( dir == TUSB_DIR_IN ) { - in_ep[epnum].diepctl &= ~DIEPCTL_STALL; - in_ep[epnum].diepctl |= DIEPCTL_SD0PID_SEVNFRM; + dwc2->epin[epnum].diepctl &= ~DIEPCTL_STALL; + dwc2->epin[epnum].diepctl |= DIEPCTL_SD0PID_SEVNFRM; } else { @@ -924,7 +918,8 @@ static void handle_epout_ints (uint8_t rhport, dwc2_regs_t *dwc2) } } -static void handle_epin_ints(uint8_t rhport, dwc2_regs_t * dwc2, dwc2_epin_t * in_ep) { +static void handle_epin_ints (uint8_t rhport, dwc2_regs_t *dwc2) +{ // DAINT for a given EP clears when DIEPINTx is cleared. // IEPINT will be cleared when DAINT's out bits are cleared. for ( uint8_t n = 0; n < DWC2_EP_MAX; n++ ) @@ -934,46 +929,49 @@ static void handle_epin_ints(uint8_t rhport, dwc2_regs_t * dwc2, dwc2_epin_t * i if ( dwc2->daint & (1 << (DAINT_IEPINT_Pos + n)) ) { // IN XFER complete (entire xfer). - if ( in_ep[n].diepint & DIEPINT_XFRC ) + if ( dwc2->epin[n].diepint & DIEPINT_XFRC ) { - in_ep[n].diepint = DIEPINT_XFRC; + dwc2->epin[n].diepint = DIEPINT_XFRC; // EP0 can only handle one packet - if((n == 0) && ep0_pending[TUSB_DIR_IN]) { + if ( (n == 0) && ep0_pending[TUSB_DIR_IN] ) + { // Schedule another packet to be transmitted. edpt_schedule_packets(rhport, n, TUSB_DIR_IN, 1, ep0_pending[TUSB_DIR_IN]); - } else { + } + else + { dcd_event_xfer_complete(rhport, n | TUSB_DIR_IN_MASK, xfer->total_len, XFER_RESULT_SUCCESS, true); } } // XFER FIFO empty - if ( (in_ep[n].diepint & DIEPINT_TXFE) && (dwc2->diepempmsk & (1 << n)) ) + if ( (dwc2->epin[n].diepint & DIEPINT_TXFE) && (dwc2->diepempmsk & (1 << n)) ) { // diepint's TXFE bit is read-only, software cannot clear it. // It will only be cleared by hardware when written bytes is more than // - 64 bytes or // - Half of TX FIFO size (configured by DIEPTXF) - uint16_t remaining_packets = (in_ep[n].dieptsiz & DIEPTSIZ_PKTCNT_Msk) >> DIEPTSIZ_PKTCNT_Pos; + uint16_t remaining_packets = (dwc2->epin[n].dieptsiz & DIEPTSIZ_PKTCNT_Msk) >> DIEPTSIZ_PKTCNT_Pos; // Process every single packet (only whole packets can be written to fifo) - for(uint16_t i = 0; i < remaining_packets; i++) + for ( uint16_t i = 0; i < remaining_packets; i++ ) { - uint16_t const remaining_bytes = (in_ep[n].dieptsiz & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos; + uint16_t const remaining_bytes = (dwc2->epin[n].dieptsiz & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos; // Packet can not be larger than ep max size uint16_t const packet_size = tu_min16(remaining_bytes, xfer->max_size); // It's only possible to write full packets into FIFO. Therefore DTXFSTS register of current // EP has to be checked if the buffer can take another WHOLE packet - if(packet_size > ((in_ep[n].dtxfsts & DTXFSTS_INEPTFSAV_Msk) << 2)) break; + if ( packet_size > ((dwc2->epin[n].dtxfsts & DTXFSTS_INEPTFSAV_Msk) << 2) ) break; // Push packet to Tx-FIFO - if (xfer->ff) + if ( xfer->ff ) { - volatile uint32_t * tx_fifo = dwc2->fifo[n]; - tu_fifo_read_n_const_addr_full_words(xfer->ff, (void *)(uintptr_t) tx_fifo, packet_size); + volatile uint32_t *tx_fifo = dwc2->fifo[n]; + tu_fifo_read_n_const_addr_full_words(xfer->ff, (void*) (uintptr_t) tx_fifo, packet_size); } else { @@ -985,7 +983,7 @@ static void handle_epin_ints(uint8_t rhport, dwc2_regs_t * dwc2, dwc2_epin_t * i } // Turn off TXFE if all bytes are written. - if (((in_ep[n].dieptsiz & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos) == 0) + if ( ((dwc2->epin[n].dieptsiz & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos) == 0 ) { dwc2->diepempmsk &= ~(1 << n); } @@ -997,7 +995,6 @@ static void handle_epin_ints(uint8_t rhport, dwc2_regs_t * dwc2, dwc2_epin_t * i void dcd_int_handler(uint8_t rhport) { dwc2_regs_t * dwc2 = DWC2_REG(rhport); - dwc2_epin_t * in_ep = EPIN_REG(rhport); uint32_t const int_status = dwc2->gintsts & dwc2->gintmsk; @@ -1095,7 +1092,7 @@ void dcd_int_handler(uint8_t rhport) if(int_status & GINTSTS_IEPINT) { // IEPINT bit read-only - handle_epin_ints(rhport, dwc2, in_ep); + handle_epin_ints(rhport, dwc2); } // // Check for Incomplete isochronous IN transfer From 4ebfd00d6741233a3dfcc3a74ee71f593887e847 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 Oct 2021 13:33:40 +0700 Subject: [PATCH 27/51] clean up --- src/portable/synopsys/dwc2/dcd_dwc2.c | 146 ++++++++++++++------------ 1 file changed, 80 insertions(+), 66 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index ec1dac66c..15dece1df 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -111,7 +111,7 @@ static void bus_reset(uint8_t rhport) { (void) rhport; - dwc2_regs_t * dwc2 = DWC2_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); tu_memclr(xfer_status, sizeof(xfer_status)); _out_ep_closed = false; @@ -269,7 +269,7 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c { (void) rhport; - dwc2_regs_t * dwc2 = DWC2_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); // EP0 is limited to one packet each xfer // We use multiple transaction of xfer->max_size length to get a whole transfer done @@ -283,18 +283,20 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c // IN and OUT endpoint xfers are interrupt-driven, we just schedule them here. if ( dir == TUSB_DIR_IN ) { + dwc2_epin_t* epin = dwc2->epin; + // A full IN transfer (multiple packets, possibly) triggers XFRC. - dwc2->epin[epnum].dieptsiz = (num_packets << DIEPTSIZ_PKTCNT_Pos) | + epin[epnum].dieptsiz = (num_packets << DIEPTSIZ_PKTCNT_Pos) | ((total_bytes << DIEPTSIZ_XFRSIZ_Pos) & DIEPTSIZ_XFRSIZ_Msk); - dwc2->epin[epnum].diepctl |= DIEPCTL_EPENA | DIEPCTL_CNAK; + epin[epnum].diepctl |= DIEPCTL_EPENA | DIEPCTL_CNAK; // For ISO endpoint set correct odd/even bit for next frame. - if ( (dwc2->epin[epnum].diepctl & DIEPCTL_EPTYP) == DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1 ) + if ( (epin[epnum].diepctl & DIEPCTL_EPTYP) == DIEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1 ) { // Take odd/even bit from frame counter. uint32_t const odd_frame_now = (dwc2->dsts & (1u << DSTS_FNSOF_Pos)); - dwc2->epin[epnum].diepctl |= (odd_frame_now ? DIEPCTL_SD0PID_SEVNFRM_Msk : DIEPCTL_SODDFRM_Msk); + epin[epnum].diepctl |= (odd_frame_now ? DIEPCTL_SD0PID_SEVNFRM_Msk : DIEPCTL_SODDFRM_Msk); } // Enable fifo empty interrupt only if there are something to put in the fifo. if ( total_bytes != 0 ) @@ -304,17 +306,19 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c } else { + dwc2_epout_t* epout = dwc2->epout; + // A full OUT transfer (multiple packets, possibly) triggers XFRC. - dwc2->epout[epnum].doeptsiz &= ~(DOEPTSIZ_PKTCNT_Msk | DOEPTSIZ_XFRSIZ); - dwc2->epout[epnum].doeptsiz |= (num_packets << DOEPTSIZ_PKTCNT_Pos) | + epout[epnum].doeptsiz &= ~(DOEPTSIZ_PKTCNT_Msk | DOEPTSIZ_XFRSIZ); + epout[epnum].doeptsiz |= (num_packets << DOEPTSIZ_PKTCNT_Pos) | ((total_bytes << DOEPTSIZ_XFRSIZ_Pos) & DOEPTSIZ_XFRSIZ_Msk); - dwc2->epout[epnum].doepctl |= DOEPCTL_EPENA | DOEPCTL_CNAK; - if ( (dwc2->epout[epnum].doepctl & DOEPCTL_EPTYP) == DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1 ) + epout[epnum].doepctl |= DOEPCTL_EPENA | DOEPCTL_CNAK; + if ( (epout[epnum].doepctl & DOEPCTL_EPTYP) == DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1 ) { // Take odd/even bit from frame counter. uint32_t const odd_frame_now = (dwc2->dsts & (1u << DSTS_FNSOF_Pos)); - dwc2->epout[epnum].doepctl |= (odd_frame_now ? DOEPCTL_SD0PID_SEVNFRM_Msk : DOEPCTL_SODDFRM_Msk); + epout[epnum].doepctl |= (odd_frame_now ? DOEPCTL_SD0PID_SEVNFRM_Msk : DOEPCTL_SODDFRM_Msk); } } } @@ -421,7 +425,7 @@ void dcd_remote_wakeup(uint8_t rhport) { (void) rhport; - dwc2_regs_t* dwc2 = DWC2_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); // set remote wakeup dwc2->dctl |= DCTL_RWUSIG; @@ -459,7 +463,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) { (void) rhport; - dwc2_regs_t * dwc2 = DWC2_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); uint8_t const epnum = tu_edpt_number(desc_edpt->bEndpointAddress); uint8_t const dir = tu_edpt_dir(desc_edpt->bEndpointAddress); @@ -486,10 +490,10 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) dwc2->grxfsiz = sz; } - dwc2->epout[epnum].doepctl |= (1 << DOEPCTL_USBAEP_Pos) | - (desc_edpt->bmAttributes.xfer << DOEPCTL_EPTYP_Pos) | - (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DOEPCTL_SD0PID_SEVNFRM : 0) | - (xfer->max_size << DOEPCTL_MPSIZ_Pos); + dwc2->epout[epnum].doepctl |= (1 << DOEPCTL_USBAEP_Pos) | + (desc_edpt->bmAttributes.xfer << DOEPCTL_EPTYP_Pos) | + (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DOEPCTL_SD0PID_SEVNFRM : 0) | + (xfer->max_size << DOEPCTL_MPSIZ_Pos); dwc2->daintmsk |= (1 << (DAINTMSK_OEPM_Pos + epnum)); } @@ -528,10 +532,10 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) dwc2->dieptxf[epnum - 1] = (fifo_size << DIEPTXF_INEPTXFD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); dwc2->epin[epnum].diepctl |= (1 << DIEPCTL_USBAEP_Pos) | - (epnum << DIEPCTL_TXFNUM_Pos) | - (desc_edpt->bmAttributes.xfer << DIEPCTL_EPTYP_Pos) | - (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DIEPCTL_SD0PID_SEVNFRM : 0) | - (xfer->max_size << DIEPCTL_MPSIZ_Pos); + (epnum << DIEPCTL_TXFNUM_Pos) | + (desc_edpt->bmAttributes.xfer << DIEPCTL_EPTYP_Pos) | + (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DIEPCTL_SD0PID_SEVNFRM : 0) | + (xfer->max_size << DIEPCTL_MPSIZ_Pos); dwc2->daintmsk |= (1 << (DAINTMSK_IEPM_Pos + epnum)); } @@ -544,7 +548,7 @@ void dcd_edpt_close_all (uint8_t rhport) { (void) rhport; - dwc2_regs_t * dwc2 = DWC2_REG(rhport); + dwc2_regs_t * dwc2 = DWC2_REG(rhport); // Disable non-control interrupt dwc2->daintmsk = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); @@ -628,29 +632,31 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) { (void) rhport; - dwc2_regs_t * dwc2 = DWC2_REG(rhport); + dwc2_regs_t *dwc2 = DWC2_REG(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const dir = tu_edpt_dir(ep_addr); if ( dir == TUSB_DIR_IN ) { + dwc2_epin_t* epin = dwc2->epin; + // Only disable currently enabled non-control endpoint - if ( (epnum == 0) || !(dwc2->epin[epnum].diepctl & DIEPCTL_EPENA) ) + if ( (epnum == 0) || !(epin[epnum].diepctl & DIEPCTL_EPENA) ) { - dwc2->epin[epnum].diepctl |= DIEPCTL_SNAK | (stall ? DIEPCTL_STALL : 0); + epin[epnum].diepctl |= DIEPCTL_SNAK | (stall ? DIEPCTL_STALL : 0); } else { // Stop transmitting packets and NAK IN xfers. - dwc2->epin[epnum].diepctl |= DIEPCTL_SNAK; - while ( (dwc2->epin[epnum].diepint & DIEPINT_INEPNE) == 0 ) {} + epin[epnum].diepctl |= DIEPCTL_SNAK; + while ( (epin[epnum].diepint & DIEPINT_INEPNE) == 0 ) {} // Disable the endpoint. - dwc2->epin[epnum].diepctl |= DIEPCTL_EPDIS | (stall ? DIEPCTL_STALL : 0); - while ( (dwc2->epin[epnum].diepint & DIEPINT_EPDISD_Msk) == 0 ) {} + epin[epnum].diepctl |= DIEPCTL_EPDIS | (stall ? DIEPCTL_STALL : 0); + while ( (epin[epnum].diepint & DIEPINT_EPDISD_Msk) == 0 ) {} - dwc2->epin[epnum].diepint = DIEPINT_EPDISD; + epin[epnum].diepint = DIEPINT_EPDISD; } // Flush the FIFO, and wait until we have confirmed it cleared. @@ -660,10 +666,12 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) } else { + dwc2_epout_t* epout = dwc2->epout; + // Only disable currently enabled non-control endpoint - if ( (epnum == 0) || !(dwc2->epout[epnum].doepctl & DOEPCTL_EPENA) ) + if ( (epnum == 0) || !(epout[epnum].doepctl & DOEPCTL_EPENA) ) { - dwc2->epout[epnum].doepctl |= stall ? DOEPCTL_STALL : 0; + epout[epnum].doepctl |= stall ? DOEPCTL_STALL : 0; } else { @@ -675,10 +683,10 @@ static void dcd_edpt_disable (uint8_t rhport, uint8_t ep_addr, bool stall) while ( (dwc2->gintsts & GINTSTS_BOUTNAKEFF_Msk) == 0 ) {} // Ditto here- disable the endpoint. - dwc2->epout[epnum].doepctl |= DOEPCTL_EPDIS | (stall ? DOEPCTL_STALL : 0); - while ( (dwc2->epout[epnum].doepint & DOEPINT_EPDISD_Msk) == 0 ) {} + epout[epnum].doepctl |= DOEPCTL_EPDIS | (stall ? DOEPCTL_STALL : 0); + while ( (epout[epnum].doepint & DOEPINT_EPDISD_Msk) == 0 ) {} - dwc2->epout[epnum].doepint = DOEPINT_EPDISD; + epout[epnum].doepint = DOEPINT_EPDISD; // Allow other OUT endpoints to keep receiving. dwc2->dctl |= DCTL_CGONAK; @@ -826,20 +834,20 @@ static void handle_rxflvl_ints(uint8_t rhport) uint8_t epnum = (ctl_word & GRXSTSP_EPNUM_Msk) >> GRXSTSP_EPNUM_Pos; uint16_t bcnt = (ctl_word & GRXSTSP_BCNT_Msk) >> GRXSTSP_BCNT_Pos; - switch(pktsts) + switch ( pktsts ) { - case 0x01: // Global OUT NAK (Interrupt) - break; + case 0x01: // Global OUT NAK (Interrupt) + break; - case 0x02: // Out packet recvd + case 0x02: // Out packet received { - xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, TUSB_DIR_OUT); + xfer_ctl_t *xfer = XFER_CTL_BASE(epnum, TUSB_DIR_OUT); // Read packet off RxFIFO - if (xfer->ff) + if ( xfer->ff ) { // Ring buffer - tu_fifo_write_n_const_addr_full_words(xfer->ff, (const void *)(uintptr_t) rx_fifo, bcnt); + tu_fifo_write_n_const_addr_full_words(xfer->ff, (const void*) (uintptr_t) rx_fifo, bcnt); } else { @@ -851,9 +859,11 @@ static void handle_rxflvl_ints(uint8_t rhport) } // Truncate transfer length in case of short packet - if(bcnt < xfer->max_size) { + if ( bcnt < xfer->max_size ) + { xfer->total_len -= (dwc2->epout[epnum].doeptsiz & DOEPTSIZ_XFRSIZ_Msk) >> DOEPTSIZ_XFRSIZ_Pos; - if(epnum == 0) { + if ( epnum == 0 ) + { xfer->total_len -= ep0_pending[TUSB_DIR_OUT]; ep0_pending[TUSB_DIR_OUT] = 0; } @@ -861,28 +871,30 @@ static void handle_rxflvl_ints(uint8_t rhport) } break; - case 0x03: // Out packet done (Interrupt) - break; + case 0x03: // Out packet done (Interrupt) + break; - case 0x04: // Setup packet done (Interrupt) + case 0x04: // Setup packet done (Interrupt) dwc2->epout[epnum].doeptsiz |= (3 << DOEPTSIZ_STUPCNT_Pos); - break; + break; - case 0x06: // Setup packet recvd + case 0x06: // Setup packet recvd // We can receive up to three setup packets in succession, but // only the last one is valid. - _setup_packet[0] = (* rx_fifo); - _setup_packet[1] = (* rx_fifo); - break; + _setup_packet[0] = (*rx_fifo); + _setup_packet[1] = (*rx_fifo); + break; - default: // Invalid + default: // Invalid TU_BREAKPOINT(); - break; + break; } } static void handle_epout_ints (uint8_t rhport, dwc2_regs_t *dwc2) { + dwc2_epout_t* epout = dwc2->epout; + // DAINT for a given EP clears when DOEPINTx is cleared. // OEPINT will be cleared when DAINT's out bits are cleared. for ( uint8_t n = 0; n < DWC2_EP_MAX; n++ ) @@ -892,16 +904,16 @@ static void handle_epout_ints (uint8_t rhport, dwc2_regs_t *dwc2) if ( dwc2->daint & (1 << (DAINT_OEPINT_Pos + n)) ) { // SETUP packet Setup Phase done. - if ( dwc2->epout[n].doepint & DOEPINT_STUP ) + if ( epout[n].doepint & DOEPINT_STUP ) { - dwc2->epout[n].doepint = DOEPINT_STUP; + epout[n].doepint = DOEPINT_STUP; dcd_event_setup_received(rhport, (uint8_t*) &_setup_packet[0], true); } // OUT XFER complete - if ( dwc2->epout[n].doepint & DOEPINT_XFRC ) + if ( epout[n].doepint & DOEPINT_XFRC ) { - dwc2->epout[n].doepint = DOEPINT_XFRC; + epout[n].doepint = DOEPINT_XFRC; // EP0 can only handle one packet if ( (n == 0) && ep0_pending[TUSB_DIR_OUT] ) @@ -920,6 +932,8 @@ static void handle_epout_ints (uint8_t rhport, dwc2_regs_t *dwc2) static void handle_epin_ints (uint8_t rhport, dwc2_regs_t *dwc2) { + dwc2_epin_t* epin = dwc2->epin; + // DAINT for a given EP clears when DIEPINTx is cleared. // IEPINT will be cleared when DAINT's out bits are cleared. for ( uint8_t n = 0; n < DWC2_EP_MAX; n++ ) @@ -929,9 +943,9 @@ static void handle_epin_ints (uint8_t rhport, dwc2_regs_t *dwc2) if ( dwc2->daint & (1 << (DAINT_IEPINT_Pos + n)) ) { // IN XFER complete (entire xfer). - if ( dwc2->epin[n].diepint & DIEPINT_XFRC ) + if ( epin[n].diepint & DIEPINT_XFRC ) { - dwc2->epin[n].diepint = DIEPINT_XFRC; + epin[n].diepint = DIEPINT_XFRC; // EP0 can only handle one packet if ( (n == 0) && ep0_pending[TUSB_DIR_IN] ) @@ -946,26 +960,26 @@ static void handle_epin_ints (uint8_t rhport, dwc2_regs_t *dwc2) } // XFER FIFO empty - if ( (dwc2->epin[n].diepint & DIEPINT_TXFE) && (dwc2->diepempmsk & (1 << n)) ) + if ( (epin[n].diepint & DIEPINT_TXFE) && (dwc2->diepempmsk & (1 << n)) ) { // diepint's TXFE bit is read-only, software cannot clear it. // It will only be cleared by hardware when written bytes is more than // - 64 bytes or // - Half of TX FIFO size (configured by DIEPTXF) - uint16_t remaining_packets = (dwc2->epin[n].dieptsiz & DIEPTSIZ_PKTCNT_Msk) >> DIEPTSIZ_PKTCNT_Pos; + uint16_t remaining_packets = (epin[n].dieptsiz & DIEPTSIZ_PKTCNT_Msk) >> DIEPTSIZ_PKTCNT_Pos; // Process every single packet (only whole packets can be written to fifo) for ( uint16_t i = 0; i < remaining_packets; i++ ) { - uint16_t const remaining_bytes = (dwc2->epin[n].dieptsiz & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos; + uint16_t const remaining_bytes = (epin[n].dieptsiz & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos; // Packet can not be larger than ep max size uint16_t const packet_size = tu_min16(remaining_bytes, xfer->max_size); // It's only possible to write full packets into FIFO. Therefore DTXFSTS register of current // EP has to be checked if the buffer can take another WHOLE packet - if ( packet_size > ((dwc2->epin[n].dtxfsts & DTXFSTS_INEPTFSAV_Msk) << 2) ) break; + if ( packet_size > ((epin[n].dtxfsts & DTXFSTS_INEPTFSAV_Msk) << 2) ) break; // Push packet to Tx-FIFO if ( xfer->ff ) @@ -983,7 +997,7 @@ static void handle_epin_ints (uint8_t rhport, dwc2_regs_t *dwc2) } // Turn off TXFE if all bytes are written. - if ( ((dwc2->epin[n].dieptsiz & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos) == 0 ) + if ( ((epin[n].dieptsiz & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos) == 0 ) { dwc2->diepempmsk &= ~(1 << n); } @@ -994,7 +1008,7 @@ static void handle_epin_ints (uint8_t rhport, dwc2_regs_t *dwc2) void dcd_int_handler(uint8_t rhport) { - dwc2_regs_t * dwc2 = DWC2_REG(rhport); + dwc2_regs_t *dwc2 = DWC2_REG(rhport); uint32_t const int_status = dwc2->gintsts & dwc2->gintmsk; From 5d05f8758fcf66ac8192eeefea7ff567ac749eb8 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 Oct 2021 13:36:43 +0700 Subject: [PATCH 28/51] more clean up --- src/portable/synopsys/dwc2/dcd_dwc2.c | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 15dece1df..d9e21652e 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -823,7 +823,7 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, u } } -static void handle_rxflvl_ints(uint8_t rhport) +static void handle_rxflvl_irq(uint8_t rhport) { dwc2_regs_t * dwc2 = DWC2_REG(rhport); volatile uint32_t * rx_fifo = dwc2->fifo[0]; @@ -891,8 +891,9 @@ static void handle_rxflvl_ints(uint8_t rhport) } } -static void handle_epout_ints (uint8_t rhport, dwc2_regs_t *dwc2) +static void handle_epout_irq (uint8_t rhport) { + dwc2_regs_t *dwc2 = DWC2_REG(rhport); dwc2_epout_t* epout = dwc2->epout; // DAINT for a given EP clears when DOEPINTx is cleared. @@ -930,8 +931,9 @@ static void handle_epout_ints (uint8_t rhport, dwc2_regs_t *dwc2) } } -static void handle_epin_ints (uint8_t rhport, dwc2_regs_t *dwc2) +static void handle_epin_irq (uint8_t rhport) { + dwc2_regs_t *dwc2 = DWC2_REG(rhport); dwc2_epin_t* epin = dwc2->epin; // DAINT for a given EP clears when DIEPINTx is cleared. @@ -1080,7 +1082,7 @@ void dcd_int_handler(uint8_t rhport) // Loop until all available packets were handled do { - handle_rxflvl_ints(rhport); + handle_rxflvl_irq(rhport); } while(dwc2->gotgint & GINTSTS_RXFLVL); // Manage RX FIFO size @@ -1099,14 +1101,14 @@ void dcd_int_handler(uint8_t rhport) if(int_status & GINTSTS_OEPINT) { // OEPINT is read-only - handle_epout_ints(rhport, dwc2); + handle_epout_irq(rhport); } // IN endpoint interrupt handling. if(int_status & GINTSTS_IEPINT) { // IEPINT bit read-only - handle_epin_ints(rhport, dwc2); + handle_epin_irq(rhport); } // // Check for Incomplete isochronous IN transfer From 68fa9d406495410914b55c50984d5a1b821ee80c Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 Oct 2021 13:56:56 +0700 Subject: [PATCH 29/51] enhance fifo read/write --- src/portable/synopsys/dwc2/dcd_dwc2.c | 54 ++++++++++----------------- 1 file changed, 19 insertions(+), 35 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index d9e21652e..67f84a083 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -758,39 +758,29 @@ static void read_fifo_packet(uint8_t rhport, uint8_t * dst, uint16_t len) (void) rhport; dwc2_regs_t * dwc2 = DWC2_REG(rhport); - volatile uint32_t * rx_fifo = dwc2->fifo[0]; + volatile const uint32_t * rx_fifo = dwc2->fifo[0]; // Reading full available 32 bit words from fifo uint16_t full_words = len >> 2; - for ( uint16_t i = 0; i < full_words; i++ ) + while(full_words--) { - uint32_t tmp = *rx_fifo; - dst[0] = tmp & 0x000000FF; - dst[1] = (tmp & 0x0000FF00) >> 8; - dst[2] = (tmp & 0x00FF0000) >> 16; - dst[3] = (tmp & 0xFF000000) >> 24; + tu_unaligned_write32(dst, *rx_fifo); dst += 4; } // Read the remaining 1-3 bytes from fifo - uint8_t bytes_rem = len & 0x03; + uint8_t const bytes_rem = len & 0x03; if ( bytes_rem != 0 ) { - uint32_t tmp = *rx_fifo; - dst[0] = tmp & 0x000000FF; - if ( bytes_rem > 1 ) - { - dst[1] = (tmp & 0x0000FF00) >> 8; - } - if ( bytes_rem > 2 ) - { - dst[2] = (tmp & 0x00FF0000) >> 16; - } + uint32_t const tmp = *rx_fifo; + dst[0] = tu_u32_byte0(tmp); + if ( bytes_rem > 1 ) dst[1] = tu_u32_byte1(tmp); + if ( bytes_rem > 2 ) dst[2] = tu_u32_byte2(tmp); } } // Write a single data packet to EPIN FIFO -static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, uint16_t len) +static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t const * src, uint16_t len) { (void) rhport; @@ -799,26 +789,20 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, u // Pushing full available 32 bit words to fifo uint16_t full_words = len >> 2; - for ( uint16_t i = 0; i < full_words; i++ ) + while(full_words--) { - *tx_fifo = (src[3] << 24) | (src[2] << 16) | (src[1] << 8) | src[0]; + *tx_fifo = tu_unaligned_read32(src); src += 4; } // Write the remaining 1-3 bytes into fifo - uint8_t bytes_rem = len & 0x03; + uint8_t const bytes_rem = len & 0x03; if ( bytes_rem ) { - uint32_t tmp_word = 0; - tmp_word |= src[0]; - if ( bytes_rem > 1 ) - { - tmp_word |= src[1] << 8; - } - if ( bytes_rem > 2 ) - { - tmp_word |= src[2] << 16; - } + uint32_t tmp_word = src[0]; + if ( bytes_rem > 1 ) tmp_word |= (src[1] << 8); + if ( bytes_rem > 2 ) tmp_word |= (src[2] << 16); + *tx_fifo = tmp_word; } } @@ -830,9 +814,9 @@ static void handle_rxflvl_irq(uint8_t rhport) // Pop control word off FIFO uint32_t ctl_word = dwc2->grxstsp; - uint8_t pktsts = (ctl_word & GRXSTSP_PKTSTS_Msk) >> GRXSTSP_PKTSTS_Pos; - uint8_t epnum = (ctl_word & GRXSTSP_EPNUM_Msk) >> GRXSTSP_EPNUM_Pos; - uint16_t bcnt = (ctl_word & GRXSTSP_BCNT_Msk) >> GRXSTSP_BCNT_Pos; + uint8_t pktsts = (ctl_word & GRXSTSP_PKTSTS_Msk ) >> GRXSTSP_PKTSTS_Pos; + uint8_t epnum = (ctl_word & GRXSTSP_EPNUM_Msk ) >> GRXSTSP_EPNUM_Pos; + uint16_t bcnt = (ctl_word & GRXSTSP_BCNT_Msk ) >> GRXSTSP_BCNT_Pos; switch ( pktsts ) { From bb5dab5c2e81be277214a6704a8d90e89a5b4759 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 Oct 2021 22:48:01 +0700 Subject: [PATCH 30/51] add hw config struct --- hw/bsp/board.c | 2 +- src/common/tusb_common.h | 4 +- src/portable/synopsys/dwc2/dcd_dwc2.c | 92 ++++++++-- src/portable/synopsys/dwc2/dwc2_type.h | 234 ++++++++++++++++--------- 4 files changed, 240 insertions(+), 92 deletions(-) diff --git a/hw/bsp/board.c b/hw/bsp/board.c index 2c18b61b4..afacdef9f 100644 --- a/hw/bsp/board.c +++ b/hw/bsp/board.c @@ -96,7 +96,7 @@ void board_led_task(void) TU_ATTR_USED int sys_write (int fhdl, const void *buf, size_t count) { (void) fhdl; - SEGGER_RTT_Write(0, (char*) buf, (int) count); + SEGGER_RTT_Write(0, (const char*) buf, (int) count); return count; } diff --git a/src/common/tusb_common.h b/src/common/tusb_common.h index bf9641622..e62bcde12 100644 --- a/src/common/tusb_common.h +++ b/src/common/tusb_common.h @@ -303,8 +303,8 @@ void tu_print_var(uint8_t const* buf, uint32_t bufsize) #define TU_LOG1 tu_printf #define TU_LOG1_MEM tu_print_mem #define TU_LOG1_VAR(_x) tu_print_var((uint8_t const*)(_x), sizeof(*(_x))) -#define TU_LOG1_INT(_x) tu_printf(#_x " = %ld\r\n", (uint32_t) (_x) ) -#define TU_LOG1_HEX(_x) tu_printf(#_x " = %lX\r\n", (uint32_t) (_x) ) +#define TU_LOG1_INT(_x) tu_printf(#_x " = %ld\r\n", (unsigned long) (_x) ) +#define TU_LOG1_HEX(_x) tu_printf(#_x " = %lX\r\n", (unsigned long) (_x) ) // Log Level 2: Warn #if CFG_TUSB_DEBUG >= 2 diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 67f84a083..7b02c75cd 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -74,14 +74,14 @@ typedef struct { } xfer_ctl_t; xfer_ctl_t xfer_status[DWC2_EP_MAX][2]; -#define XFER_CTL_BASE(_ep, _dir) &xfer_status[_ep][_dir] +#define XFER_CTL_BASE(_ep, _dir) (&xfer_status[_ep][_dir]) // EP0 transfers are limited to 1 packet - larger sizes has to be split static uint16_t ep0_pending[2]; // Index determines direction as tusb_dir_t type // TX FIFO RAM allocation so far in words - RX FIFO size is readily available from dwc2->grxfsiz static uint16_t _allocated_fifo_words_tx; // TX FIFO size in words (IN EPs) -static bool _out_ep_closed; // Flag to check if RX FIFO size needs an update (reduce its size) +static bool _out_ep_closed; // Flag to check if RX FIFO size needs an update (reduce its size) // Calculate the RX FIFO size according to recommendations from reference manual static inline uint16_t calc_rx_ff_size(uint16_t ep_size) @@ -120,14 +120,15 @@ static void bus_reset(uint8_t rhport) dwc2->dcfg &= ~DCFG_DAD_Msk; // 1. NAK for all OUT endpoints - for(uint8_t n = 0; n < DWC2_EP_MAX; n++) { + for ( uint8_t n = 0; n < DWC2_EP_MAX; n++ ) + { dwc2->epout[n].doepctl |= DOEPCTL_SNAK; } // 2. Un-mask interrupt bits dwc2->daintmsk = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); dwc2->doepmsk = DOEPMSK_STUPM | DOEPMSK_XFRCM; - dwc2->diepmsk = DIEPMSK_TOM | DIEPMSK_XFRCM; + dwc2->diepmsk = DIEPMSK_TOM | DIEPMSK_XFRCM; // "USB Data FIFOs" section in reference manual // Peripheral FIFO architecture @@ -188,7 +189,8 @@ static void bus_reset(uint8_t rhport) // Fixed control EP0 size to 64 bytes dwc2->epin[0].diepctl &= ~(0x03 << DIEPCTL_MPSIZ_Pos); - xfer_status[0][TUSB_DIR_OUT].max_size = xfer_status[0][TUSB_DIR_IN].max_size = 64; + xfer_status[0][TUSB_DIR_OUT].max_size = 64; + xfer_status[0][TUSB_DIR_IN ].max_size = 64; dwc2->epout[0].doeptsiz |= (3 << DOEPTSIZ_STUPCNT_Pos); @@ -210,7 +212,7 @@ static void set_speed(uint8_t rhport, tusb_speed_t speed) if ( rhport == 1 ) { - bitvalue = ((TUSB_SPEED_HIGH == speed) ? DCD_HIGH_SPEED : DCD_FULL_SPEED_USE_HS); + bitvalue = (TUSB_SPEED_HIGH == speed ? DCD_HIGH_SPEED : DCD_FULL_SPEED_USE_HS); } else { @@ -287,7 +289,7 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c // A full IN transfer (multiple packets, possibly) triggers XFRC. epin[epnum].dieptsiz = (num_packets << DIEPTSIZ_PKTCNT_Pos) | - ((total_bytes << DIEPTSIZ_XFRSIZ_Pos) & DIEPTSIZ_XFRSIZ_Msk); + ((total_bytes << DIEPTSIZ_XFRSIZ_Pos) & DIEPTSIZ_XFRSIZ_Msk); epin[epnum].diepctl |= DIEPCTL_EPENA | DIEPCTL_CNAK; @@ -311,10 +313,11 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c // A full OUT transfer (multiple packets, possibly) triggers XFRC. epout[epnum].doeptsiz &= ~(DOEPTSIZ_PKTCNT_Msk | DOEPTSIZ_XFRSIZ); epout[epnum].doeptsiz |= (num_packets << DOEPTSIZ_PKTCNT_Pos) | - ((total_bytes << DOEPTSIZ_XFRSIZ_Pos) & DOEPTSIZ_XFRSIZ_Msk); + ((total_bytes << DOEPTSIZ_XFRSIZ_Pos) & DOEPTSIZ_XFRSIZ_Msk); epout[epnum].doepctl |= DOEPCTL_EPENA | DOEPCTL_CNAK; - if ( (epout[epnum].doepctl & DOEPCTL_EPTYP) == DOEPCTL_EPTYP_0 && (XFER_CTL_BASE(epnum, dir))->interval == 1 ) + if ( (epout[epnum].doepctl & DOEPCTL_EPTYP) == DOEPCTL_EPTYP_0 && + XFER_CTL_BASE(epnum, dir)->interval == 1 ) { // Take odd/even bit from frame counter. uint32_t const odd_frame_now = (dwc2->dsts & (1u << DSTS_FNSOF_Pos)); @@ -326,13 +329,82 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c /*------------------------------------------------------------------*/ /* Controller API *------------------------------------------------------------------*/ +void print_dwc2_info(dwc2_regs_t * dwc2) +{ + dwc2_ghwcfg2_t const * hw_cfg2 = &dwc2->ghwcfg2_bm; + dwc2_ghwcfg3_t const * hw_cfg3 = &dwc2->ghwcfg3_bm; + dwc2_ghwcfg4_t const * hw_cfg4 = &dwc2->ghwcfg4_bm; + + TU_LOG_HEX(1, dwc2->guid); + TU_LOG_HEX(1, dwc2->gsnpsid); + TU_LOG_HEX(1, dwc2->ghwcfg1); + + // HW configure 2 + TU_LOG(1, "\r\n"); + TU_LOG_HEX(1, dwc2->ghwcfg2); + TU_LOG_INT(1, hw_cfg2->op_mode ); + TU_LOG_INT(1, hw_cfg2->arch ); + TU_LOG_INT(1, hw_cfg2->point2point ); + TU_LOG_INT(1, hw_cfg2->hs_phy_type ); + TU_LOG_INT(1, hw_cfg2->fs_phy_type ); + TU_LOG_INT(1, hw_cfg2->num_dev_ep ); + TU_LOG_INT(1, hw_cfg2->num_host_ch ); + TU_LOG_INT(1, hw_cfg2->period_channel_support ); + TU_LOG_INT(1, hw_cfg2->enable_dynamic_fifo ); + TU_LOG_INT(1, hw_cfg2->mul_cpu_int ); + TU_LOG_INT(1, hw_cfg2->nperiod_tx_q_depth ); + TU_LOG_INT(1, hw_cfg2->host_period_tx_q_depth ); + TU_LOG_INT(1, hw_cfg2->dev_token_q_depth ); + TU_LOG_INT(1, hw_cfg2->otg_enable_ic_usb ); + + // HW configure 3 + TU_LOG(1, "\r\n"); + TU_LOG_HEX(1, dwc2->ghwcfg3); + TU_LOG_INT(1, hw_cfg3->xfer_size_width ); + TU_LOG_INT(1, hw_cfg3->packet_size_width ); + TU_LOG_INT(1, hw_cfg3->otg_enable ); + TU_LOG_INT(1, hw_cfg3->i2c_enable ); + TU_LOG_INT(1, hw_cfg3->vendor_ctrl_itf ); + TU_LOG_INT(1, hw_cfg3->optional_feature_removed ); + TU_LOG_INT(1, hw_cfg3->synch_reset ); + TU_LOG_INT(1, hw_cfg3->otg_adp_support ); + TU_LOG_INT(1, hw_cfg3->otg_enable_hsic ); + TU_LOG_INT(1, hw_cfg3->otg_bc_support ); + TU_LOG_INT(1, hw_cfg3->lpm_mode ); + TU_LOG_INT(1, hw_cfg3->total_fifo_size ); + + // HW configure 4 + TU_LOG(1, "\r\n"); + TU_LOG_HEX(1, dwc2->ghwcfg4); + TU_LOG_INT(1, hw_cfg4->num_dev_period_in_ep ); + TU_LOG_INT(1, hw_cfg4->power_optimized ); + TU_LOG_INT(1, hw_cfg4->ahb_freq_min ); + TU_LOG_INT(1, hw_cfg4->hibernation ); + TU_LOG_INT(1, hw_cfg4->service_interval_mode ); + TU_LOG_INT(1, hw_cfg4->ipg_isoc_en ); + TU_LOG_INT(1, hw_cfg4->acg_enable ); + TU_LOG_INT(1, hw_cfg4->utmi_phy_data_width ); + TU_LOG_INT(1, hw_cfg4->dev_ctrl_ep_num ); + TU_LOG_INT(1, hw_cfg4->iddg_filter_enabled ); + TU_LOG_INT(1, hw_cfg4->vbus_valid_filter_enabled ); + TU_LOG_INT(1, hw_cfg4->a_valid_filter_enabled ); + TU_LOG_INT(1, hw_cfg4->b_valid_filter_enabled ); + TU_LOG_INT(1, hw_cfg4->dedicated_fifos ); + TU_LOG_INT(1, hw_cfg4->num_dev_in_eps ); + TU_LOG_INT(1, hw_cfg4->dma_desc_enable ); + TU_LOG_INT(1, hw_cfg4->dma_dynamic ); +} + void dcd_init (uint8_t rhport) { // Programming model begins in the last section of the chapter on the USB // peripheral in each Reference Manual. dwc2_regs_t * dwc2 = DWC2_REG(rhport); - // check GSNPSID + // check gsnpsid + //TU_LOG_HEX(1, dwc2->gsnpsid); + + print_dwc2_info(dwc2); // No HNP/SRP (no OTG support), program timeout later. if ( rhport == 1 ) diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 5669aa88d..58e628970 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -19,6 +19,27 @@ #include "stdint.h" +/* DWC OTG HW Release versions */ +#define DWC2_CORE_REV_2_71a 0x4f54271a +#define DWC2_CORE_REV_2_72a 0x4f54272a +#define DWC2_CORE_REV_2_80a 0x4f54280a +#define DWC2_CORE_REV_2_90a 0x4f54290a +#define DWC2_CORE_REV_2_91a 0x4f54291a +#define DWC2_CORE_REV_2_92a 0x4f54292a +#define DWC2_CORE_REV_2_94a 0x4f54294a +#define DWC2_CORE_REV_3_00a 0x4f54300a +#define DWC2_CORE_REV_3_10a 0x4f54310a +#define DWC2_CORE_REV_4_00a 0x4f54400a +#define DWC2_CORE_REV_4_20a 0x4f54420a +#define DWC2_FS_IOT_REV_1_00a 0x5531100a +#define DWC2_HS_IOT_REV_1_00a 0x5532100a +#define DWC2_CORE_REV_MASK 0x0000ffff + +/* DWC OTG HW Core ID */ +#define DWC2_OTG_ID 0x4f540000 +#define DWC2_FS_IOT_ID 0x55310000 +#define DWC2_HS_IOT_ID 0x55320000 + #ifdef __cplusplus extern "C" { #endif @@ -37,93 +58,165 @@ typedef struct } HS_PHYC_GlobalTypeDef; #endif +typedef struct TU_ATTR_PACKED +{ + uint32_t op_mode : 3; // 0: HNP and SRP | 1: SRP | 2: non-HNP, non-SRP + uint32_t arch : 2; // 0: slave-only | 1: External DMA | 2: Internal DMA | 3: others + uint32_t point2point : 1; // 0: support hub and split | 1: no hub, no split + uint32_t hs_phy_type : 2; // 0: not supported | 1: UTMI+ | 2: ULPI | 3: UTMI+ and ULPI + uint32_t fs_phy_type : 2; // 0: not supported | 1: dedicated | 2: UTMI+ | 3: ULPI + uint32_t num_dev_ep : 4; // Number of device endpoints (not including EP0) + uint32_t num_host_ch : 4; // Number of host channel + uint32_t period_channel_support : 1; // Support Periodic OUT Host Channel + uint32_t enable_dynamic_fifo : 1; // Dynamic FIFO Sizing Enabled + uint32_t mul_cpu_int : 1; // Multi-Processor Interrupt Enabled + uint32_t reserved21 : 1; + uint32_t nperiod_tx_q_depth : 2; // Non-periodic request queue depth: 0 = 2. 1 = 4, 2 = 8 + uint32_t host_period_tx_q_depth : 2; // Host periodic request queue depth: 0 = 2. 1 = 4, 2 = 8 + uint32_t dev_token_q_depth : 5; // Device IN token sequence learning queue depth: 0-30 + uint32_t otg_enable_ic_usb : 1; // IC_USB mode specified for mode of operation +} dwc2_ghwcfg2_t; + +TU_VERIFY_STATIC(sizeof(dwc2_ghwcfg2_t) == 4, "incorrect size"); + +typedef struct TU_ATTR_PACKED +{ + uint32_t xfer_size_width : 4; // Transfer size counter in bits = 11 + n (max 19 bits) + uint32_t packet_size_width : 3; // Packet size counter in bits = 4 + n (max 10 bits) + uint32_t otg_enable : 1; // 1 is OTG capable + uint32_t i2c_enable : 1; // I2C interface is available + uint32_t vendor_ctrl_itf : 1; // Vendor control interface is available + uint32_t optional_feature_removed : 1; // remove User ID, GPIO, SOF toggle & counter + uint32_t synch_reset : 1; // 0: async reset | 1: synch reset + uint32_t otg_adp_support : 1; // ADP logic is present along with HSOTG controller + uint32_t otg_enable_hsic : 1; // 1: HSIC-capable with shared UTMI PHY interface | 0: non-HSIC + uint32_t otg_bc_support : 1; // support battery charger + uint32_t lpm_mode : 1; // LPC mode + uint32_t total_fifo_size : 16; // DFIFO depth value in terms of 32-bit words +}dwc2_ghwcfg3_t; + +TU_VERIFY_STATIC(sizeof(dwc2_ghwcfg3_t) == 4, "incorrect size"); + +typedef struct TU_ATTR_PACKED +{ + uint32_t num_dev_period_in_ep : 4; // Number of Device Periodic IN Endpoints + uint32_t power_optimized : 1; // Partial Power Down Enabled + uint32_t ahb_freq_min : 1; // 1: minimum of AHB frequency is less than 60 MHz + uint32_t hibernation : 1; // Hibernation feature is enabled + uint32_t reserved7 : 3; + uint32_t service_interval_mode : 1; // Service Interval supported + uint32_t ipg_isoc_en : 1; // IPG ISOC supported + uint32_t acg_enable : 1; // ACG enabled + uint32_t reserved13 : 1; + uint32_t utmi_phy_data_width : 2; // 0: 8 bits | 1: 16 bits | 2: 8/16 software selectable + uint32_t dev_ctrl_ep_num : 4; // Number of Device control endpoints in addition to EP0 + uint32_t iddg_filter_enabled : 1; + uint32_t vbus_valid_filter_enabled : 1; + uint32_t a_valid_filter_enabled : 1; + uint32_t b_valid_filter_enabled : 1; + uint32_t dedicated_fifos : 1; // Dedicated tx fifo for device IN Endpoint is enabled + uint32_t num_dev_in_eps : 4; // Number of Device IN Endpoints including EP0 + uint32_t dma_desc_enable : 1; // scatter/gather DMA configuration + uint32_t dma_dynamic : 1; // Dynamic scatter/gather DMA +}dwc2_ghwcfg4_t; + +TU_VERIFY_STATIC(sizeof(dwc2_ghwcfg4_t) == 4, "incorrect size"); + // Host Channel typedef struct { - volatile uint32_t hcchar; // 500 + 20*ch Host Channel Characteristics Register - volatile uint32_t hcsplt; // 504 + 20*ch Host Channel Split Control Register - volatile uint32_t hcint; // 508 + 20*ch Host Channel Interrupt Register - volatile uint32_t hcintmsk; // 50C + 20*ch Host Channel Interrupt Mask Register - volatile uint32_t hctsiz; // 510 + 20*ch Host Channel Transfer Size Register - volatile uint32_t hcdma; // 514 + 20*ch Host Channel DMA Address Register + volatile uint32_t hcchar; // 500 + 20*ch Host Channel Characteristics + volatile uint32_t hcsplt; // 504 + 20*ch Host Channel Split Control + volatile uint32_t hcint; // 508 + 20*ch Host Channel Interrupt + volatile uint32_t hcintmsk; // 50C + 20*ch Host Channel Interrupt Mask + volatile uint32_t hctsiz; // 510 + 20*ch Host Channel Transfer Size + volatile uint32_t hcdma; // 514 + 20*ch Host Channel DMA Address uint32_t reserved518; // 518 + 20*ch - volatile uint32_t hcdmab; // 51C + 20*ch Host Channel DMA Address Register + volatile uint32_t hcdmab; // 51C + 20*ch Host Channel DMA Address } dwc2_channel_t; // Endpoint IN typedef struct { - volatile uint32_t diepctl; // 900 + 20*ep Device IN Endpoint Control - uint32_t reserved04; // 904 - volatile uint32_t diepint; // 908 + 20*ep Device IN Endpoint Interrupt - uint32_t reserved0c; // 90C - volatile uint32_t dieptsiz; // 910 + 20*ep Device IN Endpoint Transfer Size - volatile uint32_t diepdma; // 914 + 20*ep Device IN Endpoint DMA Address - volatile uint32_t dtxfsts; // 918 + 20*ep Device IN Endpoint Tx FIFO Status - uint32_t reserved1c; // 91C + volatile uint32_t diepctl; // 900 + 20*ep Device IN Endpoint Control + uint32_t reserved04; // 904 + volatile uint32_t diepint; // 908 + 20*ep Device IN Endpoint Interrupt + uint32_t reserved0c; // 90C + volatile uint32_t dieptsiz; // 910 + 20*ep Device IN Endpoint Transfer Size + volatile uint32_t diepdma; // 914 + 20*ep Device IN Endpoint DMA Address + volatile uint32_t dtxfsts; // 918 + 20*ep Device IN Endpoint Tx FIFO Status + uint32_t reserved1c; // 91C } dwc2_epin_t; // Endpoint OUT typedef struct { - volatile uint32_t doepctl; // B00 + 20*ep Device OUT Endpoint Control - uint32_t reserved04; // B04 - volatile uint32_t doepint; // B08 + 20*ep Device OUT Endpoint Interrupt - uint32_t reserved0c; // B0C - volatile uint32_t doeptsiz; // B10 + 20*ep Device OUT Endpoint Transfer Size - volatile uint32_t doepdma; // B14 + 20*ep Device OUT Endpoint DMA Address - uint32_t reserved18[2]; // B18..B1C + volatile uint32_t doepctl; // B00 + 20*ep Device OUT Endpoint Control + uint32_t reserved04; // B04 + volatile uint32_t doepint; // B08 + 20*ep Device OUT Endpoint Interrupt + uint32_t reserved0c; // B0C + volatile uint32_t doeptsiz; // B10 + 20*ep Device OUT Endpoint Transfer Size + volatile uint32_t doepdma; // B14 + 20*ep Device OUT Endpoint DMA Address + uint32_t reserved18[2]; // B18..B1C } dwc2_epout_t; typedef struct { //------------- Core Global -------------// - volatile uint32_t gotgctl; // 000 OTG Control and Status Register - volatile uint32_t gotgint; // 004 OTG Interrupt Register - volatile uint32_t gahbcfg; // 008 AHB Configuration Register - volatile uint32_t gusbcfg; // 00c USB Configuration Register - volatile uint32_t grstctl; // 010 Reset Register - volatile uint32_t gintsts; // 014 Interrupt Register - volatile uint32_t gintmsk; // 018 Interrupt Mask Register - volatile uint32_t grxstsr; // 01c Receive Status Debug Read Register - volatile uint32_t grxstsp; // 020 Receive Status Read/Pop Register - volatile uint32_t grxfsiz; // 024 Receive FIFO Size Register + volatile uint32_t gotgctl; // 000 OTG Control and Status + volatile uint32_t gotgint; // 004 OTG Interrupt + volatile uint32_t gahbcfg; // 008 AHB Configuration + volatile uint32_t gusbcfg; // 00c USB Configuration + volatile uint32_t grstctl; // 010 Reset + volatile uint32_t gintsts; // 014 Interrupt + volatile uint32_t gintmsk; // 018 Interrupt Mask + volatile uint32_t grxstsr; // 01c Receive Status Debug Read + volatile uint32_t grxstsp; // 020 Receive Status Read/Pop + volatile uint32_t grxfsiz; // 024 Receive FIFO Size union { - volatile uint32_t dieptxf0; // 028 EP0 Tx FIFO Size Register - volatile uint32_t gnptxfsiz; // 028 Non-periodic Transmit FIFO Size Register + volatile uint32_t dieptxf0; // 028 EP0 Tx FIFO Size + volatile uint32_t gnptxfsiz; // 028 Non-periodic Transmit FIFO Size }; - volatile uint32_t gnptxsts; // 02c Non-periodic Transmit FIFO/Queue Status Register - volatile uint32_t gi2cctl; // 030 I2C Address Register - volatile uint32_t gpvndctl; // 034 PHY Vendor Control Register + volatile uint32_t gnptxsts; // 02c Non-periodic Transmit FIFO/Queue Status + volatile uint32_t gi2cctl; // 030 I2C Address + volatile uint32_t gpvndctl; // 034 PHY Vendor Control union { - volatile uint32_t ggpio; // 038 General Purpose IO Register + volatile uint32_t ggpio; // 038 General Purpose IO volatile uint32_t stm32_gccfg; // 038 STM32 General Core Configuration }; - volatile uint32_t guid; // 03C User ID Register - volatile uint32_t gsnpsid; // 040 Synopsys ID Register - volatile uint32_t ghwcfg1; // 044 User Hardware Configuration 1 Register - volatile uint32_t ghwcfg2; // 048 User Hardware Configuration 2 Register - volatile uint32_t ghwcfg3; // 04C User Hardware Configuration 3 Register - volatile uint32_t ghwcfg4; // 050 User Hardware Configuration 4 Register - volatile uint32_t glpmcfg; // 054 Core LPM Configuration Register - volatile uint32_t gpwrdn; // 058 Power Down Register - volatile uint32_t gdfifocfg; // 05C DFIFO Software Configuration Register - volatile uint32_t gadpctl; // 060 ADP Timer, Control and Status Register - + volatile uint32_t guid; // 03C User (Application programmable) ID + volatile uint32_t gsnpsid; // 040 Synopsys ID + Release version + volatile uint32_t ghwcfg1; // 044 User Hardware Configuration1: endpoint dir (2 bit per ep) +union { + volatile uint32_t ghwcfg2; // 048 User Hardware Configuration2 + dwc2_ghwcfg2_t ghwcfg2_bm; +}; +union { + volatile uint32_t ghwcfg3; // 04C User Hardware Configuration3 + dwc2_ghwcfg3_t ghwcfg3_bm; +}; +union { + volatile uint32_t ghwcfg4; // 050 User Hardware Configuration4 + dwc2_ghwcfg4_t ghwcfg4_bm; +}; + volatile uint32_t glpmcfg; // 054 Core LPM Configuration + volatile uint32_t gpwrdn; // 058 Power Down + volatile uint32_t gdfifocfg; // 05C DFIFO Software Configuration + volatile uint32_t gadpctl; // 060 ADP Timer, Control and Status uint32_t reserved64[39]; // 064..0FF - volatile uint32_t hptxfsiz; // 100 Host Periodic Tx FIFO Size Register - volatile uint32_t dieptxf[15]; // 104..13C Device Periodic Transmit FIFO Size Register + volatile uint32_t hptxfsiz; // 100 Host Periodic Tx FIFO Size + volatile uint32_t dieptxf[15]; // 104..13C Device Periodic Transmit FIFO Size uint32_t reserved140[176]; // 140..3FF //------------- Host -------------// - volatile uint32_t hcfg; // 400 Host Configuration Register - volatile uint32_t hfir; // 404 Host Frame Interval Register + volatile uint32_t hcfg; // 400 Host Configuration + volatile uint32_t hfir; // 404 Host Frame Interval volatile uint32_t hfnum; // 408 Host Frame Number / Frame Remaining uint32_t reserved40c; // 40C volatile uint32_t hptxsts; // 410 Host Periodic TX FIFO / Queue Status - volatile uint32_t haint; // 414 Host All Channels Interrupt Register + volatile uint32_t haint; // 414 Host All Channels Interrupt volatile uint32_t haintmsk; // 418 Host All Channels Interrupt Mask - volatile uint32_t hflbaddr; // 41C Host Frame List Base Address Register + volatile uint32_t hflbaddr; // 41C Host Frame List Base Address uint32_t reserved420[8]; // 420..43F volatile uint32_t hprt; // 440 Host Port Control and Status uint32_t reserved444[47]; // 444..4FF @@ -133,18 +226,18 @@ union { uint32_t reserved700[64]; // 700..7FF //------------- Device -------------// - volatile uint32_t dcfg; // 800 Device Configuration Register - volatile uint32_t dctl; // 804 Device Control Register - volatile uint32_t dsts; // 808 Device Status Register (RO) + volatile uint32_t dcfg; // 800 Device Configuration + volatile uint32_t dctl; // 804 Device Control + volatile uint32_t dsts; // 808 Device Status (RO) uint32_t reserved80c; // 80C volatile uint32_t diepmsk; // 810 Device IN Endpoint Interrupt Mask volatile uint32_t doepmsk; // 814 Device OUT Endpoint Interrupt Mask volatile uint32_t daint; // 818 Device All Endpoints Interrupt volatile uint32_t daintmsk; // 81C Device All Endpoints Interrupt Mask - volatile uint32_t dtknqr1; // 820 Device IN token sequence learning queue read register1 - volatile uint32_t dtknqr2; // 824 Device IN token sequence learning queue read register2 - volatile uint32_t dvbusdis; // 828 Device VBUS Discharge Time Register - volatile uint32_t dvbuspulse; // 82C Device VBUS Pulsing Time Register + volatile uint32_t dtknqr1; // 820 Device IN token sequence learning queue read1 + volatile uint32_t dtknqr2; // 824 Device IN token sequence learning queue read2 + volatile uint32_t dvbusdis; // 828 Device VBUS Discharge Time + volatile uint32_t dvbuspulse; // 82C Device VBUS Pulsing Time volatile uint32_t dthrctl; // 830 Device threshold Control volatile uint32_t diepempmsk; // 834 Device IN Endpoint FIFO Empty Interrupt Mask volatile uint32_t deachint; // 838 Device Each Endpoint Interrupt @@ -176,23 +269,6 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, epout ) == 0x0B00, "incorrect size"); TU_VERIFY_STATIC(offsetof(dwc2_regs_t, pcgctrl) == 0x0E00, "incorrect size"); TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); -//--------------------------------------------------------------------+ -// Register Base Address -//--------------------------------------------------------------------+ - -#define DWC2_GLOBAL_BASE 0x00000000UL -#define DWC2_DEVICE_BASE 0x00000800UL -#define DWC2_IN_ENDPOINT_BASE 0x00000900UL -#define DWC2_OUT_ENDPOINT_BASE 0x00000B00UL -#define DWC2_EP_REG_SIZE 0x00000020UL -#define DWC2_HOST_BASE 0x00000400UL -#define DWC2_HOST_PORT_BASE 0x00000440UL -#define DWC2_HOST_CHANNEL_BASE 0x00000500UL -#define DWC2_HOST_CHANNEL_SIZE 0x00000020UL -#define DWC2_PCGCCTL_BASE 0x00000E00UL -#define DWC2_FIFO_BASE 0x00001000UL -#define DWC2_FIFO_SIZE 0x00001000UL - //--------------------------------------------------------------------+ // Register Bit Definitions //--------------------------------------------------------------------+ From 9f1cd1a753400327072973cbf2437f6c51bd5509 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 Oct 2021 23:10:26 +0700 Subject: [PATCH 31/51] add synopsys id check, rename GCCFG_* to STM32_GCCFG-* --- src/portable/synopsys/dwc2/dcd_dwc2.c | 13 ++--- src/portable/synopsys/dwc2/dwc2_type.h | 72 +++++++++++++------------- 2 files changed, 43 insertions(+), 42 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 7b02c75cd..58305838f 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -401,8 +401,9 @@ void dcd_init (uint8_t rhport) // peripheral in each Reference Manual. dwc2_regs_t * dwc2 = DWC2_REG(rhport); - // check gsnpsid - //TU_LOG_HEX(1, dwc2->gsnpsid); + // Check Synopsys ID + uint32_t const gsnpsid = dwc2->gsnpsid & 0xffff0000u; + TU_ASSERT(gsnpsid == DWC2_OTG_ID || gsnpsid == DWC2_FS_IOT_ID || gsnpsid == DWC2_HS_IOT_ID, ); print_dwc2_info(dwc2); @@ -412,7 +413,7 @@ void dcd_init (uint8_t rhport) // On selected MCUs HS port1 can be used with external PHY via ULPI interface #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED // deactivate internal PHY - dwc2->stm32_gccfg &= ~GCCFG_PWRDWN; + dwc2->stm32_gccfg &= ~STM32_GCCFG_PWRDWN; // Init The UTMI Interface dwc2->gusbcfg &= ~(GUSBCFG_TSDPS | GUSBCFG_ULPIFSLS | GUSBCFG_PHYSEL); @@ -428,7 +429,7 @@ void dcd_init (uint8_t rhport) // Select UTMI Interface dwc2->gusbcfg &= ~GUSBCFG_ULPI_UTMI_SEL; - dwc2->stm32_gccfg |= GCCFG_PHYHSEN; + dwc2->stm32_gccfg |= STM32_GCCFG_PHYHSEN; // Enables control of a High Speed USB PHY USB_HS_PHYCInit(); @@ -463,7 +464,7 @@ void dcd_init (uint8_t rhport) set_speed(rhport, TUD_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL); // Enable internal USB transceiver, unless using HS core (port 1) with external PHY. - if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) dwc2->stm32_gccfg |= GCCFG_PWRDWN; + if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) dwc2->stm32_gccfg |= STM32_GCCFG_PWRDWN; dwc2->gintmsk |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_USBSUSPM | GINTMSK_WUIM | GINTMSK_RXFLVLM; @@ -546,7 +547,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) xfer->max_size = tu_edpt_packet_size(desc_edpt); xfer->interval = desc_edpt->bInterval; - uint16_t const fifo_size = (xfer->max_size + 3) / 4; // Round up to next full word + uint16_t const fifo_size = tu_div_ceil(xfer->max_size, 4); if(dir == TUSB_DIR_OUT) { diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 58e628970..113f99180 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -1051,42 +1051,42 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define DEACHINT_OEP1INT DEACHINT_OEP1INT_Msk // OUT endpoint 1 interrupt bit */ /******************** Bit definition for GCCFG register ********************/ -#define GCCFG_DCDET_Pos (0U) -#define GCCFG_DCDET_Msk (0x1UL << GCCFG_DCDET_Pos) // 0x00000001 */ -#define GCCFG_DCDET GCCFG_DCDET_Msk // Data contact detection (DCD) status */ -#define GCCFG_PDET_Pos (1U) -#define GCCFG_PDET_Msk (0x1UL << GCCFG_PDET_Pos) // 0x00000002 */ -#define GCCFG_PDET GCCFG_PDET_Msk // Primary detection (PD) status */ -#define GCCFG_SDET_Pos (2U) -#define GCCFG_SDET_Msk (0x1UL << GCCFG_SDET_Pos) // 0x00000004 */ -#define GCCFG_SDET GCCFG_SDET_Msk // Secondary detection (SD) status */ -#define GCCFG_PS2DET_Pos (3U) -#define GCCFG_PS2DET_Msk (0x1UL << GCCFG_PS2DET_Pos) // 0x00000008 */ -#define GCCFG_PS2DET GCCFG_PS2DET_Msk // DM pull-up detection status */ -#define GCCFG_PWRDWN_Pos (16U) -#define GCCFG_PWRDWN_Msk (0x1UL << GCCFG_PWRDWN_Pos) // 0x00010000 */ -#define GCCFG_PWRDWN GCCFG_PWRDWN_Msk // Power down */ -#define GCCFG_BCDEN_Pos (17U) -#define GCCFG_BCDEN_Msk (0x1UL << GCCFG_BCDEN_Pos) // 0x00020000 */ -#define GCCFG_BCDEN GCCFG_BCDEN_Msk // Battery charging detector (BCD) enable */ -#define GCCFG_DCDEN_Pos (18U) -#define GCCFG_DCDEN_Msk (0x1UL << GCCFG_DCDEN_Pos) // 0x00040000 */ -#define GCCFG_DCDEN GCCFG_DCDEN_Msk // Data contact detection (DCD) mode enable*/ -#define GCCFG_PDEN_Pos (19U) -#define GCCFG_PDEN_Msk (0x1UL << GCCFG_PDEN_Pos) // 0x00080000 */ -#define GCCFG_PDEN GCCFG_PDEN_Msk // Primary detection (PD) mode enable*/ -#define GCCFG_SDEN_Pos (20U) -#define GCCFG_SDEN_Msk (0x1UL << GCCFG_SDEN_Pos) // 0x00100000 */ -#define GCCFG_SDEN GCCFG_SDEN_Msk // Secondary detection (SD) mode enable */ -#define GCCFG_VBDEN_Pos (21U) -#define GCCFG_VBDEN_Msk (0x1UL << GCCFG_VBDEN_Pos) // 0x00200000 */ -#define GCCFG_VBDEN GCCFG_VBDEN_Msk // VBUS mode enable */ -#define GCCFG_OTGIDEN_Pos (22U) -#define GCCFG_OTGIDEN_Msk (0x1UL << GCCFG_OTGIDEN_Pos) // 0x00400000 */ -#define GCCFG_OTGIDEN GCCFG_OTGIDEN_Msk // OTG Id enable */ -#define GCCFG_PHYHSEN_Pos (23U) -#define GCCFG_PHYHSEN_Msk (0x1UL << GCCFG_PHYHSEN_Pos) // 0x00800000 */ -#define GCCFG_PHYHSEN GCCFG_PHYHSEN_Msk // HS PHY enable */ +#define STM32_GCCFG_DCDET_Pos (0U) +#define STM32_GCCFG_DCDET_Msk (0x1UL << STM32_GCCFG_DCDET_Pos) // 0x00000001 */ +#define STM32_GCCFG_DCDET STM32_GCCFG_DCDET_Msk // Data contact detection (DCD) status */ +#define STM32_GCCFG_PDET_Pos (1U) +#define STM32_GCCFG_PDET_Msk (0x1UL << STM32_GCCFG_PDET_Pos) // 0x00000002 */ +#define STM32_GCCFG_PDET STM32_GCCFG_PDET_Msk // Primary detection (PD) status */ +#define STM32_GCCFG_SDET_Pos (2U) +#define STM32_GCCFG_SDET_Msk (0x1UL << STM32_GCCFG_SDET_Pos) // 0x00000004 */ +#define STM32_GCCFG_SDET STM32_GCCFG_SDET_Msk // Secondary detection (SD) status */ +#define STM32_GCCFG_PS2DET_Pos (3U) +#define STM32_GCCFG_PS2DET_Msk (0x1UL << STM32_GCCFG_PS2DET_Pos) // 0x00000008 */ +#define STM32_GCCFG_PS2DET STM32_GCCFG_PS2DET_Msk // DM pull-up detection status */ +#define STM32_GCCFG_PWRDWN_Pos (16U) +#define STM32_GCCFG_PWRDWN_Msk (0x1UL << STM32_GCCFG_PWRDWN_Pos) // 0x00010000 */ +#define STM32_GCCFG_PWRDWN STM32_GCCFG_PWRDWN_Msk // Power down */ +#define STM32_GCCFG_BCDEN_Pos (17U) +#define STM32_GCCFG_BCDEN_Msk (0x1UL << STM32_GCCFG_BCDEN_Pos) // 0x00020000 */ +#define STM32_GCCFG_BCDEN STM32_GCCFG_BCDEN_Msk // Battery charging detector (BCD) enable */ +#define STM32_GCCFG_DCDEN_Pos (18U) +#define STM32_GCCFG_DCDEN_Msk (0x1UL << STM32_GCCFG_DCDEN_Pos) // 0x00040000 */ +#define STM32_GCCFG_DCDEN STM32_GCCFG_DCDEN_Msk // Data contact detection (DCD) mode enable*/ +#define STM32_GCCFG_PDEN_Pos (19U) +#define STM32_GCCFG_PDEN_Msk (0x1UL << STM32_GCCFG_PDEN_Pos) // 0x00080000 */ +#define STM32_GCCFG_PDEN STM32_GCCFG_PDEN_Msk // Primary detection (PD) mode enable*/ +#define STM32_GCCFG_SDEN_Pos (20U) +#define STM32_GCCFG_SDEN_Msk (0x1UL << STM32_GCCFG_SDEN_Pos) // 0x00100000 */ +#define STM32_GCCFG_SDEN STM32_GCCFG_SDEN_Msk // Secondary detection (SD) mode enable */ +#define STM32_GCCFG_VBDEN_Pos (21U) +#define STM32_GCCFG_VBDEN_Msk (0x1UL << STM32_GCCFG_VBDEN_Pos) // 0x00200000 */ +#define STM32_GCCFG_VBDEN STM32_GCCFG_VBDEN_Msk // VBUS mode enable */ +#define STM32_GCCFG_OTGIDEN_Pos (22U) +#define STM32_GCCFG_OTGIDEN_Msk (0x1UL << STM32_GCCFG_OTGIDEN_Pos) // 0x00400000 */ +#define STM32_GCCFG_OTGIDEN STM32_GCCFG_OTGIDEN_Msk // OTG Id enable */ +#define STM32_GCCFG_PHYHSEN_Pos (23U) +#define STM32_GCCFG_PHYHSEN_Msk (0x1UL << STM32_GCCFG_PHYHSEN_Pos) // 0x00800000 */ +#define STM32_GCCFG_PHYHSEN STM32_GCCFG_PHYHSEN_Msk // HS PHY enable */ /******************** Bit definition for DEACHINTMSK register ********************/ #define DEACHINTMSK_IEP1INTM_Pos (1U) From 49aa69a301abfc86e1182d329c1f3b586cdcf204 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 Oct 2021 23:57:48 +0700 Subject: [PATCH 32/51] update bcm dcd --- src/device/dcd_attr.h | 2 +- src/portable/broadcom/synopsys/dcd_synopsys.c | 18 +++++++++--------- src/portable/st/synopsys/dcd_synopsys.c | 2 +- 3 files changed, 11 insertions(+), 11 deletions(-) diff --git a/src/device/dcd_attr.h b/src/device/dcd_attr.h index 61f31e38a..90f3a526a 100644 --- a/src/device/dcd_attr.h +++ b/src/device/dcd_attr.h @@ -181,7 +181,7 @@ #define DCD_ATTR_ENDPOINT_MAX 4 //------------- Broadcom -------------// -#elif TU_CHECK_MCU(BCM2711) +#elif TU_CHECK_MCU(OPT_MCU_BCM2711) #define DCD_ATTR_ENDPOINT_MAX 8 #else diff --git a/src/portable/broadcom/synopsys/dcd_synopsys.c b/src/portable/broadcom/synopsys/dcd_synopsys.c index 87150f683..041158871 100644 --- a/src/portable/broadcom/synopsys/dcd_synopsys.c +++ b/src/portable/broadcom/synopsys/dcd_synopsys.c @@ -37,9 +37,9 @@ // We disable SOF for now until needed later on #define USE_SOF 0 -#if TUSB_OPT_DEVICE_ENABLED && \ - ( (CFG_TUSB_MCU == OPT_MCU_BCM2711 ) \ - ) +#if TUSB_OPT_DEVICE_ENABLED && \ + (CFG_TUSB_MCU == OPT_MCU_BCM2711 ) \ + // EP_MAX : Max number of bi-directional endpoints including EP0 // EP_FIFO_SIZE : Size of dedicated USB SRAM @@ -656,10 +656,10 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) TU_ASSERT(epnum < EP_MAX); xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); - xfer->max_size = desc_edpt->wMaxPacketSize.size; + xfer->max_size = tu_edpt_packet_size(desc_edpt); xfer->interval = desc_edpt->bInterval; - uint16_t const fifo_size = (desc_edpt->wMaxPacketSize.size + 3) / 4; // Round up to next full word + uint16_t const fifo_size = (xfer->max_size + 3) / 4; // Round up to next full word if(dir == TUSB_DIR_OUT) { @@ -678,7 +678,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) out_ep[epnum].DOEPCTL |= (1 << USB_OTG_DOEPCTL_USBAEP_Pos) | (desc_edpt->bmAttributes.xfer << USB_OTG_DOEPCTL_EPTYP_Pos) | (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? USB_OTG_DOEPCTL_SD0PID_SEVNFRM : 0) | - (desc_edpt->wMaxPacketSize.size << USB_OTG_DOEPCTL_MPSIZ_Pos); + (xfer->max_size << USB_OTG_DOEPCTL_MPSIZ_Pos); dev->DAINTMSK |= (1 << (USB_OTG_DAINTMSK_OEPM_Pos + epnum)); } @@ -720,7 +720,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) (epnum << USB_OTG_DIEPCTL_TXFNUM_Pos) | (desc_edpt->bmAttributes.xfer << USB_OTG_DIEPCTL_EPTYP_Pos) | (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? USB_OTG_DIEPCTL_SD0PID_SEVNFRM : 0) | - (desc_edpt->wMaxPacketSize.size << USB_OTG_DIEPCTL_MPSIZ_Pos); + (xfer->max_size << USB_OTG_DIEPCTL_MPSIZ_Pos); dev->DAINTMSK |= (1 << (USB_OTG_DAINTMSK_IEPM_Pos + epnum)); } @@ -1010,7 +1010,7 @@ static void handle_rxflvl_ints(uint8_t rhport, USB_OTG_OUTEndpointTypeDef * out_ if (xfer->ff) { // Ring buffer - tu_fifo_write_n_const_addr_full_words(xfer->ff, (const void *) rx_fifo, bcnt); + tu_fifo_write_n_const_addr_full_words(xfer->ff, (const void *)(uintptr_t) rx_fifo, bcnt); } else { @@ -1130,7 +1130,7 @@ static void handle_epin_ints(uint8_t rhport, USB_OTG_DeviceTypeDef * dev, USB_OT if (xfer->ff) { usb_fifo_t tx_fifo = FIFO_BASE(rhport, n); - tu_fifo_read_n_const_addr_full_words(xfer->ff, (void *) tx_fifo, packet_size); + tu_fifo_read_n_const_addr_full_words(xfer->ff, (void *)(uintptr_t) tx_fifo, packet_size); } else { diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 4e2bbd076..4782ead8c 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -370,7 +370,7 @@ static bool USB_HS_PHYCInit(void) { USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef*) USB_HS_PHYC_CONTROLLER_BASE; - // Enable LDO + // Enable LDO: Note STM32F72/3xx Reference Manual rev 3 June 2018 incorrectly defined this bit as Disabled !! usb_hs_phyc->USB_HS_PHYC_LDO |= USB_HS_PHYC_LDO_ENABLE; // Wait until LDO ready From 7def38005853df94a61365c52cae27e8cba2cf81 Mon Sep 17 00:00:00 2001 From: hathach Date: Thu, 28 Oct 2021 12:52:18 +0700 Subject: [PATCH 33/51] support bcm2711 on pi4, enhance dcd init with utmi and ulpi hs phy --- hw/bsp/raspberrypi4/family.mk | 8 +- hw/bsp/stm32f7/boards/stm32f723disco/board.mk | 3 + hw/bsp/stm32f7/family.mk | 2 +- hw/bsp/stm32h7/family.mk | 2 +- src/portable/synopsys/dwc2/dcd_dwc2.c | 162 +++++++++--------- src/portable/synopsys/dwc2/dwc2_bcm.h | 72 ++++++++ src/portable/synopsys/dwc2/dwc2_stm32.h | 49 +++++- src/portable/synopsys/dwc2/dwc2_type.h | 46 +++-- 8 files changed, 242 insertions(+), 102 deletions(-) create mode 100644 src/portable/synopsys/dwc2/dwc2_bcm.h diff --git a/hw/bsp/raspberrypi4/family.mk b/hw/bsp/raspberrypi4/family.mk index 0424b2154..b0326c056 100644 --- a/hw/bsp/raspberrypi4/family.mk +++ b/hw/bsp/raspberrypi4/family.mk @@ -16,8 +16,11 @@ CFLAGS += \ -mgeneral-regs-only \ -DCFG_TUSB_MCU=OPT_MCU_BCM2711 +# mcu driver cause following warnings +CFLAGS += -Wno-error=cast-qual + SRC_C += \ - src/portable/broadcom/synopsys/dcd_synopsys.c \ + src/portable/synopsys/dwc2/dcd_dwc2.c \ $(MCU_DIR)/broadcom/gen/interrupt_handlers.c \ $(MCU_DIR)/broadcom/interrupts.c \ $(MCU_DIR)/broadcom/io.c \ @@ -39,3 +42,6 @@ SRC_S += $(MCU_DIR)/broadcom/boot.S $(BUILD)/kernel8.img: $(BUILD)/$(PROJECT).elf $(OBJCOPY) -O binary $^ $@ + +flash: $(BUILD)/kernel8.img + @$(CP) $< /home/$(USER)/Documents/code/pi4_tinyusb/boot_cpy diff --git a/hw/bsp/stm32f7/boards/stm32f723disco/board.mk b/hw/bsp/stm32f7/boards/stm32f723disco/board.mk index 8f05199d0..66d9ff8fb 100644 --- a/hw/bsp/stm32f7/boards/stm32f723disco/board.mk +++ b/hw/bsp/stm32f7/boards/stm32f723disco/board.mk @@ -10,3 +10,6 @@ SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f723xx.s # flash target using on-board stlink flash: flash-stlink + +# For flash-jlink target +JLINK_DEVICE = stm32f723ie diff --git a/hw/bsp/stm32f7/family.mk b/hw/bsp/stm32f7/family.mk index ead0c977a..8482e6dd2 100644 --- a/hw/bsp/stm32f7/family.mk +++ b/hw/bsp/stm32f7/family.mk @@ -34,7 +34,7 @@ endif CFLAGS += -Wno-error=shadow -Wno-error=cast-align SRC_C += \ - src/portable/st/synopsys/dcd_synopsys.c \ + src/portable/synopsys/dwc2/dcd_dwc2.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 \ diff --git a/hw/bsp/stm32h7/family.mk b/hw/bsp/stm32h7/family.mk index e35e75610..6a257e22d 100644 --- a/hw/bsp/stm32h7/family.mk +++ b/hw/bsp/stm32h7/family.mk @@ -30,7 +30,7 @@ CFLAGS += -Wno-error=maybe-uninitialized -Wno-error=cast-align # All source paths should be relative to the top level. SRC_C += \ - src/portable/st/synopsys/dcd_synopsys.c \ + src/portable/synopsys/dwc2/dcd_dwc2.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 \ diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 58305838f..0d2766c38 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -31,7 +31,7 @@ #include "device/dcd_attr.h" #if TUSB_OPT_DEVICE_ENABLED && \ - ( defined(DCD_ATTR_DWC2_STM32) || TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3, OPT_MCU_GD32VF103) ) + ( defined(DCD_ATTR_DWC2_STM32) || TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3, OPT_MCU_GD32VF103, OPT_MCU_BCM2711) ) #include "device/dcd.h" #include "dwc2_type.h" @@ -42,6 +42,8 @@ #include "dwc2_esp32.h" #elif TU_CHECK_MCU(OPT_MCU_GD32VF103) #include "dwc2_gd32.h" +#elif TU_CHECK_MCU(OPT_MCU_BCM2711) + #include "dwc2_bcm.h" #else #error "Unsupported MCUs" #endif @@ -185,7 +187,7 @@ static void bus_reset(uint8_t rhport) _allocated_fifo_words_tx = 16; // Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) - dwc2->dieptxf0 = (16 << TX0FD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); + dwc2->dieptxf0 = (16 << DIEPTXF0_TX0FD_Pos) | (DWC2_EP_FIFO_SIZE/4 - _allocated_fifo_words_tx); // Fixed control EP0 size to 64 bytes dwc2->epin[0].diepctl &= ~(0x03 << DIEPCTL_MPSIZ_Pos); @@ -226,47 +228,6 @@ static void set_speed(uint8_t rhport, tusb_speed_t speed) dwc2->dcfg |= (bitvalue << DCFG_DSPD_Pos); } -#if defined(USB_HS_PHYC) -static bool USB_HS_PHYCInit(void) -{ - USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef*) USB_HS_PHYC_CONTROLLER_BASE; - - // Enable LDO - usb_hs_phyc->USB_HS_PHYC_LDO |= USB_HS_PHYC_LDO_ENABLE; - - // Wait until LDO ready - while ( 0 == (usb_hs_phyc->USB_HS_PHYC_LDO & USB_HS_PHYC_LDO_STATUS) ) {} - - uint32_t phyc_pll = 0; - - // TODO Try to get HSE_VALUE from registers instead of depending CFLAGS - switch ( HSE_VALUE ) - { - case 12000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12MHZ ; break; - case 12500000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12_5MHZ ; break; - case 16000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_16MHZ ; break; - case 24000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_24MHZ ; break; - case 25000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_25MHZ ; break; - case 32000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_Msk ; break; // Value not defined in header - default: - TU_ASSERT(0); - } - usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll; - - // Control the tuning interface of the High Speed PHY - // Use magic value (USB_HS_PHYC_TUNE_VALUE) from ST driver - usb_hs_phyc->USB_HS_PHYC_TUNE |= 0x00000F13U; - - // Enable PLL internal PHY - usb_hs_phyc->USB_HS_PHYC_PLL |= USB_HS_PHYC_PLL_PLLEN; - - // Original ST code has 2 ms delay for PLL stabilization. - // Primitive test shows that more than 10 USB un/replug cycle showed no error with enumeration - - return true; -} -#endif - static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t const dir, uint16_t const num_packets, uint16_t total_bytes) { (void) rhport; @@ -369,7 +330,7 @@ void print_dwc2_info(dwc2_regs_t * dwc2) TU_LOG_INT(1, hw_cfg3->synch_reset ); TU_LOG_INT(1, hw_cfg3->otg_adp_support ); TU_LOG_INT(1, hw_cfg3->otg_enable_hsic ); - TU_LOG_INT(1, hw_cfg3->otg_bc_support ); + TU_LOG_INT(1, hw_cfg3->battery_charger_support ); TU_LOG_INT(1, hw_cfg3->lpm_mode ); TU_LOG_INT(1, hw_cfg3->total_fifo_size ); @@ -395,57 +356,103 @@ void print_dwc2_info(dwc2_regs_t * dwc2) TU_LOG_INT(1, hw_cfg4->dma_dynamic ); } +static void reset_core(dwc2_regs_t * dwc2) +{ + // reset core + dwc2->grstctl |= GRSTCTL_CSRST; + + // wait for reset bit is cleared + // TODO version 4.20a should wait for RESET DONE mask + while (dwc2->grstctl & GRSTCTL_CSRST) { } + + // wait for AHB master IDLE + while ( !(dwc2->grstctl & GRSTCTL_AHBIDL) ) { } + + // wait for device mode ? +} + void dcd_init (uint8_t rhport) { // Programming model begins in the last section of the chapter on the USB // peripheral in each Reference Manual. dwc2_regs_t * dwc2 = DWC2_REG(rhport); - // Check Synopsys ID - uint32_t const gsnpsid = dwc2->gsnpsid & 0xffff0000u; + // Check Synopsys ID, failed if controller is not enabled + uint32_t const gsnpsid = dwc2->gsnpsid & GSNPSID_ID_MASK; TU_ASSERT(gsnpsid == DWC2_OTG_ID || gsnpsid == DWC2_FS_IOT_ID || gsnpsid == DWC2_HS_IOT_ID, ); print_dwc2_info(dwc2); - // No HNP/SRP (no OTG support), program timeout later. - if ( rhport == 1 ) + // Force device mode + dwc2->gusbcfg = (dwc2->gusbcfg & ~GUSBCFG_FHMOD) | GUSBCFG_FDMOD; + + uint32_t const hs_phy_type = dwc2->ghwcfg2_bm.hs_phy_type; + + if( !TUD_OPT_HIGH_SPEED || hs_phy_type == HS_PHY_TYPE_NONE) { - // On selected MCUs HS port1 can be used with external PHY via ULPI interface -#if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED - // deactivate internal PHY + // max speed is full or core does not support highspeed + TU_LOG2("Fullspeed PHY init\r\n"); + + // Select FS PHY + dwc2->gusbcfg |= GUSBCFG_PHYSEL; + + // Reset core after selecting PHY + reset_core(dwc2); + + #if defined(DCD_ATTR_DWC2_STM32) + // activate FS PHY on stm32 + dwc2->stm32_gccfg |= STM32_GCCFG_PWRDWN; + #endif + }else + { + // Highspeed mode + + #if defined(DCD_ATTR_DWC2_STM32) + // Disable STM32 FS PHY dwc2->stm32_gccfg &= ~STM32_GCCFG_PWRDWN; + #endif - // Init The UTMI Interface - dwc2->gusbcfg &= ~(GUSBCFG_TSDPS | GUSBCFG_ULPIFSLS | GUSBCFG_PHYSEL); + uint32_t gusbcfg = dwc2->gusbcfg; - // Select default internal VBUS Indicator and Drive for ULPI - dwc2->gusbcfg &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI); -#else - dwc2->gusbcfg |= GUSBCFG_PHYSEL; -#endif + // De-select FS PHY + gusbcfg &= ~GUSBCFG_PHYSEL; -#if defined(USB_HS_PHYC) - // Highspeed with embedded UTMI PHYC + if (hs_phy_type == HS_PHY_TYPE_ULPI) + { + TU_LOG2("Highspeed ULPI PHY init\r\n"); - // Select UTMI Interface - dwc2->gusbcfg &= ~GUSBCFG_ULPI_UTMI_SEL; - dwc2->stm32_gccfg |= STM32_GCCFG_PHYHSEN; + // Select ULPI + gusbcfg |= GUSBCFG_ULPI_UTMI_SEL; - // Enables control of a High Speed USB PHY - USB_HS_PHYCInit(); -#endif - } else - { - // Enable internal PHY - dwc2->gusbcfg |= GUSBCFG_PHYSEL; + // ULPI 8-bit interface, single data rate + gusbcfg &= ~(GUSBCFG_PHYIF16 | GUSBCFG_DDRSEL); + + // default internal VBUS Indicator and Drive + gusbcfg &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI); + + // Disable FS/LS ULPI + gusbcfg &= ~(GUSBCFG_ULPIFSLS | GUSBCFG_ULPICSM); + }else + { + TU_LOG2("Highspeed UTMI+ PHY init\r\n"); + + // Select UTMI+ with 8-bit interface + gusbcfg &= ~(GUSBCFG_ULPI_UTMI_SEL | GUSBCFG_PHYIF16); + + // Set 16-bit interface if supported + if (dwc2->ghwcfg4_bm.utmi_phy_data_width) gusbcfg |= GUSBCFG_PHYIF16; + + #if defined(DCD_ATTR_DWC2_STM32) && defined(USB_HS_PHYC) + dwc2_stm32_utmi_phy_init(dwc2); + #endif + } + + dwc2->gusbcfg = gusbcfg; + + // Reset core after selecting PHY + reset_core(dwc2); } - // Reset core after selecting PHYst - // Wait AHB IDLE, reset then wait until it is cleared - while ((dwc2->grstctl & GRSTCTL_AHBIDL) == 0U) {} - dwc2->grstctl |= GRSTCTL_CSRST; - while ((dwc2->grstctl & GRSTCTL_CSRST) == GRSTCTL_CSRST) {} - // Restart PHY clock dwc2->pcgctrl = 0; @@ -463,9 +470,6 @@ void dcd_init (uint8_t rhport) set_speed(rhport, TUD_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL); - // Enable internal USB transceiver, unless using HS core (port 1) with external PHY. - if (!(rhport == 1 && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED))) dwc2->stm32_gccfg |= STM32_GCCFG_PWRDWN; - dwc2->gintmsk |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_USBSUSPM | GINTMSK_WUIM | GINTMSK_RXFLVLM; diff --git a/src/portable/synopsys/dwc2/dwc2_bcm.h b/src/portable/synopsys/dwc2/dwc2_bcm.h new file mode 100644 index 000000000..da1f23ae0 --- /dev/null +++ b/src/portable/synopsys/dwc2/dwc2_bcm.h @@ -0,0 +1,72 @@ +/* + * 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 _TUSB_DWC2_BCM_H_ +#define _TUSB_DWC2_BCM_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#include "broadcom/interrupts.h" + +#define DWC2_REG_BASE 0xFE980000UL +#define DWC2_EP_MAX 8 +#define DWC2_EP_FIFO_SIZE 4096 + +TU_ATTR_ALWAYS_INLINE +static inline void dwc2_dcd_int_enable(uint8_t rhport) +{ + (void) rhport; + BP_EnableIRQ(USB_IRQn); +} + +TU_ATTR_ALWAYS_INLINE +static inline void dwc2_dcd_int_disable (uint8_t rhport) +{ + (void) rhport; + BP_DisableIRQ(USB_IRQn); +} + +TU_ATTR_ALWAYS_INLINE +static inline void dwc2_remote_wakeup_delay(void) +{ + // try to delay for 1 ms + // TODO implement later +} + +static inline void dwc2_set_turnaround(dwc2_regs_t * core, tusb_speed_t speed) +{ + // TODO implement later + (void) core; + (void) speed; +} + +#ifdef __cplusplus + } +#endif + +#endif diff --git a/src/portable/synopsys/dwc2/dwc2_stm32.h b/src/portable/synopsys/dwc2/dwc2_stm32.h index 236936d66..b77cda2ca 100644 --- a/src/portable/synopsys/dwc2/dwc2_stm32.h +++ b/src/portable/synopsys/dwc2/dwc2_stm32.h @@ -113,14 +113,14 @@ static inline void dwc2_remote_wakeup_delay(void) } // Set turn-around timeout according to link speed -static inline void dwc2_set_turnaround(dwc2_regs_t * core, tusb_speed_t speed) +static inline void dwc2_set_turnaround(dwc2_regs_t * dwc2, tusb_speed_t speed) { - core->gusbcfg &= ~GUSBCFG_TRDT; + dwc2->gusbcfg &= ~GUSBCFG_TRDT; if ( speed == TUSB_SPEED_HIGH ) { // Use fixed 0x09 for Highspeed - core->gusbcfg |= (0x09 << GUSBCFG_TRDT_Pos); + dwc2->gusbcfg |= (0x09 << GUSBCFG_TRDT_Pos); } else { @@ -149,11 +149,52 @@ static inline void dwc2_set_turnaround(dwc2_regs_t * core, tusb_speed_t speed) turnaround = 0xFU; // Fullspeed depends on MCU clocks, but we will use 0x06 for 32+ Mhz - core->gusbcfg |= (turnaround << GUSBCFG_TRDT_Pos); + dwc2->gusbcfg |= (turnaround << GUSBCFG_TRDT_Pos); } } +#if defined(USB_HS_PHYC) +static inline void dwc2_stm32_utmi_phy_init(dwc2_regs_t * dwc2) +{ + USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef*) USB_HS_PHYC_CONTROLLER_BASE; + // Enable UTMI HS PHY + dwc2->stm32_gccfg |= STM32_GCCFG_PHYHSEN; + + // Enable LDO + usb_hs_phyc->USB_HS_PHYC_LDO |= USB_HS_PHYC_LDO_ENABLE; + + // Wait until LDO ready + while ( 0 == (usb_hs_phyc->USB_HS_PHYC_LDO & USB_HS_PHYC_LDO_STATUS) ) {} + + uint32_t phyc_pll = 0; + + // TODO Try to get HSE_VALUE from registers instead of depending CFLAGS + switch ( HSE_VALUE ) + { + case 12000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12MHZ ; break; + case 12500000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12_5MHZ ; break; + case 16000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_16MHZ ; break; + case 24000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_24MHZ ; break; + case 25000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_25MHZ ; break; + case 32000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_Msk ; break; // Value not defined in header + default: + TU_ASSERT(false, ); + } + usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll; + + // Control the tuning interface of the High Speed PHY + // Use magic value (USB_HS_PHYC_TUNE_VALUE) from ST driver + usb_hs_phyc->USB_HS_PHYC_TUNE |= 0x00000F13U; + + // Enable PLL internal PHY + usb_hs_phyc->USB_HS_PHYC_PLL |= USB_HS_PHYC_PLL_PLLEN; + + // Original ST code has 2 ms delay for PLL stabilization. + // Primitive test shows that more than 10 USB un/replug cycle showed no error with enumeration +} + +#endif #ifdef __cplusplus } diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 113f99180..5ded366d7 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -58,6 +58,13 @@ typedef struct } HS_PHYC_GlobalTypeDef; #endif +enum { + HS_PHY_TYPE_NONE = 0 , + HS_PHY_TYPE_UTMI , // internal PHY (mostly) + HS_PHY_TYPE_ULPI , // external PHY + HS_PHY_TYPE_UTMI_ULPI , +}; + typedef struct TU_ATTR_PACKED { uint32_t op_mode : 3; // 0: HNP and SRP | 1: SRP | 2: non-HNP, non-SRP @@ -90,7 +97,7 @@ typedef struct TU_ATTR_PACKED uint32_t synch_reset : 1; // 0: async reset | 1: synch reset uint32_t otg_adp_support : 1; // ADP logic is present along with HSOTG controller uint32_t otg_enable_hsic : 1; // 1: HSIC-capable with shared UTMI PHY interface | 0: non-HSIC - uint32_t otg_bc_support : 1; // support battery charger + uint32_t battery_charger_support : 1; // support battery charger uint32_t lpm_mode : 1; // LPC mode uint32_t total_fifo_size : 16; // DFIFO depth value in terms of 32-bit words }dwc2_ghwcfg3_t; @@ -494,6 +501,8 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define GAHBCFG_PTXFELVL_Msk (0x1UL << GAHBCFG_PTXFELVL_Pos) // 0x00000100 */ #define GAHBCFG_PTXFELVL GAHBCFG_PTXFELVL_Msk // Periodic TxFIFO empty level */ +#define GSNPSID_ID_MASK TU_GENMASK(31, 16) + /******************** Bit definition for GUSBCFG register ********************/ #define GUSBCFG_TOCAL_Pos (0U) #define GUSBCFG_TOCAL_Msk (0x7UL << GUSBCFG_TOCAL_Pos) // 0x00000007 */ @@ -501,15 +510,16 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define GUSBCFG_TOCAL_0 (0x1UL << GUSBCFG_TOCAL_Pos) // 0x00000001 */ #define GUSBCFG_TOCAL_1 (0x2UL << GUSBCFG_TOCAL_Pos) // 0x00000002 */ #define GUSBCFG_TOCAL_2 (0x4UL << GUSBCFG_TOCAL_Pos) // 0x00000004 */ -#define GUSBCFG_PHYIF_Pos (3U) -#define GUSBCFG_PHYIF_Msk (0x1UL << GUSBCFG_PHYIF_Pos) // 0x00000008 */ -#define GUSBCFG_PHYIF GUSBCFG_PHYIF_Msk // PHY Interface (PHYIf) */ +#define GUSBCFG_PHYIF16_Pos (3U) +#define GUSBCFG_PHYIF16_Msk (0x1UL << GUSBCFG_PHYIF16_Pos) // 0x00000008 */ +#define GUSBCFG_PHYIF16 GUSBCFG_PHYIF16_Msk // PHY Interface (PHYIf) */ #define GUSBCFG_ULPI_UTMI_SEL_Pos (4U) #define GUSBCFG_ULPI_UTMI_SEL_Msk (0x1UL << GUSBCFG_ULPI_UTMI_SEL_Pos) // 0x00000010 */ #define GUSBCFG_ULPI_UTMI_SEL GUSBCFG_ULPI_UTMI_SEL_Msk // ULPI or UTMI+ Select (ULPI_UTMI_Sel) */ #define GUSBCFG_PHYSEL_Pos (6U) #define GUSBCFG_PHYSEL_Msk (0x1UL << GUSBCFG_PHYSEL_Pos) // 0x00000040 */ #define GUSBCFG_PHYSEL GUSBCFG_PHYSEL_Msk // USB 2.0 high-speed ULPI PHY or USB 1.1 full-speed serial transceiver select */ +#define GUSBCFG_DDRSEL TU_BIT(7) // Single Data Rate (SDR) or Double Data Rate (DDR) or ULPI interface. #define GUSBCFG_SRPCAP_Pos (8U) #define GUSBCFG_SRPCAP_Msk (0x1UL << GUSBCFG_SRPCAP_Pos) // 0x00000100 */ #define GUSBCFG_SRPCAP GUSBCFG_SRPCAP_Msk // SRP-capable */ @@ -587,6 +597,8 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define GRSTCTL_TXFNUM_2 (0x04UL << GRSTCTL_TXFNUM_Pos) // 0x00000100 */ #define GRSTCTL_TXFNUM_3 (0x08UL << GRSTCTL_TXFNUM_Pos) // 0x00000200 */ #define GRSTCTL_TXFNUM_4 (0x10UL << GRSTCTL_TXFNUM_Pos) // 0x00000400 */ +#define GRSTCTL_CSFTRST_DONE_Pos (29) +#define GRSTCTL_CSFTRST_DONE (1u << GRSTCTL_CSFTRST_DONE_Pos) // Reset Done, only available from v4.20a #define GRSTCTL_DMAREQ_Pos (30U) #define GRSTCTL_DMAREQ_Msk (0x1UL << GRSTCTL_DMAREQ_Pos) // 0x40000000 */ #define GRSTCTL_DMAREQ GRSTCTL_DMAREQ_Msk // DMA request signal */ @@ -898,6 +910,7 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define DAINTMSK_OEPM_Msk (0xFFFFUL << DAINTMSK_OEPM_Pos) // 0xFFFF0000 */ #define DAINTMSK_OEPM DAINTMSK_OEPM_Msk // OUT EP interrupt mask bits */ +#if 0 /******************** Bit definition for OTG register ********************/ #define CHNUM_Pos (0U) #define CHNUM_Msk (0xFUL << CHNUM_Pos) // 0x0000000F */ @@ -939,6 +952,7 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define FRMNUM_1 (0x2UL << FRMNUM_Pos) // 0x00400000 */ #define FRMNUM_2 (0x4UL << FRMNUM_Pos) // 0x00800000 */ #define FRMNUM_3 (0x8UL << FRMNUM_Pos) // 0x01000000 */ +#endif /******************** Bit definition for GRXFSIZ register ********************/ #define GRXFSIZ_RXFD_Pos (0U) @@ -951,18 +965,18 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define DVBUSDIS_VBUSDT DVBUSDIS_VBUSDT_Msk // Device VBUS discharge time */ /******************** Bit definition for OTG register ********************/ -#define NPTXFSA_Pos (0U) -#define NPTXFSA_Msk (0xFFFFUL << NPTXFSA_Pos) // 0x0000FFFF */ -#define NPTXFSA NPTXFSA_Msk // Nonperiodic transmit RAM start address */ -#define NPTXFD_Pos (16U) -#define NPTXFD_Msk (0xFFFFUL << NPTXFD_Pos) // 0xFFFF0000 */ -#define NPTXFD NPTXFD_Msk // Nonperiodic TxFIFO depth */ -#define TX0FSA_Pos (0U) -#define TX0FSA_Msk (0xFFFFUL << TX0FSA_Pos) // 0x0000FFFF */ -#define TX0FSA TX0FSA_Msk // Endpoint 0 transmit RAM start address */ -#define TX0FD_Pos (16U) -#define TX0FD_Msk (0xFFFFUL << TX0FD_Pos) // 0xFFFF0000 */ -#define TX0FD TX0FD_Msk // Endpoint 0 TxFIFO depth */ +#define GNPTXFSIZ_NPTXFSA_Pos (0U) +#define GNPTXFSIZ_NPTXFSA_Msk (0xFFFFUL << NPTXFSA_Pos) // 0x0000FFFF */ +#define GNPTXFSIZ_NPTXFSA GNPTXFSIZ_NPTXFSA_Msk // Nonperiodic transmit RAM start address */ +#define GNPTXFSIZ_NPTXFD_Pos (16U) +#define GNPTXFSIZ_NPTXFD_Msk (0xFFFFUL << NPTXFD_Pos) // 0xFFFF0000 */ +#define GNPTXFSIZ_NPTXFD GNPTXFSIZ_NPTXFD_Msk // Nonperiodic TxFIFO depth */ +#define DIEPTXF0_TX0FSA_Pos (0U) +#define DIEPTXF0_TX0FSA_Msk (0xFFFFUL << TX0FSA_Pos) // 0x0000FFFF */ +#define DIEPTXF0_TX0FSA DIEPTXF0_TX0FSA_Msk // Endpoint 0 transmit RAM start address */ +#define DIEPTXF0_TX0FD_Pos (16U) +#define DIEPTXF0_TX0FD_Msk (0xFFFFUL << TX0FD_Pos) // 0xFFFF0000 */ +#define DIEPTXF0_TX0FD DIEPTXF0_TX0FD_Msk // Endpoint 0 TxFIFO depth */ /******************** Bit definition for DVBUSPULSE register ********************/ #define DVBUSPULSE_DVBUSP_Pos (0U) From 6c67fc412516950622a13fb34ddc10b64b9b3843 Mon Sep 17 00:00:00 2001 From: hathach Date: Fri, 29 Oct 2021 00:53:30 +0700 Subject: [PATCH 34/51] correctly init hs phy for bcm --- examples/device/cdc_msc/src/tusb_config.h | 5 +- .../device/hid_composite/src/tusb_config.h | 4 +- src/common/tusb_types.h | 4 +- src/portable/synopsys/dwc2/dcd_dwc2.c | 221 ++++++++++-------- src/portable/synopsys/dwc2/dwc2_type.h | 164 ++++++------- 5 files changed, 208 insertions(+), 190 deletions(-) diff --git a/examples/device/cdc_msc/src/tusb_config.h b/examples/device/cdc_msc/src/tusb_config.h index a3802f536..499966cb4 100644 --- a/examples/device/cdc_msc/src/tusb_config.h +++ b/examples/device/cdc_msc/src/tusb_config.h @@ -47,9 +47,8 @@ // RHPort max operational speed can defined by board.mk // Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed #ifndef BOARD_DEVICE_RHPORT_SPEED - #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 || CFG_TUSB_MCU == OPT_MCU_SAMX7X || \ - CFG_TUSB_MCU == OPT_MCU_BCM2711) + #if TU_CHECK_MCU(OPT_MCU_LPC18XX, OPT_MCU_LPC43XX, OPT_MCU_MIMXRT10XX, OPT_MCU_NUC505) ||\ + TU_CHECK_MCU(OPT_MCU_CXD56, OPT_MCU_SAMX7X, OPT_MCU_BCM2711) #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED #else #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED diff --git a/examples/device/hid_composite/src/tusb_config.h b/examples/device/hid_composite/src/tusb_config.h index 868424e6d..8fa5e5cd4 100644 --- a/examples/device/hid_composite/src/tusb_config.h +++ b/examples/device/hid_composite/src/tusb_config.h @@ -47,8 +47,8 @@ // RHPort max operational speed can defined by board.mk // Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed #ifndef BOARD_DEVICE_RHPORT_SPEED - #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 || CFG_TUSB_MCU == OPT_MCU_SAMX7X) + #if TU_CHECK_MCU(OPT_MCU_LPC18XX, OPT_MCU_LPC43XX, OPT_MCU_MIMXRT10XX, OPT_MCU_NUC505) ||\ + TU_CHECK_MCU(OPT_MCU_CXD56, OPT_MCU_SAMX7X, OPT_MCU_BCM2711) #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED #else #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED diff --git a/src/common/tusb_types.h b/src/common/tusb_types.h index 233def466..5b26f5aec 100644 --- a/src/common/tusb_types.h +++ b/src/common/tusb_types.h @@ -47,8 +47,8 @@ typedef enum { TUSB_SPEED_FULL = 0, - TUSB_SPEED_LOW , - TUSB_SPEED_HIGH, + TUSB_SPEED_LOW = 1, + TUSB_SPEED_HIGH = 2, TUSB_SPEED_INVALID = 0xff, }tusb_speed_t; diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 0d2766c38..ce9b58e03 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -199,35 +199,6 @@ static void bus_reset(uint8_t rhport) dwc2->gintmsk |= GINTMSK_OEPINT | GINTMSK_IEPINT; } - -static tusb_speed_t get_speed(uint8_t rhport) -{ - (void) rhport; - dwc2_regs_t * dwc2 = DWC2_REG(rhport); - uint32_t const enum_spd = (dwc2->dsts & DSTS_ENUMSPD_Msk) >> DSTS_ENUMSPD_Pos; - return (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL; -} - -static void set_speed(uint8_t rhport, tusb_speed_t speed) -{ - uint32_t bitvalue; - - if ( rhport == 1 ) - { - bitvalue = (TUSB_SPEED_HIGH == speed ? DCD_HIGH_SPEED : DCD_FULL_SPEED_USE_HS); - } - else - { - bitvalue = DCD_FULL_SPEED; - } - - dwc2_regs_t * dwc2 = DWC2_REG(rhport); - - // Clear and set speed bits - dwc2->dcfg &= ~(3 << DCFG_DSPD_Pos); - dwc2->dcfg |= (bitvalue << DCFG_DSPD_Pos); -} - static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t const dir, uint16_t const num_packets, uint16_t total_bytes) { (void) rhport; @@ -371,6 +342,99 @@ static void reset_core(dwc2_regs_t * dwc2) // wait for device mode ? } +static bool has_hs_phy(dwc2_regs_t * dwc2) +{ + return TUD_OPT_HIGH_SPEED && dwc2->ghwcfg2_bm.hs_phy_type != HS_PHY_TYPE_NONE; +} + +static void phy_fs_init(dwc2_regs_t * dwc2) +{ + TU_LOG1("Fullspeed PHY init\r\n"); + + // Select FS PHY + dwc2->gusbcfg |= GUSBCFG_PHYSEL; + + // Reset core after selecting PHY + reset_core(dwc2); + + // set turn around + // The values above are calculated for the minimum AHB frequency of 30 MHz. USB turnaround + // time is critical for certification where long cables and 5-Hubs are used, so if + // you need the AHB to run at less than 30 MHz, and if USB turnaround time is not critical, + // these bits can be programmed to a larger value. + dwc2_set_turnaround(dwc2, TUSB_SPEED_FULL); + + // set max speed + dwc2->dcfg = (dwc2->dcfg & ~DCFG_DSPD_Msk) | (DCFG_DSPD_FS << DCFG_DSPD_Pos); + + #if defined(DCD_ATTR_DWC2_STM32) + // activate FS PHY on stm32 + dwc2->stm32_gccfg |= STM32_GCCFG_PWRDWN; + #endif +} + +static void phy_hs_init(dwc2_regs_t * dwc2) +{ + uint32_t gusbcfg = dwc2->gusbcfg; + + // De-select FS PHY + gusbcfg &= ~GUSBCFG_PHYSEL; + + if (dwc2->ghwcfg2_bm.hs_phy_type == HS_PHY_TYPE_ULPI) + { + TU_LOG1("Highspeed ULPI PHY init\r\n"); + + // Select ULPI + gusbcfg |= GUSBCFG_ULPI_UTMI_SEL; + + // ULPI 8-bit interface, single data rate + gusbcfg &= ~(GUSBCFG_PHYIF16 | GUSBCFG_DDRSEL); + + // default internal VBUS Indicator and Drive + gusbcfg &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI); + + // Disable FS/LS ULPI + gusbcfg &= ~(GUSBCFG_ULPIFSLS | GUSBCFG_ULPICSM); + }else + { + TU_LOG1("Highspeed UTMI+ PHY init\r\n"); + + // Select UTMI+ with 8-bit interface + gusbcfg &= ~(GUSBCFG_ULPI_UTMI_SEL | GUSBCFG_PHYIF16); + + // Set 16-bit interface if supported + if (dwc2->ghwcfg4_bm.utmi_phy_data_width) gusbcfg |= GUSBCFG_PHYIF16; + + #if defined(DCD_ATTR_DWC2_STM32) && defined(USB_HS_PHYC) + dwc2_stm32_utmi_phy_init(dwc2); + #endif + } + + // Apply config + dwc2->gusbcfg = gusbcfg; + + #if defined(DCD_ATTR_DWC2_STM32) + // Disable STM32 FS PHY + dwc2->stm32_gccfg &= ~STM32_GCCFG_PWRDWN; + #endif + + // Reset core after selecting PHY + reset_core(dwc2); + + // Set turn-around, must after core reset otherwise it will be clear + // 9 if UTMI interface is 8-bit, 5 if 16-bit + // The values above are calculated for the minimum AHB frequency of 30 MHz. USB turnaround + // time is critical for certification where long cables and 5-Hubs are used, so if + // you need the AHB to run at less than 30 MHz, and if USB turnaround time is not critical, + // these bits can be programmed to a larger value. + gusbcfg &= ~GUSBCFG_TRDT_Msk; + gusbcfg |= (dwc2->ghwcfg4_bm.utmi_phy_data_width ? 5u : 9u) << GUSBCFG_TRDT_Pos; + dwc2->gusbcfg = gusbcfg; // Apply config + + // Set max speed + dwc2->dcfg = (dwc2->dcfg & ~DCFG_DSPD_Msk) | (DCFG_DSPD_HS << DCFG_DSPD_Pos); +} + void dcd_init (uint8_t rhport) { // Programming model begins in the last section of the chapter on the USB @@ -386,75 +450,28 @@ void dcd_init (uint8_t rhport) // Force device mode dwc2->gusbcfg = (dwc2->gusbcfg & ~GUSBCFG_FHMOD) | GUSBCFG_FDMOD; - uint32_t const hs_phy_type = dwc2->ghwcfg2_bm.hs_phy_type; - - if( !TUD_OPT_HIGH_SPEED || hs_phy_type == HS_PHY_TYPE_NONE) + if( !has_hs_phy(dwc2) ) { - // max speed is full or core does not support highspeed - TU_LOG2("Fullspeed PHY init\r\n"); - - // Select FS PHY - dwc2->gusbcfg |= GUSBCFG_PHYSEL; - - // Reset core after selecting PHY - reset_core(dwc2); - - #if defined(DCD_ATTR_DWC2_STM32) - // activate FS PHY on stm32 - dwc2->stm32_gccfg |= STM32_GCCFG_PWRDWN; - #endif + // core does not support highspeed or hs-phy is not present + phy_fs_init(dwc2); }else { - // Highspeed mode - - #if defined(DCD_ATTR_DWC2_STM32) - // Disable STM32 FS PHY - dwc2->stm32_gccfg &= ~STM32_GCCFG_PWRDWN; - #endif - - uint32_t gusbcfg = dwc2->gusbcfg; - - // De-select FS PHY - gusbcfg &= ~GUSBCFG_PHYSEL; - - if (hs_phy_type == HS_PHY_TYPE_ULPI) - { - TU_LOG2("Highspeed ULPI PHY init\r\n"); - - // Select ULPI - gusbcfg |= GUSBCFG_ULPI_UTMI_SEL; - - // ULPI 8-bit interface, single data rate - gusbcfg &= ~(GUSBCFG_PHYIF16 | GUSBCFG_DDRSEL); - - // default internal VBUS Indicator and Drive - gusbcfg &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI); - - // Disable FS/LS ULPI - gusbcfg &= ~(GUSBCFG_ULPIFSLS | GUSBCFG_ULPICSM); - }else - { - TU_LOG2("Highspeed UTMI+ PHY init\r\n"); - - // Select UTMI+ with 8-bit interface - gusbcfg &= ~(GUSBCFG_ULPI_UTMI_SEL | GUSBCFG_PHYIF16); - - // Set 16-bit interface if supported - if (dwc2->ghwcfg4_bm.utmi_phy_data_width) gusbcfg |= GUSBCFG_PHYIF16; - - #if defined(DCD_ATTR_DWC2_STM32) && defined(USB_HS_PHYC) - dwc2_stm32_utmi_phy_init(dwc2); - #endif - } - - dwc2->gusbcfg = gusbcfg; - - // Reset core after selecting PHY - reset_core(dwc2); + // Highspeed + phy_hs_init(dwc2); } + /* Set HS/FS Timeout Calibration to 7 (max available value). + * The number of PHY clocks that the application programs in + * this field is added to the high/full speed interpacket timeout + * duration in the core to account for any additional delays + * introduced by the PHY. This can be required, because the delay + * introduced by the PHY in generating the linestate condition + * can vary from one PHY to another. + */ + // dwc2->gusbcfg |= (7ul << GUSBCFG_TOCAL_Pos); + // Restart PHY clock - dwc2->pcgctrl = 0; + dwc2->pcgctl &= ~(PCGCTL_STOPPCLK | PCGCTL_GATEHCLK | PCGCTL_PWRCLMP | PCGCTL_RSTPDWNMODULE); // Clear all interrupts dwc2->gintsts |= dwc2->gintsts; @@ -468,8 +485,6 @@ void dcd_init (uint8_t rhport) // (non zero-length packet), send STALL back and discard. dwc2->dcfg |= DCFG_NZLSOHSK; - set_speed(rhport, TUD_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL); - dwc2->gintmsk |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_USBSUSPM | GINTMSK_WUIM | GINTMSK_RXFLVLM; @@ -1088,9 +1103,23 @@ void dcd_int_handler(uint8_t rhport) dwc2->gintsts = GINTSTS_ENUMDNE; - tusb_speed_t const speed = get_speed(rhport); + tusb_speed_t speed; + switch ((dwc2->dsts & DSTS_ENUMSPD_Msk) >> DSTS_ENUMSPD_Pos) + { + case DSTS_ENUMSPD_HS: + speed = TUSB_SPEED_HIGH; + break; + + case DSTS_ENUMSPD_FS_HSPHY: + case DSTS_ENUMSPD_FS: + speed = TUSB_SPEED_FULL; + break; + + case DSTS_ENUMSPD_LS: + speed = TUSB_SPEED_LOW; + break; + } - dwc2_set_turnaround(dwc2, speed); dcd_event_bus_reset(rhport, speed, true); } diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 5ded366d7..7e472310f 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -259,8 +259,8 @@ union { uint32_t reservedd00[64]; // D00..DFF //------------- Power Clock -------------// - volatile uint32_t pcgctrl; // E00 Power and Clock Gating Control - volatile uint32_t pcgcctl1; // E04 + volatile uint32_t pcgctl; // E00 Power and Clock Gating Control + volatile uint32_t pcgctl1; // E04 uint32_t reservede08[126]; // E08..FFF //------------- FIFOs -------------// @@ -273,7 +273,7 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, channel) == 0x0500, "incorrect size"); TU_VERIFY_STATIC(offsetof(dwc2_regs_t, dcfg ) == 0x0800, "incorrect size"); TU_VERIFY_STATIC(offsetof(dwc2_regs_t, epin ) == 0x0900, "incorrect size"); TU_VERIFY_STATIC(offsetof(dwc2_regs_t, epout ) == 0x0B00, "incorrect size"); -TU_VERIFY_STATIC(offsetof(dwc2_regs_t, pcgctrl) == 0x0E00, "incorrect size"); +TU_VERIFY_STATIC(offsetof(dwc2_regs_t, pcgctl ) == 0x0E00, "incorrect size"); TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); //--------------------------------------------------------------------+ @@ -346,39 +346,6 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define HCFG_FSLSS_Msk (0x1UL << HCFG_FSLSS_Pos) // 0x00000004 */ #define HCFG_FSLSS HCFG_FSLSS_Msk // FS- and LS-only support */ -/******************** Bit definition for DCFG register ********************/ -#define DCFG_DSPD_Pos (0U) -#define DCFG_DSPD_Msk (0x3UL << DCFG_DSPD_Pos) // 0x00000003 */ -#define DCFG_DSPD DCFG_DSPD_Msk // Device speed */ -#define DCFG_DSPD_0 (0x1UL << DCFG_DSPD_Pos) // 0x00000001 */ -#define DCFG_DSPD_1 (0x2UL << DCFG_DSPD_Pos) // 0x00000002 */ -#define DCFG_NZLSOHSK_Pos (2U) -#define DCFG_NZLSOHSK_Msk (0x1UL << DCFG_NZLSOHSK_Pos) // 0x00000004 */ -#define DCFG_NZLSOHSK DCFG_NZLSOHSK_Msk // Nonzero-length status OUT handshake */ - -#define DCFG_DAD_Pos (4U) -#define DCFG_DAD_Msk (0x7FUL << DCFG_DAD_Pos) // 0x000007F0 */ -#define DCFG_DAD DCFG_DAD_Msk // Device address */ -#define DCFG_DAD_0 (0x01UL << DCFG_DAD_Pos) // 0x00000010 */ -#define DCFG_DAD_1 (0x02UL << DCFG_DAD_Pos) // 0x00000020 */ -#define DCFG_DAD_2 (0x04UL << DCFG_DAD_Pos) // 0x00000040 */ -#define DCFG_DAD_3 (0x08UL << DCFG_DAD_Pos) // 0x00000080 */ -#define DCFG_DAD_4 (0x10UL << DCFG_DAD_Pos) // 0x00000100 */ -#define DCFG_DAD_5 (0x20UL << DCFG_DAD_Pos) // 0x00000200 */ -#define DCFG_DAD_6 (0x40UL << DCFG_DAD_Pos) // 0x00000400 */ - -#define DCFG_PFIVL_Pos (11U) -#define DCFG_PFIVL_Msk (0x3UL << DCFG_PFIVL_Pos) // 0x00001800 */ -#define DCFG_PFIVL DCFG_PFIVL_Msk // Periodic (micro)frame interval */ -#define DCFG_PFIVL_0 (0x1UL << DCFG_PFIVL_Pos) // 0x00000800 */ -#define DCFG_PFIVL_1 (0x2UL << DCFG_PFIVL_Pos) // 0x00001000 */ - -#define DCFG_PERSCHIVL_Pos (24U) -#define DCFG_PERSCHIVL_Msk (0x3UL << DCFG_PERSCHIVL_Pos) // 0x03000000 */ -#define DCFG_PERSCHIVL DCFG_PERSCHIVL_Msk // Periodic scheduling interval */ -#define DCFG_PERSCHIVL_0 (0x1UL << DCFG_PERSCHIVL_Pos) // 0x01000000 */ -#define DCFG_PERSCHIVL_1 (0x2UL << DCFG_PERSCHIVL_Pos) // 0x02000000 */ - /******************** Bit definition for PCGCR register ********************/ #define PCGCR_STPPCLK_Pos (0U) #define PCGCR_STPPCLK_Msk (0x1UL << PCGCR_STPPCLK_Pos) // 0x00000001 */ @@ -413,6 +380,41 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define GOTGINT_IDCHNG_Msk (0x1UL << GOTGINT_IDCHNG_Pos) // 0x00100000 */ #define GOTGINT_IDCHNG GOTGINT_IDCHNG_Msk // Change in ID pin input value */ +/******************** Bit definition for DCFG register ********************/ +#define DCFG_DSPD_Pos (0U) +#define DCFG_DSPD_Msk (0x3UL << DCFG_DSPD_Pos) // 0x00000003 +#define DCFG_DSPD_HS 0 // Highspeed +#define DCFG_DSPD_FS_HSPHY 1 // Fullspeed on HS PHY +#define DCFG_DSPD_LS 2 // Lowspeed +#define DCFG_DSPD_FS 3 // Fullspeed on FS PHY + +#define DCFG_NZLSOHSK_Pos (2U) +#define DCFG_NZLSOHSK_Msk (0x1UL << DCFG_NZLSOHSK_Pos) // 0x00000004 */ +#define DCFG_NZLSOHSK DCFG_NZLSOHSK_Msk // Nonzero-length status OUT handshake */ + +#define DCFG_DAD_Pos (4U) +#define DCFG_DAD_Msk (0x7FUL << DCFG_DAD_Pos) // 0x000007F0 */ +#define DCFG_DAD DCFG_DAD_Msk // Device address */ +#define DCFG_DAD_0 (0x01UL << DCFG_DAD_Pos) // 0x00000010 */ +#define DCFG_DAD_1 (0x02UL << DCFG_DAD_Pos) // 0x00000020 */ +#define DCFG_DAD_2 (0x04UL << DCFG_DAD_Pos) // 0x00000040 */ +#define DCFG_DAD_3 (0x08UL << DCFG_DAD_Pos) // 0x00000080 */ +#define DCFG_DAD_4 (0x10UL << DCFG_DAD_Pos) // 0x00000100 */ +#define DCFG_DAD_5 (0x20UL << DCFG_DAD_Pos) // 0x00000200 */ +#define DCFG_DAD_6 (0x40UL << DCFG_DAD_Pos) // 0x00000400 */ + +#define DCFG_PFIVL_Pos (11U) +#define DCFG_PFIVL_Msk (0x3UL << DCFG_PFIVL_Pos) // 0x00001800 */ +#define DCFG_PFIVL DCFG_PFIVL_Msk // Periodic (micro)frame interval */ +#define DCFG_PFIVL_0 (0x1UL << DCFG_PFIVL_Pos) // 0x00000800 */ +#define DCFG_PFIVL_1 (0x2UL << DCFG_PFIVL_Pos) // 0x00001000 */ + +#define DCFG_PERSCHIVL_Pos (24U) +#define DCFG_PERSCHIVL_Msk (0x3UL << DCFG_PERSCHIVL_Pos) // 0x03000000 */ +#define DCFG_PERSCHIVL DCFG_PERSCHIVL_Msk // Periodic scheduling interval */ +#define DCFG_PERSCHIVL_0 (0x1UL << DCFG_PERSCHIVL_Pos) // 0x01000000 */ +#define DCFG_PERSCHIVL_1 (0x2UL << DCFG_PERSCHIVL_Pos) // 0x02000000 */ + /******************** Bit definition for DCTL register ********************/ #define DCTL_RWUSIG_Pos (0U) #define DCTL_RWUSIG_Msk (0x1UL << DCTL_RWUSIG_Pos) // 0x00000001 */ @@ -466,12 +468,15 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define DSTS_SUSPSTS_Pos (0U) #define DSTS_SUSPSTS_Msk (0x1UL << DSTS_SUSPSTS_Pos) // 0x00000001 */ #define DSTS_SUSPSTS DSTS_SUSPSTS_Msk // Suspend status */ - #define DSTS_ENUMSPD_Pos (1U) #define DSTS_ENUMSPD_Msk (0x3UL << DSTS_ENUMSPD_Pos) // 0x00000006 */ #define DSTS_ENUMSPD DSTS_ENUMSPD_Msk // Enumerated speed */ -#define DSTS_ENUMSPD_0 (0x1UL << DSTS_ENUMSPD_Pos) // 0x00000002 */ -#define DSTS_ENUMSPD_1 (0x2UL << DSTS_ENUMSPD_Pos) // 0x00000004 */ +#define DSTS_ENUMSPD_HS 0 // Highspeed +#define DSTS_ENUMSPD_FS_HSPHY 1 // Fullspeed on HS PHY +#define DSTS_ENUMSPD_LS 2 // Lowspeed +#define DSTS_ENUMSPD_FS 3 // Fullspeed on FS PHY + + #define DSTS_EERR_Pos (3U) #define DSTS_EERR_Msk (0x1UL << DSTS_EERR_Pos) // 0x00000008 */ #define DSTS_EERR DSTS_EERR_Msk // Erratic error */ @@ -501,15 +506,12 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define GAHBCFG_PTXFELVL_Msk (0x1UL << GAHBCFG_PTXFELVL_Pos) // 0x00000100 */ #define GAHBCFG_PTXFELVL GAHBCFG_PTXFELVL_Msk // Periodic TxFIFO empty level */ -#define GSNPSID_ID_MASK TU_GENMASK(31, 16) +#define GSNPSID_ID_MASK TU_GENMASK(31, 16) /******************** Bit definition for GUSBCFG register ********************/ #define GUSBCFG_TOCAL_Pos (0U) #define GUSBCFG_TOCAL_Msk (0x7UL << GUSBCFG_TOCAL_Pos) // 0x00000007 */ #define GUSBCFG_TOCAL GUSBCFG_TOCAL_Msk // FS timeout calibration */ -#define GUSBCFG_TOCAL_0 (0x1UL << GUSBCFG_TOCAL_Pos) // 0x00000001 */ -#define GUSBCFG_TOCAL_1 (0x2UL << GUSBCFG_TOCAL_Pos) // 0x00000002 */ -#define GUSBCFG_TOCAL_2 (0x4UL << GUSBCFG_TOCAL_Pos) // 0x00000004 */ #define GUSBCFG_PHYIF16_Pos (3U) #define GUSBCFG_PHYIF16_Msk (0x1UL << GUSBCFG_PHYIF16_Pos) // 0x00000008 */ #define GUSBCFG_PHYIF16 GUSBCFG_PHYIF16_Msk // PHY Interface (PHYIf) */ @@ -519,7 +521,7 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define GUSBCFG_PHYSEL_Pos (6U) #define GUSBCFG_PHYSEL_Msk (0x1UL << GUSBCFG_PHYSEL_Pos) // 0x00000040 */ #define GUSBCFG_PHYSEL GUSBCFG_PHYSEL_Msk // USB 2.0 high-speed ULPI PHY or USB 1.1 full-speed serial transceiver select */ -#define GUSBCFG_DDRSEL TU_BIT(7) // Single Data Rate (SDR) or Double Data Rate (DDR) or ULPI interface. +#define GUSBCFG_DDRSEL TU_BIT(7) // Single Data Rate (SDR) or Double Data Rate (DDR) or ULPI interface. #define GUSBCFG_SRPCAP_Pos (8U) #define GUSBCFG_SRPCAP_Msk (0x1UL << GUSBCFG_SRPCAP_Pos) // 0x00000100 */ #define GUSBCFG_SRPCAP GUSBCFG_SRPCAP_Msk // SRP-capable */ @@ -597,8 +599,8 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define GRSTCTL_TXFNUM_2 (0x04UL << GRSTCTL_TXFNUM_Pos) // 0x00000100 */ #define GRSTCTL_TXFNUM_3 (0x08UL << GRSTCTL_TXFNUM_Pos) // 0x00000200 */ #define GRSTCTL_TXFNUM_4 (0x10UL << GRSTCTL_TXFNUM_Pos) // 0x00000400 */ -#define GRSTCTL_CSFTRST_DONE_Pos (29) -#define GRSTCTL_CSFTRST_DONE (1u << GRSTCTL_CSFTRST_DONE_Pos) // Reset Done, only available from v4.20a +#define GRSTCTL_CSFTRST_DONE_Pos (29) +#define GRSTCTL_CSFTRST_DONE (1u << GRSTCTL_CSFTRST_DONE_Pos) // Reset Done, only available from v4.20a #define GRSTCTL_DMAREQ_Pos (30U) #define GRSTCTL_DMAREQ_Msk (0x1UL << GRSTCTL_DMAREQ_Pos) // 0x40000000 */ #define GRSTCTL_DMAREQ GRSTCTL_DMAREQ_Msk // DMA request signal */ @@ -1672,48 +1674,36 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define DOEPTSIZ_STUPCNT_0 (0x1UL << DOEPTSIZ_STUPCNT_Pos) // 0x20000000 */ #define DOEPTSIZ_STUPCNT_1 (0x2UL << DOEPTSIZ_STUPCNT_Pos) // 0x40000000 */ -/******************** Bit definition for PCGCCTL register ********************/ -#define PCGCCTL_STOPCLK_Pos (0U) -#define PCGCCTL_STOPCLK_Msk (0x1UL << PCGCCTL_STOPCLK_Pos) // 0x00000001 */ -#define PCGCCTL_STOPCLK PCGCCTL_STOPCLK_Msk // SETUP packet count */ -#define PCGCCTL_GATECLK_Pos (1U) -#define PCGCCTL_GATECLK_Msk (0x1UL << PCGCCTL_GATECLK_Pos) // 0x00000002 */ -#define PCGCCTL_GATECLK PCGCCTL_GATECLK_Msk //Bit 0 */ -#define PCGCCTL_PHYSUSP_Pos (4U) -#define PCGCCTL_PHYSUSP_Msk (0x1UL << PCGCCTL_PHYSUSP_Pos) // 0x00000010 */ -#define PCGCCTL_PHYSUSP PCGCCTL_PHYSUSP_Msk //Bit 1 */ +/******************** Bit definition for PCGCTL register ********************/ +#define PCGCTL_IF_DEV_MODE TU_BIT(31) +#define PCGCTL_P2HD_PRT_SPD_MASK (0x3ul << 29) +#define PCGCTL_P2HD_PRT_SPD_SHIFT 29 +#define PCGCTL_P2HD_DEV_ENUM_SPD_MASK (0x3ul << 27) +#define PCGCTL_P2HD_DEV_ENUM_SPD_SHIFT 27 +#define PCGCTL_MAC_DEV_ADDR_MASK (0x7ful << 20) +#define PCGCTL_MAC_DEV_ADDR_SHIFT 20 +#define PCGCTL_MAX_TERMSEL TU_BIT(19) +#define PCGCTL_MAX_XCVRSELECT_MASK (0x3ul << 17) +#define PCGCTL_MAX_XCVRSELECT_SHIFT 17 +#define PCGCTL_PORT_POWER TU_BIT(16) +#define PCGCTL_PRT_CLK_SEL_MASK (0x3ul << 14) +#define PCGCTL_PRT_CLK_SEL_SHIFT 14 +#define PCGCTL_ESS_REG_RESTORED TU_BIT(13) +#define PCGCTL_EXTND_HIBER_SWITCH TU_BIT(12) +#define PCGCTL_EXTND_HIBER_PWRCLMP TU_BIT(11) +#define PCGCTL_ENBL_EXTND_HIBER TU_BIT(10) +#define PCGCTL_RESTOREMODE TU_BIT(9) +#define PCGCTL_RESETAFTSUSP TU_BIT(8) +#define PCGCTL_DEEP_SLEEP TU_BIT(7) +#define PCGCTL_PHY_IN_SLEEP TU_BIT(6) +#define PCGCTL_ENBL_SLEEP_GATING TU_BIT(5) +#define PCGCTL_RSTPDWNMODULE TU_BIT(3) +#define PCGCTL_PWRCLMP TU_BIT(2) +#define PCGCTL_GATEHCLK TU_BIT(1) +#define PCGCTL_STOPPCLK TU_BIT(0) -/******************** Bit definition for USBPHYC_PLL1 register ********************/ -#define HS_PHYC_PLL1_PLLEN_Pos (0U) -#define HS_PHYC_PLL1_PLLEN_Msk (0x1UL << HS_PHYC_PLL1_PLLEN_Pos) // 0x00000001 */ -#define HS_PHYC_PLL1_PLLEN HS_PHYC_PLL1_PLLEN_Msk // Enable PLL */ -#define HS_PHYC_PLL1_PLLSEL_Pos (1U) -#define HS_PHYC_PLL1_PLLSEL_Msk (0x7UL << HS_PHYC_PLL1_PLLSEL_Pos) // 0x0000000E */ -#define HS_PHYC_PLL1_PLLSEL HS_PHYC_PLL1_PLLSEL_Msk // Controls PHY frequency operation selection */ -#define HS_PHYC_PLL1_PLLSEL_1 (0x1UL << HS_PHYC_PLL1_PLLSEL_Pos) // 0x00000002 */ -#define HS_PHYC_PLL1_PLLSEL_2 (0x2UL << HS_PHYC_PLL1_PLLSEL_Pos) // 0x00000004 */ -#define HS_PHYC_PLL1_PLLSEL_3 (0x4UL << HS_PHYC_PLL1_PLLSEL_Pos) // 0x00000008 */ - -#define HS_PHYC_PLL1_PLLSEL_12MHZ 0x00000000U // PHY PLL1 input clock frequency 12 MHz */ -#define HS_PHYC_PLL1_PLLSEL_12_5MHZ HS_PHYC_PLL1_PLLSEL_1 // PHY PLL1 input clock frequency 12.5 MHz */ -#define HS_PHYC_PLL1_PLLSEL_16MHZ (uint32_t)(HS_PHYC_PLL1_PLLSEL_1 | HS_PHYC_PLL1_PLLSEL_2) // PHY PLL1 input clock frequency 16 MHz */ -#define HS_PHYC_PLL1_PLLSEL_24MHZ HS_PHYC_PLL1_PLLSEL_3 // PHY PLL1 input clock frequency 24 MHz */ -#define HS_PHYC_PLL1_PLLSEL_25MHZ (uint32_t)(HS_PHYC_PLL1_PLLSEL_2 | HS_PHYC_PLL1_PLLSEL_3) // PHY PLL1 input clock frequency 25 MHz */ - -/******************** Bit definition for USBPHYC_LDO register ********************/ -#define HS_PHYC_LDO_USED_Pos (0U) -#define HS_PHYC_LDO_USED_Msk (0x1UL << HS_PHYC_LDO_USED_Pos) // 0x00000001 */ -#define HS_PHYC_LDO_USED HS_PHYC_LDO_USED_Msk // Monitors the usage status of the PHY's LDO */ -#define HS_PHYC_LDO_STATUS_Pos (1U) -#define HS_PHYC_LDO_STATUS_Msk (0x1UL << HS_PHYC_LDO_STATUS_Pos) // 0x00000002 */ -#define HS_PHYC_LDO_STATUS HS_PHYC_LDO_STATUS_Msk // Monitors the status of the PHY's LDO. */ -#define HS_PHYC_LDO_DISABLE_Pos (2U) -#define HS_PHYC_LDO_DISABLE_Msk (0x1UL << HS_PHYC_LDO_DISABLE_Pos) // 0x00000004 */ -#define HS_PHYC_LDO_DISABLE HS_PHYC_LDO_DISABLE_Msk // Controls disable of the High Speed PHY's LDO */ - -#define HS_PHYC_LDO_ENABLE_Pos HS_PHYC_LDO_DISABLE_Pos -#define HS_PHYC_LDO_ENABLE_Msk HS_PHYC_LDO_DISABLE_Msk -#define HS_PHYC_LDO_ENABLE HS_PHYC_LDO_DISABLE +#define PCGCTL1_TIMER (0x3ul << 1) +#define PCGCTL1_GATEEN TU_BIT(0) #ifdef __cplusplus } From 660e8b8c887091e17323c361f25e804a5d06d6df Mon Sep 17 00:00:00 2001 From: hathach Date: Fri, 29 Oct 2021 16:08:19 +0700 Subject: [PATCH 35/51] skip snpsid check for gd32, abstract phyfs turnaround, set max timeout calibration. still has issue with gd32 with msc (does work with running with rtt as log). --- src/common/tusb_common.h | 3 + src/portable/synopsys/dwc2/dcd_dwc2.c | 193 ++++++++++++------------ src/portable/synopsys/dwc2/dwc2_bcm.h | 7 +- src/portable/synopsys/dwc2/dwc2_esp32.h | 8 +- src/portable/synopsys/dwc2/dwc2_gd32.h | 8 +- src/portable/synopsys/dwc2/dwc2_stm32.h | 57 +++---- src/portable/synopsys/dwc2/dwc2_type.h | 13 +- 7 files changed, 143 insertions(+), 146 deletions(-) diff --git a/src/common/tusb_common.h b/src/common/tusb_common.h index e62bcde12..9b9e2b007 100644 --- a/src/common/tusb_common.h +++ b/src/common/tusb_common.h @@ -111,6 +111,9 @@ TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u32_byte2(uint32_t ui32) { return TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u32_byte1(uint32_t ui32) { return TU_U32_BYTE1(ui32); } TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u32_byte0(uint32_t ui32) { return TU_U32_BYTE0(ui32); } +TU_ATTR_ALWAYS_INLINE static inline uint16_t tu_u32_high16(uint32_t ui32) { return (uint16_t) (ui32 >> 16); } +TU_ATTR_ALWAYS_INLINE static inline uint16_t tu_u32_low16 (uint32_t ui32) { return (uint16_t) (ui32 & 0x0000ffffu); } + TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u16_high(uint16_t ui16) { return TU_U16_HIGH(ui16); } TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u16_low (uint16_t ui16) { return TU_U16_LOW(ui16); } diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index ce9b58e03..aad7e45cc 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -54,16 +54,8 @@ #define DWC2_REG(_port) ((dwc2_regs_t*) DWC2_REG_BASE) -enum -{ - DCD_HIGH_SPEED = 0, // Highspeed mode - DCD_FULL_SPEED_USE_HS = 1, // Full speed in Highspeed port (probably with internal PHY) - DCD_FULL_SPEED = 3, // Full speed with internal PHY -}; - -// PHYSEL, ULPISEL -// UTMI internal HS PHY -// ULPI external HS PHY +// Debug level for DWC2 +#define DWC2_DEBUG 1 static TU_ATTR_ALIGNED(4) uint32_t _setup_packet[2]; @@ -261,71 +253,73 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c /*------------------------------------------------------------------*/ /* Controller API *------------------------------------------------------------------*/ +#if CFG_TUSB_DEBUG >= DWC2_DEBUG void print_dwc2_info(dwc2_regs_t * dwc2) { dwc2_ghwcfg2_t const * hw_cfg2 = &dwc2->ghwcfg2_bm; dwc2_ghwcfg3_t const * hw_cfg3 = &dwc2->ghwcfg3_bm; dwc2_ghwcfg4_t const * hw_cfg4 = &dwc2->ghwcfg4_bm; - TU_LOG_HEX(1, dwc2->guid); - TU_LOG_HEX(1, dwc2->gsnpsid); - TU_LOG_HEX(1, dwc2->ghwcfg1); + TU_LOG_HEX(DWC2_DEBUG, dwc2->guid); + TU_LOG_HEX(DWC2_DEBUG, dwc2->gsnpsid); + TU_LOG_HEX(DWC2_DEBUG, dwc2->ghwcfg1); // HW configure 2 - TU_LOG(1, "\r\n"); - TU_LOG_HEX(1, dwc2->ghwcfg2); - TU_LOG_INT(1, hw_cfg2->op_mode ); - TU_LOG_INT(1, hw_cfg2->arch ); - TU_LOG_INT(1, hw_cfg2->point2point ); - TU_LOG_INT(1, hw_cfg2->hs_phy_type ); - TU_LOG_INT(1, hw_cfg2->fs_phy_type ); - TU_LOG_INT(1, hw_cfg2->num_dev_ep ); - TU_LOG_INT(1, hw_cfg2->num_host_ch ); - TU_LOG_INT(1, hw_cfg2->period_channel_support ); - TU_LOG_INT(1, hw_cfg2->enable_dynamic_fifo ); - TU_LOG_INT(1, hw_cfg2->mul_cpu_int ); - TU_LOG_INT(1, hw_cfg2->nperiod_tx_q_depth ); - TU_LOG_INT(1, hw_cfg2->host_period_tx_q_depth ); - TU_LOG_INT(1, hw_cfg2->dev_token_q_depth ); - TU_LOG_INT(1, hw_cfg2->otg_enable_ic_usb ); + TU_LOG(DWC2_DEBUG, "\r\n"); + TU_LOG_HEX(DWC2_DEBUG, dwc2->ghwcfg2); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->op_mode ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->arch ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->point2point ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->hs_phy_type ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->fs_phy_type ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->num_dev_ep ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->num_host_ch ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->period_channel_support ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->enable_dynamic_fifo ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->mul_cpu_int ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->nperiod_tx_q_depth ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->host_period_tx_q_depth ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->dev_token_q_depth ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg2->otg_enable_ic_usb ); // HW configure 3 - TU_LOG(1, "\r\n"); - TU_LOG_HEX(1, dwc2->ghwcfg3); - TU_LOG_INT(1, hw_cfg3->xfer_size_width ); - TU_LOG_INT(1, hw_cfg3->packet_size_width ); - TU_LOG_INT(1, hw_cfg3->otg_enable ); - TU_LOG_INT(1, hw_cfg3->i2c_enable ); - TU_LOG_INT(1, hw_cfg3->vendor_ctrl_itf ); - TU_LOG_INT(1, hw_cfg3->optional_feature_removed ); - TU_LOG_INT(1, hw_cfg3->synch_reset ); - TU_LOG_INT(1, hw_cfg3->otg_adp_support ); - TU_LOG_INT(1, hw_cfg3->otg_enable_hsic ); - TU_LOG_INT(1, hw_cfg3->battery_charger_support ); - TU_LOG_INT(1, hw_cfg3->lpm_mode ); - TU_LOG_INT(1, hw_cfg3->total_fifo_size ); + TU_LOG(DWC2_DEBUG, "\r\n"); + TU_LOG_HEX(DWC2_DEBUG, dwc2->ghwcfg3); + TU_LOG_INT(DWC2_DEBUG, hw_cfg3->xfer_size_width ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg3->packet_size_width ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg3->otg_enable ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg3->i2c_enable ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg3->vendor_ctrl_itf ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg3->optional_feature_removed ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg3->synch_reset ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg3->otg_adp_support ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg3->otg_enable_hsic ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg3->battery_charger_support ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg3->lpm_mode ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg3->total_fifo_size ); // HW configure 4 - TU_LOG(1, "\r\n"); - TU_LOG_HEX(1, dwc2->ghwcfg4); - TU_LOG_INT(1, hw_cfg4->num_dev_period_in_ep ); - TU_LOG_INT(1, hw_cfg4->power_optimized ); - TU_LOG_INT(1, hw_cfg4->ahb_freq_min ); - TU_LOG_INT(1, hw_cfg4->hibernation ); - TU_LOG_INT(1, hw_cfg4->service_interval_mode ); - TU_LOG_INT(1, hw_cfg4->ipg_isoc_en ); - TU_LOG_INT(1, hw_cfg4->acg_enable ); - TU_LOG_INT(1, hw_cfg4->utmi_phy_data_width ); - TU_LOG_INT(1, hw_cfg4->dev_ctrl_ep_num ); - TU_LOG_INT(1, hw_cfg4->iddg_filter_enabled ); - TU_LOG_INT(1, hw_cfg4->vbus_valid_filter_enabled ); - TU_LOG_INT(1, hw_cfg4->a_valid_filter_enabled ); - TU_LOG_INT(1, hw_cfg4->b_valid_filter_enabled ); - TU_LOG_INT(1, hw_cfg4->dedicated_fifos ); - TU_LOG_INT(1, hw_cfg4->num_dev_in_eps ); - TU_LOG_INT(1, hw_cfg4->dma_desc_enable ); - TU_LOG_INT(1, hw_cfg4->dma_dynamic ); + TU_LOG(DWC2_DEBUG, "\r\n"); + TU_LOG_HEX(DWC2_DEBUG, dwc2->ghwcfg4); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->num_dev_period_in_ep ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->power_optimized ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->ahb_freq_min ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->hibernation ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->service_interval_mode ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->ipg_isoc_en ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->acg_enable ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->utmi_phy_data_width ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->dev_ctrl_ep_num ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->iddg_filter_enabled ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->vbus_valid_filter_enabled ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->a_valid_filter_enabled ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->b_valid_filter_enabled ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->dedicated_fifos ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->num_dev_in_eps ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->dma_desc_enable ); + TU_LOG_INT(DWC2_DEBUG, hw_cfg4->dma_dynamic ); } +#endif static void reset_core(dwc2_regs_t * dwc2) { @@ -342,14 +336,15 @@ static void reset_core(dwc2_regs_t * dwc2) // wait for device mode ? } -static bool has_hs_phy(dwc2_regs_t * dwc2) +static bool phy_hs_supported(dwc2_regs_t * dwc2) { + // note: esp32 incorrect report its hs_phy_type as utmi return TUD_OPT_HIGH_SPEED && dwc2->ghwcfg2_bm.hs_phy_type != HS_PHY_TYPE_NONE; } static void phy_fs_init(dwc2_regs_t * dwc2) { - TU_LOG1("Fullspeed PHY init\r\n"); + TU_LOG(DWC2_DEBUG, "Fullspeed PHY init\r\n"); // Select FS PHY dwc2->gusbcfg |= GUSBCFG_PHYSEL; @@ -358,11 +353,11 @@ static void phy_fs_init(dwc2_regs_t * dwc2) reset_core(dwc2); // set turn around - // The values above are calculated for the minimum AHB frequency of 30 MHz. USB turnaround - // time is critical for certification where long cables and 5-Hubs are used, so if - // you need the AHB to run at less than 30 MHz, and if USB turnaround time is not critical, + // USB turnaround time is critical for certification where long cables and 5-Hubs are used. + // So if you need the AHB to run at less than 30 MHz, and if USB turnaround time is not critical, // these bits can be programmed to a larger value. - dwc2_set_turnaround(dwc2, TUSB_SPEED_FULL); + //TU_LOG_INT(DWC2_DEBUG, (dwc2->gusbcfg & GUSBCFG_TRDT_Msk) >> GUSBCFG_TRDT_Pos ); + dwc2_phyfs_set_turnaround(dwc2); // set max speed dwc2->dcfg = (dwc2->dcfg & ~DCFG_DSPD_Msk) | (DCFG_DSPD_FS << DCFG_DSPD_Pos); @@ -382,7 +377,7 @@ static void phy_hs_init(dwc2_regs_t * dwc2) if (dwc2->ghwcfg2_bm.hs_phy_type == HS_PHY_TYPE_ULPI) { - TU_LOG1("Highspeed ULPI PHY init\r\n"); + TU_LOG(DWC2_DEBUG, "Highspeed ULPI PHY init\r\n"); // Select ULPI gusbcfg |= GUSBCFG_ULPI_UTMI_SEL; @@ -397,7 +392,7 @@ static void phy_hs_init(dwc2_regs_t * dwc2) gusbcfg &= ~(GUSBCFG_ULPIFSLS | GUSBCFG_ULPICSM); }else { - TU_LOG1("Highspeed UTMI+ PHY init\r\n"); + TU_LOG(DWC2_DEBUG, "Highspeed UTMI+ PHY init\r\n"); // Select UTMI+ with 8-bit interface gusbcfg &= ~(GUSBCFG_ULPI_UTMI_SEL | GUSBCFG_PHYIF16); @@ -422,11 +417,8 @@ static void phy_hs_init(dwc2_regs_t * dwc2) reset_core(dwc2); // Set turn-around, must after core reset otherwise it will be clear - // 9 if UTMI interface is 8-bit, 5 if 16-bit - // The values above are calculated for the minimum AHB frequency of 30 MHz. USB turnaround - // time is critical for certification where long cables and 5-Hubs are used, so if - // you need the AHB to run at less than 30 MHz, and if USB turnaround time is not critical, - // these bits can be programmed to a larger value. + // - 9 if using 8-bit PHY interface + // - 5 if using 16-bit PHY interface gusbcfg &= ~GUSBCFG_TRDT_Msk; gusbcfg |= (dwc2->ghwcfg4_bm.utmi_phy_data_width ? 5u : 9u) << GUSBCFG_TRDT_Pos; dwc2->gusbcfg = gusbcfg; // Apply config @@ -435,31 +427,45 @@ static void phy_hs_init(dwc2_regs_t * dwc2) dwc2->dcfg = (dwc2->dcfg & ~DCFG_DSPD_Msk) | (DCFG_DSPD_HS << DCFG_DSPD_Pos); } +static bool check_dwc2(dwc2_regs_t * dwc2) +{ + // For some reasons: GD32VF103 snpsid and all hwcfg register are always zero (skip it) +#if !TU_CHECK_MCU(OPT_MCU_GD32VF103) + uint32_t const gsnpsid = dwc2->gsnpsid & GSNPSID_ID_MASK; + TU_ASSERT(gsnpsid == DWC2_OTG_ID || gsnpsid == DWC2_FS_IOT_ID || gsnpsid == DWC2_HS_IOT_ID); +#endif + +#if CFG_TUSB_DEBUG >= DWC2_DEBUG + print_dwc2_info(dwc2); +#endif + + return true; +} + void dcd_init (uint8_t rhport) { // Programming model begins in the last section of the chapter on the USB // peripheral in each Reference Manual. dwc2_regs_t * dwc2 = DWC2_REG(rhport); - // Check Synopsys ID, failed if controller is not enabled - uint32_t const gsnpsid = dwc2->gsnpsid & GSNPSID_ID_MASK; - TU_ASSERT(gsnpsid == DWC2_OTG_ID || gsnpsid == DWC2_FS_IOT_ID || gsnpsid == DWC2_HS_IOT_ID, ); - - print_dwc2_info(dwc2); + // Check Synopsys ID register, failed if controller clock/power is not enabled + TU_VERIFY(check_dwc2(dwc2), ); // Force device mode dwc2->gusbcfg = (dwc2->gusbcfg & ~GUSBCFG_FHMOD) | GUSBCFG_FDMOD; - if( !has_hs_phy(dwc2) ) - { - // core does not support highspeed or hs-phy is not present - phy_fs_init(dwc2); - }else + if( phy_hs_supported(dwc2) ) { // Highspeed phy_hs_init(dwc2); + }else + { + // core does not support highspeed or hs-phy is not present + phy_fs_init(dwc2); } + TU_LOG_HEX(DWC2_DEBUG, dwc2->gusbcfg); + /* Set HS/FS Timeout Calibration to 7 (max available value). * The number of PHY clocks that the application programs in * this field is added to the high/full speed interpacket timeout @@ -468,7 +474,7 @@ void dcd_init (uint8_t rhport) * introduced by the PHY in generating the linestate condition * can vary from one PHY to another. */ - // dwc2->gusbcfg |= (7ul << GUSBCFG_TOCAL_Pos); + dwc2->gusbcfg |= (7ul << GUSBCFG_TOCAL_Pos); // Restart PHY clock dwc2->pcgctl &= ~(PCGCTL_STOPPCLK | PCGCTL_GATEHCLK | PCGCTL_PWRCLMP | PCGCTL_RSTPDWNMODULE); @@ -617,7 +623,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) _allocated_fifo_words_tx += fifo_size; - TU_LOG(2, " Allocated %u bytes at offset %u", fifo_size*4, DWC2_EP_FIFO_SIZE-_allocated_fifo_words_tx*4); + TU_LOG(DWC2_DEBUG, " Allocated %u bytes at offset %u", fifo_size*4, DWC2_EP_FIFO_SIZE-_allocated_fifo_words_tx*4); // DIEPTXF starts at FIFO #1. // Both TXFD and TXSA are in unit of 32-bit words. @@ -1110,14 +1116,15 @@ void dcd_int_handler(uint8_t rhport) speed = TUSB_SPEED_HIGH; break; - case DSTS_ENUMSPD_FS_HSPHY: - case DSTS_ENUMSPD_FS: - speed = TUSB_SPEED_FULL; - break; - case DSTS_ENUMSPD_LS: speed = TUSB_SPEED_LOW; break; + + case DSTS_ENUMSPD_FS_HSPHY: + case DSTS_ENUMSPD_FS: + default: + speed = TUSB_SPEED_FULL; + break; } dcd_event_bus_reset(rhport, speed, true); @@ -1204,7 +1211,7 @@ void dcd_int_handler(uint8_t rhport) // // Check for Incomplete isochronous IN transfer // if(int_status & GINTSTS_IISOIXFR) { // printf(" IISOIXFR!\r\n"); - //// TU_LOG2(" IISOIXFR!\r\n"); + //// TU_LOG(DWC2_DEBUG, " IISOIXFR!\r\n"); // } } diff --git a/src/portable/synopsys/dwc2/dwc2_bcm.h b/src/portable/synopsys/dwc2/dwc2_bcm.h index da1f23ae0..c064946cf 100644 --- a/src/portable/synopsys/dwc2/dwc2_bcm.h +++ b/src/portable/synopsys/dwc2/dwc2_bcm.h @@ -58,11 +58,10 @@ static inline void dwc2_remote_wakeup_delay(void) // TODO implement later } -static inline void dwc2_set_turnaround(dwc2_regs_t * core, tusb_speed_t speed) +static inline void dwc2_phyfs_set_turnaround(dwc2_regs_t * dwc2) { - // TODO implement later - (void) core; - (void) speed; + (void) dwc2; + // do nothing since bcm alwyas use HS PHY } #ifdef __cplusplus diff --git a/src/portable/synopsys/dwc2/dwc2_esp32.h b/src/portable/synopsys/dwc2/dwc2_esp32.h index b8a040041..af5d5f093 100644 --- a/src/portable/synopsys/dwc2/dwc2_esp32.h +++ b/src/portable/synopsys/dwc2/dwc2_esp32.h @@ -67,12 +67,10 @@ static inline void dwc2_remote_wakeup_delay(void) vTaskDelay(pdMS_TO_TICKS(1)); } -static inline void dwc2_set_turnaround(dwc2_regs_t * core, tusb_speed_t speed) +static inline void dwc2_phyfs_set_turnaround(dwc2_regs_t * dwc2) { - (void) core; - (void) speed; - - // keep the reset value + (void) dwc2; + // keep the reset value which is 5 on this port } #ifdef __cplusplus diff --git a/src/portable/synopsys/dwc2/dwc2_gd32.h b/src/portable/synopsys/dwc2/dwc2_gd32.h index de3ccb3b0..15e73ad1e 100644 --- a/src/portable/synopsys/dwc2/dwc2_gd32.h +++ b/src/portable/synopsys/dwc2/dwc2_gd32.h @@ -76,12 +76,10 @@ static inline void dwc2_remote_wakeup_delay(void) while ( count-- ) __asm volatile ("nop"); } -static inline void dwc2_set_turnaround(dwc2_regs_t * core, tusb_speed_t speed) +static inline void dwc2_phyfs_set_turnaround(dwc2_regs_t * dwc2) { - (void) core; - (void) speed; - - // keep the reset value + // use recommeded value 6 by stm32 for mcu with AHB clock > 32Mhz + dwc2->gusbcfg = (dwc2->gusbcfg & GUSBCFG_TRDT_Msk) | (6u << GUSBCFG_TRDT_Pos); } diff --git a/src/portable/synopsys/dwc2/dwc2_stm32.h b/src/portable/synopsys/dwc2/dwc2_stm32.h index b77cda2ca..4d0ed3f0a 100644 --- a/src/portable/synopsys/dwc2/dwc2_stm32.h +++ b/src/portable/synopsys/dwc2/dwc2_stm32.h @@ -113,44 +113,33 @@ static inline void dwc2_remote_wakeup_delay(void) } // Set turn-around timeout according to link speed -static inline void dwc2_set_turnaround(dwc2_regs_t * dwc2, tusb_speed_t speed) +static inline void dwc2_phyfs_set_turnaround(dwc2_regs_t * dwc2) { - dwc2->gusbcfg &= ~GUSBCFG_TRDT; + // Turnaround timeout depends on the AHB clock dictated by STM32 Reference Manual + uint32_t turnaround; - if ( speed == TUSB_SPEED_HIGH ) - { - // Use fixed 0x09 for Highspeed - dwc2->gusbcfg |= (0x09 << GUSBCFG_TRDT_Pos); - } + if ( SystemCoreClock >= 32000000U ) + turnaround = 0x6u; + else if ( SystemCoreClock >= 27500000U ) + turnaround = 0x7u; + else if ( SystemCoreClock >= 24000000U ) + turnaround = 0x8u; + else if ( SystemCoreClock >= 21800000U ) + turnaround = 0x9u; + else if ( SystemCoreClock >= 20000000U ) + turnaround = 0xAu; + else if ( SystemCoreClock >= 18500000U ) + turnaround = 0xBu; + else if ( SystemCoreClock >= 17200000U ) + turnaround = 0xCu; + else if ( SystemCoreClock >= 16000000U ) + turnaround = 0xDu; + else if ( SystemCoreClock >= 15000000U ) + turnaround = 0xEu; else - { - // Turnaround timeout depends on the MCU clock - uint32_t turnaround; + turnaround = 0xFu; - if ( SystemCoreClock >= 32000000U ) - turnaround = 0x6U; - else if ( SystemCoreClock >= 27500000U ) - turnaround = 0x7U; - else if ( SystemCoreClock >= 24000000U ) - turnaround = 0x8U; - else if ( SystemCoreClock >= 21800000U ) - turnaround = 0x9U; - else if ( SystemCoreClock >= 20000000U ) - turnaround = 0xAU; - else if ( SystemCoreClock >= 18500000U ) - turnaround = 0xBU; - else if ( SystemCoreClock >= 17200000U ) - turnaround = 0xCU; - else if ( SystemCoreClock >= 16000000U ) - turnaround = 0xDU; - else if ( SystemCoreClock >= 15000000U ) - turnaround = 0xEU; - else - turnaround = 0xFU; - - // Fullspeed depends on MCU clocks, but we will use 0x06 for 32+ Mhz - dwc2->gusbcfg |= (turnaround << GUSBCFG_TRDT_Pos); - } + dwc2->gusbcfg = (dwc2->gusbcfg & GUSBCFG_TRDT_Msk) | (turnaround << GUSBCFG_TRDT_Pos); } #if defined(USB_HS_PHYC) diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 7e472310f..7b3db4dd9 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -59,12 +59,19 @@ typedef struct #endif enum { - HS_PHY_TYPE_NONE = 0 , + HS_PHY_TYPE_NONE = 0 , // not supported HS_PHY_TYPE_UTMI , // internal PHY (mostly) HS_PHY_TYPE_ULPI , // external PHY HS_PHY_TYPE_UTMI_ULPI , }; +enum { + FS_PHY_TYPE_NONE = 0, // not supported + FS_PHY_TYPE_DEDICATED, + FS_PHY_TYPE_UTMI, + FS_PHY_TYPE_ULPI, +}; + typedef struct TU_ATTR_PACKED { uint32_t op_mode : 3; // 0: HNP and SRP | 1: SRP | 2: non-HNP, non-SRP @@ -531,10 +538,6 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define GUSBCFG_TRDT_Pos (10U) #define GUSBCFG_TRDT_Msk (0xFUL << GUSBCFG_TRDT_Pos) // 0x00003C00 */ #define GUSBCFG_TRDT GUSBCFG_TRDT_Msk // USB turnaround time */ -#define GUSBCFG_TRDT_0 (0x1UL << GUSBCFG_TRDT_Pos) // 0x00000400 */ -#define GUSBCFG_TRDT_1 (0x2UL << GUSBCFG_TRDT_Pos) // 0x00000800 */ -#define GUSBCFG_TRDT_2 (0x4UL << GUSBCFG_TRDT_Pos) // 0x00001000 */ -#define GUSBCFG_TRDT_3 (0x8UL << GUSBCFG_TRDT_Pos) // 0x00002000 */ #define GUSBCFG_PHYLPCS_Pos (15U) #define GUSBCFG_PHYLPCS_Msk (0x1UL << GUSBCFG_PHYLPCS_Pos) // 0x00008000 */ #define GUSBCFG_PHYLPCS GUSBCFG_PHYLPCS_Msk // PHY Low-power clock select */ From 9cd5a87c64425b8a7427531735f06f255117aeeb Mon Sep 17 00:00:00 2001 From: hathach Date: Sat, 30 Oct 2021 20:42:55 +0700 Subject: [PATCH 36/51] add support for EFM32GG merge GG12 GG12 to simply OPT_MCU_EFM32GG --- hw/bsp/board_mcu.h | 2 +- hw/bsp/sltb009a/board.mk | 4 +- hw/bsp/stm32f4/family.c | 7 + hw/bsp/stm32h7/boards/stm32h743eval/board.mk | 1 + hw/bsp/stm32h7/family.mk | 12 +- src/device/dcd_attr.h | 2 +- src/host/hcd_attr.h | 2 +- src/portable/synopsys/dwc2/dcd_dwc2.c | 96 +++++++----- src/portable/synopsys/dwc2/dwc2_bcm.h | 17 ++- src/portable/synopsys/dwc2/dwc2_esp32.h | 18 ++- src/portable/synopsys/dwc2/dwc2_gd32.h | 18 ++- src/portable/synopsys/dwc2/dwc2_stm32.h | 147 ++++++++++--------- src/portable/synopsys/dwc2/dwc2_type.h | 2 +- src/tusb_option.h | 2 - 14 files changed, 204 insertions(+), 126 deletions(-) diff --git a/hw/bsp/board_mcu.h b/hw/bsp/board_mcu.h index a4d57597c..c840db89e 100644 --- a/hw/bsp/board_mcu.h +++ b/hw/bsp/board_mcu.h @@ -125,7 +125,7 @@ #elif CFG_TUSB_MCU == OPT_MCU_RP2040 #include "pico.h" -#elif CFG_TUSB_MCU == OPT_MCU_EFM32GG || CFG_TUSB_MCU == OPT_MCU_EFM32GG11 || CFG_TUSB_MCU == OPT_MCU_EFM32GG12 +#elif CFG_TUSB_MCU == OPT_MCU_EFM32GG #include "em_device.h" #elif CFG_TUSB_MCU == OPT_MCU_RX63X || CFG_TUSB_MCU == OPT_MCU_RX65X diff --git a/hw/bsp/sltb009a/board.mk b/hw/bsp/sltb009a/board.mk index e8a24d1bd..7a046b34b 100644 --- a/hw/bsp/sltb009a/board.mk +++ b/hw/bsp/sltb009a/board.mk @@ -8,7 +8,7 @@ CFLAGS += \ -D__STARTUP_CLEAR_BSS \ -D__START=main \ -DEFM32GG12B810F1024GM64 \ - -DCFG_TUSB_MCU=OPT_MCU_EFM32GG12 + -DCFG_TUSB_MCU=OPT_MCU_EFM32GG # mcu driver cause following warnings #CFLAGS += -Wno-error=unused-parameter @@ -24,7 +24,7 @@ LD_FILE = $(SILABS_CMSIS)/Source/GCC/$(SILABS_FAMILY).ld SRC_C += \ $(SILABS_CMSIS)/Source/system_$(SILABS_FAMILY).c \ - src/portable/silabs/efm32/dcd_efm32.c + src/portable/synopsys/dwc2/dcd_dwc2.c SRC_S += \ $(SILABS_CMSIS)/Source/GCC/startup_$(SILABS_FAMILY).S diff --git a/hw/bsp/stm32f4/family.c b/hw/bsp/stm32f4/family.c index 31f27fa3f..82d4957e7 100644 --- a/hw/bsp/stm32f4/family.c +++ b/hw/bsp/stm32f4/family.c @@ -36,6 +36,11 @@ void OTG_FS_IRQHandler(void) tud_int_handler(0); } +void OTG_HS_IRQHandler(void) +{ + tud_int_handler(1); +} + //--------------------------------------------------------------------+ // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ @@ -134,6 +139,8 @@ void board_init(void) // Enable USB OTG clock __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); +// __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); + board_vbus_sense_init(); } diff --git a/hw/bsp/stm32h7/boards/stm32h743eval/board.mk b/hw/bsp/stm32h7/boards/stm32h743eval/board.mk index 96d14a795..b768a0ee6 100644 --- a/hw/bsp/stm32h7/boards/stm32h743eval/board.mk +++ b/hw/bsp/stm32h7/boards/stm32h743eval/board.mk @@ -2,6 +2,7 @@ CFLAGS += -DSTM32H743xx -DHSE_VALUE=25000000 # Default is Highspeed port PORT ?= 1 +SPEED ?= high SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32h743xx.s LD_FILE = $(BOARD_PATH)/stm32h743xx_flash.ld diff --git a/hw/bsp/stm32h7/family.mk b/hw/bsp/stm32h7/family.mk index 6a257e22d..096d04d0c 100644 --- a/hw/bsp/stm32h7/family.mk +++ b/hw/bsp/stm32h7/family.mk @@ -19,16 +19,22 @@ CFLAGS += \ -DBOARD_DEVICE_RHPORT_NUM=$(PORT) ifeq ($(PORT), 1) - CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED - $(info "PORT1 High Speed") + 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 "PORT0 Full Speed") + $(info "Using OTG_FS") endif # suppress warning caused by vendor mcu driver CFLAGS += -Wno-error=maybe-uninitialized -Wno-error=cast-align # All source paths should be relative to the top level. + SRC_C += \ src/portable/synopsys/dwc2/dcd_dwc2.c \ $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ diff --git a/src/device/dcd_attr.h b/src/device/dcd_attr.h index 90f3a526a..70854f9c6 100644 --- a/src/device/dcd_attr.h +++ b/src/device/dcd_attr.h @@ -169,7 +169,7 @@ #define DCD_ATTR_ENDPOINT_MAX 16 //------------- Silabs -------------// -#elif TU_CHECK_MCU(OPT_MCU_EFM32GG, OPT_MCU_EFM32GG11, OPT_MCU_EFM32GG12) +#elif TU_CHECK_MCU(OPT_MCU_EFM32GG) #define DCD_ATTR_ENDPOINT_MAX 7 //------------- Renesas -------------// diff --git a/src/host/hcd_attr.h b/src/host/hcd_attr.h index a9bc242d7..06011c63c 100644 --- a/src/host/hcd_attr.h +++ b/src/host/hcd_attr.h @@ -82,7 +82,7 @@ #elif TU_CHECK_MCU(OPT_MCU_RP2040) //------------- Silabs -------------// -#elif TU_CHECK_MCU(OPT_MCU_EFM32GG, OPT_MCU_EFM32GG11, OPT_MCU_EFM32GG12) +#elif TU_CHECK_MCU(OPT_MCU_EFM32GG) //------------- Renesas -------------// #elif TU_CHECK_MCU(OPT_MCU_RX63X, OPT_MCU_RX65X, OPT_MCU_RX72N) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index aad7e45cc..16780cba8 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -31,7 +31,9 @@ #include "device/dcd_attr.h" #if TUSB_OPT_DEVICE_ENABLED && \ - ( defined(DCD_ATTR_DWC2_STM32) || TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3, OPT_MCU_GD32VF103, OPT_MCU_BCM2711) ) + ( defined(DCD_ATTR_DWC2_STM32) || \ + TU_CHECK_MCU(OPT_MCU_ESP32S2, OPT_MCU_ESP32S3, OPT_MCU_GD32VF103) || \ + TU_CHECK_MCU(OPT_MCU_EFM32GG, OPT_MCU_BCM2711) ) #include "device/dcd.h" #include "dwc2_type.h" @@ -44,6 +46,8 @@ #include "dwc2_gd32.h" #elif TU_CHECK_MCU(OPT_MCU_BCM2711) #include "dwc2_bcm.h" +#elif TU_CHECK_MCU(OPT_MCU_EFM32GG) + #include "dwc2_efm32.h" #else #error "Unsupported MCUs" #endif @@ -260,6 +264,9 @@ void print_dwc2_info(dwc2_regs_t * dwc2) dwc2_ghwcfg3_t const * hw_cfg3 = &dwc2->ghwcfg3_bm; dwc2_ghwcfg4_t const * hw_cfg4 = &dwc2->ghwcfg4_bm; + TU_LOG_HEX(DWC2_DEBUG, dwc2->gotgctl); + TU_LOG_HEX(DWC2_DEBUG, dwc2->gusbcfg); + TU_LOG_HEX(DWC2_DEBUG, dwc2->dcfg); TU_LOG_HEX(DWC2_DEBUG, dwc2->guid); TU_LOG_HEX(DWC2_DEBUG, dwc2->gsnpsid); TU_LOG_HEX(DWC2_DEBUG, dwc2->ghwcfg1); @@ -349,23 +356,22 @@ static void phy_fs_init(dwc2_regs_t * dwc2) // Select FS PHY dwc2->gusbcfg |= GUSBCFG_PHYSEL; + // MCU specific PHY init before reset + dwc2_phy_init(dwc2, HS_PHY_TYPE_NONE); + // Reset core after selecting PHY reset_core(dwc2); - // set turn around // USB turnaround time is critical for certification where long cables and 5-Hubs are used. // So if you need the AHB to run at less than 30 MHz, and if USB turnaround time is not critical, - // these bits can be programmed to a larger value. - //TU_LOG_INT(DWC2_DEBUG, (dwc2->gusbcfg & GUSBCFG_TRDT_Msk) >> GUSBCFG_TRDT_Pos ); - dwc2_phyfs_set_turnaround(dwc2); + // these bits can be programmed to a larger value. Default is 5 + dwc2->gusbcfg = (dwc2->gusbcfg & ~GUSBCFG_TRDT_Msk) | (5u << GUSBCFG_TRDT_Pos); + + // MCU specific PHY update post reset + dwc2_phy_update(dwc2, HS_PHY_TYPE_NONE); // set max speed dwc2->dcfg = (dwc2->dcfg & ~DCFG_DSPD_Msk) | (DCFG_DSPD_FS << DCFG_DSPD_Pos); - - #if defined(DCD_ATTR_DWC2_STM32) - // activate FS PHY on stm32 - dwc2->stm32_gccfg |= STM32_GCCFG_PWRDWN; - #endif } static void phy_hs_init(dwc2_regs_t * dwc2) @@ -399,19 +405,13 @@ static void phy_hs_init(dwc2_regs_t * dwc2) // Set 16-bit interface if supported if (dwc2->ghwcfg4_bm.utmi_phy_data_width) gusbcfg |= GUSBCFG_PHYIF16; - - #if defined(DCD_ATTR_DWC2_STM32) && defined(USB_HS_PHYC) - dwc2_stm32_utmi_phy_init(dwc2); - #endif } // Apply config dwc2->gusbcfg = gusbcfg; - #if defined(DCD_ATTR_DWC2_STM32) - // Disable STM32 FS PHY - dwc2->stm32_gccfg &= ~STM32_GCCFG_PWRDWN; - #endif + // mcu specific phy init + dwc2_phy_init(dwc2, dwc2->ghwcfg2_bm.hs_phy_type); // Reset core after selecting PHY reset_core(dwc2); @@ -421,7 +421,10 @@ static void phy_hs_init(dwc2_regs_t * dwc2) // - 5 if using 16-bit PHY interface gusbcfg &= ~GUSBCFG_TRDT_Msk; gusbcfg |= (dwc2->ghwcfg4_bm.utmi_phy_data_width ? 5u : 9u) << GUSBCFG_TRDT_Pos; - dwc2->gusbcfg = gusbcfg; // Apply config + dwc2->gusbcfg = gusbcfg; + + // MCU specific PHY update post reset + dwc2_phy_update(dwc2, dwc2->ghwcfg2_bm.hs_phy_type); // Set max speed dwc2->dcfg = (dwc2->dcfg & ~DCFG_DSPD_Msk) | (DCFG_DSPD_HS << DCFG_DSPD_Pos); @@ -429,16 +432,16 @@ static void phy_hs_init(dwc2_regs_t * dwc2) static bool check_dwc2(dwc2_regs_t * dwc2) { +#if CFG_TUSB_DEBUG >= DWC2_DEBUG + print_dwc2_info(dwc2); +#endif + // For some reasons: GD32VF103 snpsid and all hwcfg register are always zero (skip it) #if !TU_CHECK_MCU(OPT_MCU_GD32VF103) uint32_t const gsnpsid = dwc2->gsnpsid & GSNPSID_ID_MASK; TU_ASSERT(gsnpsid == DWC2_OTG_ID || gsnpsid == DWC2_FS_IOT_ID || gsnpsid == DWC2_HS_IOT_ID); #endif -#if CFG_TUSB_DEBUG >= DWC2_DEBUG - print_dwc2_info(dwc2); -#endif - return true; } @@ -451,8 +454,10 @@ void dcd_init (uint8_t rhport) // Check Synopsys ID register, failed if controller clock/power is not enabled TU_VERIFY(check_dwc2(dwc2), ); - // Force device mode - dwc2->gusbcfg = (dwc2->gusbcfg & ~GUSBCFG_FHMOD) | GUSBCFG_FDMOD; + dcd_disconnect(rhport); + + // max number of endpoints & total_fifo_size are: + // hw_cfg2->num_dev_ep, hw_cfg2->total_fifo_size if( phy_hs_supported(dwc2) ) { @@ -464,7 +469,11 @@ void dcd_init (uint8_t rhport) phy_fs_init(dwc2); } - TU_LOG_HEX(DWC2_DEBUG, dwc2->gusbcfg); + // Restart PHY clock + dwc2->pcgctl &= ~(PCGCTL_STOPPCLK | PCGCTL_GATEHCLK | PCGCTL_PWRCLMP | PCGCTL_RSTPDWNMODULE); + + // Force device mode + dwc2->gusbcfg = (dwc2->gusbcfg & ~GUSBCFG_FHMOD) | GUSBCFG_FDMOD; /* Set HS/FS Timeout Calibration to 7 (max available value). * The number of PHY clocks that the application programs in @@ -476,27 +485,34 @@ void dcd_init (uint8_t rhport) */ dwc2->gusbcfg |= (7ul << GUSBCFG_TOCAL_Pos); - // Restart PHY clock - dwc2->pcgctl &= ~(PCGCTL_STOPPCLK | PCGCTL_GATEHCLK | PCGCTL_PWRCLMP | PCGCTL_RSTPDWNMODULE); - - // Clear all interrupts - dwc2->gintsts |= dwc2->gintsts; - - // Required as part of core initialization. - // TODO: How should mode mismatch be handled? It will cause - // the core to stop working/require reset. - dwc2->gintmsk |= GINTMSK_OTGINT | GINTMSK_MMISM; - // If USB host misbehaves during status portion of control xfer // (non zero-length packet), send STALL back and discard. dwc2->dcfg |= DCFG_NZLSOHSK; - dwc2->gintmsk |= GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_USBSUSPM | - GINTMSK_WUIM | GINTMSK_RXFLVLM; + // Clear A,B, VBus valid override + dwc2->gotgctl &= ~(GOTGCTL_BVALOEN | GOTGCTL_AVALOEN | GOTGCTL_VBVALOEN); + + // Clear all interrupts + dwc2->gintsts |= dwc2->gintsts; + dwc2->gotgint |= dwc2->gotgint; + + // Required as part of core initialization. + // TODO: How should mode mismatch be handled? It will cause + // the core to stop working/require reset. + dwc2->gintmsk = GINTMSK_OTGINT | GINTMSK_MMISM | GINTMSK_RXFLVLM | + GINTMSK_USBSUSPM | GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_WUIM; // Enable global interrupt dwc2->gahbcfg |= GAHBCFG_GINT; + // make sure we are in device mode +// TU_ASSERT(!(dwc2->gintsts & GINTSTS_CMOD), ); + +// TU_LOG_HEX(DWC2_DEBUG, dwc2->gotgctl); +// TU_LOG_HEX(DWC2_DEBUG, dwc2->gusbcfg); +// TU_LOG_HEX(DWC2_DEBUG, dwc2->dcfg); +// TU_LOG_HEX(DWC2_DEBUG, dwc2->gahbcfg); + dcd_connect(rhport); } @@ -1096,6 +1112,8 @@ void dcd_int_handler(uint8_t rhport) uint32_t const int_status = dwc2->gintsts & dwc2->gintmsk; +// TU_LOG_HEX(DWC2_DEBUG, int_status); + if(int_status & GINTSTS_USBRST) { // USBRST is start of reset. diff --git a/src/portable/synopsys/dwc2/dwc2_bcm.h b/src/portable/synopsys/dwc2/dwc2_bcm.h index c064946cf..38d10930c 100644 --- a/src/portable/synopsys/dwc2/dwc2_bcm.h +++ b/src/portable/synopsys/dwc2/dwc2_bcm.h @@ -51,17 +51,28 @@ static inline void dwc2_dcd_int_disable (uint8_t rhport) BP_DisableIRQ(USB_IRQn); } -TU_ATTR_ALWAYS_INLINE static inline void dwc2_remote_wakeup_delay(void) { // try to delay for 1 ms // TODO implement later } -static inline void dwc2_phyfs_set_turnaround(dwc2_regs_t * dwc2) +// MCU specific PHY init, called BEFORE core reset +static inline void dwc2_phy_init(dwc2_regs_t * dwc2, uint8_t hs_phy_type) { (void) dwc2; - // do nothing since bcm alwyas use HS PHY + (void) hs_phy_type; + + // nothing to do +} + +// MCU specific PHY update, it is called AFTER init() and core reset +static inline void dwc2_phy_update(dwc2_regs_t * dwc2, uint8_t hs_phy_type) +{ + (void) dwc2; + (void) hs_phy_type; + + // nothing to do } #ifdef __cplusplus diff --git a/src/portable/synopsys/dwc2/dwc2_esp32.h b/src/portable/synopsys/dwc2/dwc2_esp32.h index af5d5f093..78da277d5 100644 --- a/src/portable/synopsys/dwc2/dwc2_esp32.h +++ b/src/portable/synopsys/dwc2/dwc2_esp32.h @@ -50,12 +50,14 @@ static void dcd_int_handler_wrap(void* arg) dcd_int_handler(0); } +TU_ATTR_ALWAYS_INLINE static inline void dwc2_dcd_int_enable (uint8_t rhport) { (void) rhport; esp_intr_alloc(ETS_USB_INTR_SOURCE, ESP_INTR_FLAG_LOWMED, dcd_int_handler_wrap, NULL, &usb_ih); } +TU_ATTR_ALWAYS_INLINE static inline void dwc2_dcd_int_disable (uint8_t rhport) { (void) rhport; @@ -67,10 +69,22 @@ static inline void dwc2_remote_wakeup_delay(void) vTaskDelay(pdMS_TO_TICKS(1)); } -static inline void dwc2_phyfs_set_turnaround(dwc2_regs_t * dwc2) +// MCU specific PHY init, called BEFORE core reset +static inline void dwc2_phy_init(dwc2_regs_t * dwc2, uint8_t hs_phy_type) { (void) dwc2; - // keep the reset value which is 5 on this port + (void) hs_phy_type; + + // nothing to do +} + +// MCU specific PHY update, it is called AFTER init() and core reset +static inline void dwc2_phy_update(dwc2_regs_t * dwc2, uint8_t hs_phy_type) +{ + (void) dwc2; + (void) hs_phy_type; + + // nothing to do } #ifdef __cplusplus diff --git a/src/portable/synopsys/dwc2/dwc2_gd32.h b/src/portable/synopsys/dwc2/dwc2_gd32.h index 15e73ad1e..f8fa01ee0 100644 --- a/src/portable/synopsys/dwc2/dwc2_gd32.h +++ b/src/portable/synopsys/dwc2/dwc2_gd32.h @@ -68,7 +68,6 @@ static inline void dwc2_dcd_int_disable (uint8_t rhport) __eclic_disable_interrupt(RHPORT_IRQn); } -TU_ATTR_ALWAYS_INLINE static inline void dwc2_remote_wakeup_delay(void) { // try to delay for 1 ms @@ -76,12 +75,23 @@ static inline void dwc2_remote_wakeup_delay(void) while ( count-- ) __asm volatile ("nop"); } -static inline void dwc2_phyfs_set_turnaround(dwc2_regs_t * dwc2) +// MCU specific PHY init, called BEFORE core reset +static inline void dwc2_phy_init(dwc2_regs_t * dwc2, uint8_t hs_phy_type) { - // use recommeded value 6 by stm32 for mcu with AHB clock > 32Mhz - dwc2->gusbcfg = (dwc2->gusbcfg & GUSBCFG_TRDT_Msk) | (6u << GUSBCFG_TRDT_Pos); + (void) dwc2; + (void) hs_phy_type; + + // nothing to do } +// MCU specific PHY update, it is called AFTER init() and core reset +static inline void dwc2_phy_update(dwc2_regs_t * dwc2, uint8_t hs_phy_type) +{ + (void) dwc2; + (void) hs_phy_type; + + // nothing to do +} #ifdef __cplusplus } diff --git a/src/portable/synopsys/dwc2/dwc2_stm32.h b/src/portable/synopsys/dwc2/dwc2_stm32.h index 4d0ed3f0a..469045ac4 100644 --- a/src/portable/synopsys/dwc2/dwc2_stm32.h +++ b/src/portable/synopsys/dwc2/dwc2_stm32.h @@ -112,78 +112,91 @@ static inline void dwc2_remote_wakeup_delay(void) while ( count-- ) __NOP(); } -// Set turn-around timeout according to link speed -static inline void dwc2_phyfs_set_turnaround(dwc2_regs_t * dwc2) +// MCU specific PHY init, called BEFORE core reset +static inline void dwc2_phy_init(dwc2_regs_t * dwc2, uint8_t hs_phy_type) { - // Turnaround timeout depends on the AHB clock dictated by STM32 Reference Manual - uint32_t turnaround; - - if ( SystemCoreClock >= 32000000U ) - turnaround = 0x6u; - else if ( SystemCoreClock >= 27500000U ) - turnaround = 0x7u; - else if ( SystemCoreClock >= 24000000U ) - turnaround = 0x8u; - else if ( SystemCoreClock >= 21800000U ) - turnaround = 0x9u; - else if ( SystemCoreClock >= 20000000U ) - turnaround = 0xAu; - else if ( SystemCoreClock >= 18500000U ) - turnaround = 0xBu; - else if ( SystemCoreClock >= 17200000U ) - turnaround = 0xCu; - else if ( SystemCoreClock >= 16000000U ) - turnaround = 0xDu; - else if ( SystemCoreClock >= 15000000U ) - turnaround = 0xEu; - else - turnaround = 0xFu; - - dwc2->gusbcfg = (dwc2->gusbcfg & GUSBCFG_TRDT_Msk) | (turnaround << GUSBCFG_TRDT_Pos); -} - -#if defined(USB_HS_PHYC) -static inline void dwc2_stm32_utmi_phy_init(dwc2_regs_t * dwc2) -{ - USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef*) USB_HS_PHYC_CONTROLLER_BASE; - - // Enable UTMI HS PHY - dwc2->stm32_gccfg |= STM32_GCCFG_PHYHSEN; - - // Enable LDO - usb_hs_phyc->USB_HS_PHYC_LDO |= USB_HS_PHYC_LDO_ENABLE; - - // Wait until LDO ready - while ( 0 == (usb_hs_phyc->USB_HS_PHYC_LDO & USB_HS_PHYC_LDO_STATUS) ) {} - - uint32_t phyc_pll = 0; - - // TODO Try to get HSE_VALUE from registers instead of depending CFLAGS - switch ( HSE_VALUE ) + if ( hs_phy_type == HS_PHY_TYPE_NONE ) { - case 12000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12MHZ ; break; - case 12500000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12_5MHZ ; break; - case 16000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_16MHZ ; break; - case 24000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_24MHZ ; break; - case 25000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_25MHZ ; break; - case 32000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_Msk ; break; // Value not defined in header - default: - TU_ASSERT(false, ); + // Enable on-chip FS PHY + dwc2->stm32_gccfg |= STM32_GCCFG_PWRDWN; + }else + { + // Disable FS PHY + dwc2->stm32_gccfg &= ~STM32_GCCFG_PWRDWN; + + // Enable on-chip HS PHY + if (hs_phy_type == HS_PHY_TYPE_UTMI || hs_phy_type == HS_PHY_TYPE_UTMI_ULPI) + { +#ifdef USB_HS_PHYC + // Enable UTMI HS PHY + dwc2->stm32_gccfg |= STM32_GCCFG_PHYHSEN; + + // Enable LDO + USB_HS_PHYC->USB_HS_PHYC_LDO |= USB_HS_PHYC_LDO_ENABLE; + + // Wait until LDO ready + while ( 0 == (USB_HS_PHYC->USB_HS_PHYC_LDO & USB_HS_PHYC_LDO_STATUS) ) {} + + uint32_t phyc_pll = 0; + + // TODO Try to get HSE_VALUE from registers instead of depending CFLAGS + switch ( HSE_VALUE ) + { + case 12000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12MHZ ; break; + case 12500000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12_5MHZ ; break; + case 16000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_16MHZ ; break; + case 24000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_24MHZ ; break; + case 25000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_25MHZ ; break; + case 32000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_Msk ; break; // Value not defined in header + default: + TU_ASSERT(false, ); + } + USB_HS_PHYC->USB_HS_PHYC_PLL = phyc_pll; + + // Control the tuning interface of the High Speed PHY + // Use magic value (USB_HS_PHYC_TUNE_VALUE) from ST driver for F7 + USB_HS_PHYC->USB_HS_PHYC_TUNE |= 0x00000F13U; + + // Enable PLL internal PHY + USB_HS_PHYC->USB_HS_PHYC_PLL |= USB_HS_PHYC_PLL_PLLEN; +#endif + } } - usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll; - - // Control the tuning interface of the High Speed PHY - // Use magic value (USB_HS_PHYC_TUNE_VALUE) from ST driver - usb_hs_phyc->USB_HS_PHYC_TUNE |= 0x00000F13U; - - // Enable PLL internal PHY - usb_hs_phyc->USB_HS_PHYC_PLL |= USB_HS_PHYC_PLL_PLLEN; - - // Original ST code has 2 ms delay for PLL stabilization. - // Primitive test shows that more than 10 USB un/replug cycle showed no error with enumeration } -#endif +// MCU specific PHY update, it is called AFTER init() and core reset +static inline void dwc2_phy_update(dwc2_regs_t * dwc2, uint8_t hs_phy_type) +{ + // used to set turnaround time for fullspeed, nothing to do in highspeed mode + if ( hs_phy_type == HS_PHY_TYPE_NONE ) + { + // Turnaround timeout depends on the AHB clock dictated by STM32 Reference Manual + uint32_t turnaround; + + if ( SystemCoreClock >= 32000000u ) + turnaround = 0x6u; + else if ( SystemCoreClock >= 27500000u ) + turnaround = 0x7u; + else if ( SystemCoreClock >= 24000000u ) + turnaround = 0x8u; + else if ( SystemCoreClock >= 21800000u ) + turnaround = 0x9u; + else if ( SystemCoreClock >= 20000000u ) + turnaround = 0xAu; + else if ( SystemCoreClock >= 18500000u ) + turnaround = 0xBu; + else if ( SystemCoreClock >= 17200000u ) + turnaround = 0xCu; + else if ( SystemCoreClock >= 16000000u ) + turnaround = 0xDu; + else if ( SystemCoreClock >= 15000000u ) + turnaround = 0xEu; + else + turnaround = 0xFu; + + dwc2->gusbcfg = (dwc2->gusbcfg & ~GUSBCFG_TRDT_Msk) | (turnaround << GUSBCFG_TRDT_Pos); + } +} #ifdef __cplusplus } diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 7b3db4dd9..583a7274a 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -528,7 +528,7 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define GUSBCFG_PHYSEL_Pos (6U) #define GUSBCFG_PHYSEL_Msk (0x1UL << GUSBCFG_PHYSEL_Pos) // 0x00000040 */ #define GUSBCFG_PHYSEL GUSBCFG_PHYSEL_Msk // USB 2.0 high-speed ULPI PHY or USB 1.1 full-speed serial transceiver select */ -#define GUSBCFG_DDRSEL TU_BIT(7) // Single Data Rate (SDR) or Double Data Rate (DDR) or ULPI interface. +#define GUSBCFG_DDRSEL TU_BIT(7) // Single Data Rate (SDR) or Double Data Rate (DDR) or ULPI interface. #define GUSBCFG_SRPCAP_Pos (8U) #define GUSBCFG_SRPCAP_Msk (0x1UL << GUSBCFG_SRPCAP_Pos) // 0x00000100 */ #define GUSBCFG_SRPCAP GUSBCFG_SRPCAP_Msk // SRP-capable */ diff --git a/src/tusb_option.h b/src/tusb_option.h index de0279dda..4da07e241 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -113,8 +113,6 @@ // Silabs #define OPT_MCU_EFM32GG 1300 ///< Silabs EFM32GG -#define OPT_MCU_EFM32GG11 1301 ///< Silabs EFM32GG11 -#define OPT_MCU_EFM32GG12 1302 ///< Silabs EFM32GG12 // Renesas RX #define OPT_MCU_RX63X 1400 ///< Renesas RX63N/631 From b85a6898af6fb75d5e877d418748a22c92a6d7bf Mon Sep 17 00:00:00 2001 From: hathach Date: Sat, 30 Oct 2021 20:45:58 +0700 Subject: [PATCH 37/51] remove dcd_efm32 --- src/portable/silabs/efm32/dcd_efm32.c | 936 ------------------------ src/portable/synopsys/dwc2/dwc2_efm32.h | 87 +++ 2 files changed, 87 insertions(+), 936 deletions(-) delete mode 100644 src/portable/silabs/efm32/dcd_efm32.c create mode 100644 src/portable/synopsys/dwc2/dwc2_efm32.h diff --git a/src/portable/silabs/efm32/dcd_efm32.c b/src/portable/silabs/efm32/dcd_efm32.c deleted file mode 100644 index ccae113a3..000000000 --- a/src/portable/silabs/efm32/dcd_efm32.c +++ /dev/null @@ -1,936 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2021 Rafael Silva (@perigoso) - * 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. - */ - -#include "tusb_option.h" - -#if TUSB_OPT_DEVICE_ENABLED && ( \ - (CFG_TUSB_MCU == OPT_MCU_EFM32GG) || \ - (CFG_TUSB_MCU == OPT_MCU_EFM32GG11) || \ - (CFG_TUSB_MCU == OPT_MCU_EFM32GG12) ) - -/* Silabs */ -#include "em_device.h" - -#include "device/dcd.h" - -/* - * Since TinyUSB doesn't use SOF for now, and this interrupt too often (1ms interval) - * We disable SOF for now until needed later on - */ -#define USE_SOF 0 - -/* - * Number of endpoints - * 12 software-configurable endpoints (6 IN, 6 OUT) in addition to endpoint 0 - */ -#define EP_COUNT 7 - -/* FIFO size in bytes */ -#define EP_FIFO_SIZE 2048 - -/* Max number of IN EP FIFOs */ -#define EP_FIFO_NUM 7 - -/* */ -typedef struct { - uint8_t *buffer; - uint16_t total_len; - uint16_t queued_len; - uint16_t max_size; - bool short_packet; -} xfer_ctl_t; - -static uint32_t _setup_packet[2]; - -#define XFER_CTL_BASE(_ep, _dir) &xfer_status[_ep][_dir] -static xfer_ctl_t xfer_status[EP_COUNT][2]; - -/* Keep count of how many FIFOs are in use */ -static uint8_t _allocated_fifos = 1; /* FIFO0 is always in use */ - -static volatile uint32_t* tx_fifo[EP_FIFO_NUM] = { - USB->FIFO0D, - USB->FIFO1D, - USB->FIFO2D, - USB->FIFO3D, - USB->FIFO4D, - USB->FIFO5D, - USB->FIFO6D, -}; - -/* Register Helpers */ -#define DCTL_WO_BITMASK (USB_DCTL_CGOUTNAK | USB_DCTL_SGOUTNAK | USB_DCTL_CGNPINNAK | USB_DCTL_SGNPINNAK) -#define GUSBCFG_WO_BITMASK (USB_GUSBCFG_CORRUPTTXPKT) -#define DEPCTL_WO_BITMASK (USB_DIEP_CTL_CNAK | USB_DIEP_CTL_SNAK | USB_DIEP_CTL_SETD0PIDEF | USB_DIEP_CTL_SETD1PIDOF) - -/* Will either return an unused FIFO number, or 0 if all are used. */ -static uint8_t get_free_fifo(void) -{ - if(_allocated_fifos < EP_FIFO_NUM) return _allocated_fifos++; - return 0; -} - -/* -static void flush_rx_fifo(void) -{ - USB->GRSTCTL = USB_GRSTCTL_RXFFLSH; - while(USB->GRSTCTL & USB_GRSTCTL_RXFFLSH); -} -*/ - -static void flush_tx_fifo(uint8_t fifo_num) -{ - USB->GRSTCTL = USB_GRSTCTL_TXFFLSH | (fifo_num << _USB_GRSTCTL_TXFNUM_SHIFT); - while(USB->GRSTCTL & USB_GRSTCTL_TXFFLSH); -} - -/* Setup the control endpoint 0. */ -static void bus_reset(void) -{ - USB->DOEP0CTL |= USB_DIEP_CTL_SNAK; - for(uint8_t i = 0; i < EP_COUNT - 1; i++) - { - USB->DOEP[i].CTL |= USB_DIEP_CTL_SNAK; - } - - /* reset address */ - USB->DCFG &= ~_USB_DCFG_DEVADDR_MASK; - - USB->DAINTMSK |= USB_DAINTMSK_OUTEPMSK0 | USB_DAINTMSK_INEPMSK0; - USB->DOEPMSK |= USB_DOEPMSK_SETUPMSK | USB_DOEPMSK_XFERCOMPLMSK; - USB->DIEPMSK |= USB_DIEPMSK_TIMEOUTMSK | USB_DIEPMSK_XFERCOMPLMSK; - - /* - * - All EP OUT shared a unique OUT FIFO which uses - * * 10 locations in hardware for setup packets + setup control words (up to 3 setup packets). - * * 2 locations for OUT endpoint control words. - * * 16 for largest packet size of 64 bytes. ( TODO Highspeed is 512 bytes) - * * 1 location for global NAK (not required/used here). - * * It is recommended to allocate 2 times the largest packet size, therefore - * Recommended value = 10 + 1 + 2 x (16+2) = 47 --> Let's make it 52 - */ - flush_tx_fifo(_USB_GRSTCTL_TXFNUM_FALL); // Flush All - USB->GRXFSIZ = 52; - - /* Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) */ - USB->GNPTXFSIZ = (16 << _USB_GNPTXFSIZ_NPTXFINEPTXF0DEP_SHIFT) | (USB->GRXFSIZ & _USB_GNPTXFSIZ_NPTXFSTADDR_MASK); - - /* Ready to receive SETUP packet */ - USB->DOEP0TSIZ |= (1 << _USB_DOEP0TSIZ_SUPCNT_SHIFT); - - USB->GINTMSK |= USB_GINTMSK_IEPINTMSK | USB_GINTMSK_OEPINTMSK; -} - -static void enum_done_processing(void) -{ - /* Maximum packet size for EP 0 is set for both directions by writing DIEPCTL */ - if((USB->DSTS & _USB_DSTS_ENUMSPD_MASK) == USB_DSTS_ENUMSPD_FS) - { - /* Full Speed (PHY on 48 MHz) */ - USB->DOEP0CTL = (USB->DOEP0CTL & ~_USB_DOEP0CTL_MPS_MASK) | _USB_DOEP0CTL_MPS_64B; /* Maximum Packet Size 64 bytes */ - USB->DOEP0CTL &= ~_USB_DOEP0CTL_STALL_MASK; /* clear Stall */ - xfer_status[0][TUSB_DIR_OUT].max_size = 64; - xfer_status[0][TUSB_DIR_IN].max_size = 64; - } - else - { - /* Low Speed (PHY on 6 MHz) */ - USB->DOEP0CTL = (USB->DOEP0CTL & ~_USB_DOEP0CTL_MPS_MASK) | _USB_DOEP0CTL_MPS_8B; /* Maximum Packet Size 64 bytes */ - USB->DOEP0CTL &= ~_USB_DOEP0CTL_STALL_MASK; /* clear Stall */ - xfer_status[0][TUSB_DIR_OUT].max_size = 8; - xfer_status[0][TUSB_DIR_IN].max_size = 8; - } -} - - -/*------------------------------------------------------------------*/ -/* Controller API */ -/*------------------------------------------------------------------*/ -void dcd_init(uint8_t rhport) -{ - (void) rhport; - - /* Reset Core */ - USB->PCGCCTL &= ~USB_PCGCCTL_STOPPCLK; - USB->PCGCCTL &= ~(USB_PCGCCTL_PWRCLMP | USB_PCGCCTL_RSTPDWNMODULE); - - /* Core Soft Reset */ - USB->GRSTCTL |= USB_GRSTCTL_CSFTRST; - while(USB->GRSTCTL & USB_GRSTCTL_CSFTRST); - - while(!(USB->GRSTCTL & USB_GRSTCTL_AHBIDLE)); - - /* Enable PHY pins */ - USB->ROUTE = USB_ROUTE_PHYPEN; - - dcd_disconnect(rhport); - - /* - * Set device speed (Full speed PHY) - * Stall on non-zero len status OUT packets (ctrl transfers) - * periodic frame interval to 80% - */ - USB->DCFG = (USB->DCFG & ~(_USB_DCFG_DEVSPD_MASK | _USB_DCFG_PERFRINT_MASK)) | USB_DCFG_DEVSPD_FS | USB_DCFG_NZSTSOUTHSHK; - - /* Enable Global Interrupts */ - USB->GAHBCFG = (USB->GAHBCFG & ~_USB_GAHBCFG_HBSTLEN_MASK) | USB_GAHBCFG_GLBLINTRMSK; - - /* Force Device Mode */ - USB->GUSBCFG = (USB->GUSBCFG & ~(GUSBCFG_WO_BITMASK | USB_GUSBCFG_FORCEHSTMODE)) | USB_GUSBCFG_FORCEDEVMODE; - - /* No Overrides */ - USB->GOTGCTL &= ~(USB_GOTGCTL_BVALIDOVVAL | USB_GOTGCTL_BVALIDOVEN | USB_GOTGCTL_VBVALIDOVVAL); - - /* Ignore frame numbers on ISO transfers. */ - USB->DCTL = (USB->DCTL & ~DCTL_WO_BITMASK) | USB_DCTL_IGNRFRMNUM; - - /* Setting SNAKs */ - USB->DOEP0CTL |= USB_DIEP_CTL_SNAK; - for(uint8_t i = 0; i < EP_COUNT - 1; i++) - { - USB->DOEP[i].CTL |= USB_DIEP_CTL_SNAK; - } - - /* D. Interruption masking */ - /* Disable all device interrupts */ - USB->DIEPMSK = 0; - USB->DOEPMSK = 0; - USB->DAINTMSK = 0; - USB->DIEPEMPMSK = 0; - USB->GINTMSK = 0; - USB->GOTGINT = ~0U; /* clear OTG ints */ - USB->GINTSTS = ~0U; /* clear pending ints */ - USB->GINTMSK = USB_GINTMSK_MODEMISMSK | - #if USE_SOF - USB_GINTMSK_SOFMSK | - #endif - USB_GINTMSK_ERLYSUSPMSK | - USB_GINTMSK_USBSUSPMSK | - USB_GINTMSK_USBRSTMSK | - USB_GINTMSK_ENUMDONEMSK | - USB_GINTMSK_RESETDETMSK | - USB_GINTMSK_DISCONNINTMSK; - - NVIC_ClearPendingIRQ(USB_IRQn); - - dcd_connect(rhport); -} - -void dcd_set_address(uint8_t rhport, uint8_t dev_addr) -{ - (void) rhport; - - USB->DCFG = (USB->DCFG & ~_USB_DCFG_DEVADDR_MASK) | (dev_addr << _USB_DCFG_DEVADDR_SHIFT); - - /* Response with status after changing device address */ - dcd_edpt_xfer(rhport, tu_edpt_addr(0, TUSB_DIR_IN), NULL, 0); -} - -void dcd_remote_wakeup(uint8_t rhport) -{ - (void) rhport; -} - -void dcd_connect(uint8_t rhport) -{ - (void) rhport; - - /* connect by enabling internal pull-up resistor on D+/D- */ - USB->DCTL &= ~(DCTL_WO_BITMASK | USB_DCTL_SFTDISCON); -} - -void dcd_disconnect(uint8_t rhport) -{ - (void) rhport; - - /* disconnect by disabling internal pull-up resistor on D+/D- */ - USB->DCTL = (USB->DCTL & ~(DCTL_WO_BITMASK)) | USB_DCTL_SFTDISCON; -} - -/*------------------------------------------------------------------*/ -/* DCD Endpoint Port */ -/*------------------------------------------------------------------*/ -void dcd_edpt_stall(uint8_t rhport, uint8_t ep_addr) -{ - (void) rhport; - - uint8_t const epnum = tu_edpt_number(ep_addr); - uint8_t const dir = tu_edpt_dir(ep_addr); - - if(dir == TUSB_DIR_IN) - { - if(epnum == 0) - { - USB->DIEP0CTL = (USB->DIEP0CTL & ~DEPCTL_WO_BITMASK) | USB_DIEP0CTL_SNAK | USB_DIEP0CTL_STALL; - - flush_tx_fifo(_USB_GRSTCTL_TXFNUM_F0); - } - else - { - /* Only disable currently enabled non-control endpoint */ - if(USB->DIEP[epnum - 1].CTL & USB_DIEP_CTL_EPENA) - { - USB->DIEP[epnum - 1].CTL = (USB->DIEP[epnum - 1].CTL & ~DEPCTL_WO_BITMASK) | USB_DIEP_CTL_EPDIS | USB_DIEP_CTL_SNAK | USB_DIEP_CTL_STALL; - while(!(USB->DIEP[epnum - 1].INT & USB_DIEP_INT_EPDISBLD)); - USB->DIEP[epnum - 1].INT |= USB_DIEP_INT_EPDISBLD; - } - else - { - USB->DIEP[epnum - 1].CTL = (USB->DIEP[epnum - 1].CTL & ~DEPCTL_WO_BITMASK) | USB_DIEP_CTL_SNAK | USB_DIEP_CTL_STALL; - } - - /* Flush the FIFO */ - uint8_t const fifo_num = ((USB->DIEP[epnum - 1].CTL & _USB_DIEP_CTL_TXFNUM_MASK) >> _USB_DIEP_CTL_TXFNUM_SHIFT); - flush_tx_fifo(fifo_num); - } - } - else - { - if(epnum == 0) - { - USB->DOEP0CTL = (USB->DOEP0CTL & ~DEPCTL_WO_BITMASK) | USB_DIEP0CTL_STALL; - } - else - { - /* Only disable currently enabled non-control endpoint */ - if(USB->DOEP[epnum - 1].CTL & USB_DIEP_CTL_EPENA) - { - /* Asserting GONAK is required to STALL an OUT endpoint. */ - USB->DCTL |= USB_DCTL_SGOUTNAK; - while(!(USB->GINTSTS & USB_GINTSTS_GOUTNAKEFF)); - - /* Disable the endpoint. Note that only STALL and not SNAK is set here. */ - USB->DOEP[epnum - 1].CTL = (USB->DOEP[epnum - 1].CTL & ~DEPCTL_WO_BITMASK) | USB_DIEP_CTL_EPDIS | USB_DIEP_CTL_STALL; - while(USB->DOEP[epnum - 1].INT & USB_DIEP_INT_EPDISBLD); - USB->DOEP[epnum - 1].INT |= USB_DIEP_INT_EPDISBLD; - - /* Allow other OUT endpoints to keep receiving. */ - USB->DCTL |= USB_DCTL_CGOUTNAK; - } - else - { - USB->DIEP[epnum - 1].CTL = (USB->DIEP[epnum - 1].CTL & ~DEPCTL_WO_BITMASK) | USB_DIEP_CTL_STALL; - } - } - } -} - -void dcd_edpt_clear_stall(uint8_t rhport, uint8_t ep_addr) -{ - (void) rhport; - - uint8_t const epnum = tu_edpt_number(ep_addr); - uint8_t const dir = tu_edpt_dir(ep_addr); - - if(dir == TUSB_DIR_IN) - { - if(epnum == 0) - { - USB->DIEP0CTL &= ~(DEPCTL_WO_BITMASK | USB_DIEP0CTL_STALL); - } - else - { - USB->DIEP[epnum - 1].CTL &= ~(DEPCTL_WO_BITMASK | USB_DIEP_CTL_STALL); - - /* Required by USB spec to reset DATA toggle bit to DATA0 on interrupt and bulk endpoints. */ - uint8_t eptype = (USB->DIEP[epnum - 1].CTL & _USB_DIEP_CTL_EPTYPE_MASK) >> _USB_DIEP_CTL_EPTYPE_SHIFT; - - if((eptype == _USB_DIEP_CTL_EPTYPE_BULK) || (eptype == _USB_DIEP_CTL_EPTYPE_INT)) - { - USB->DIEP[epnum - 1].CTL |= USB_DIEP_CTL_SETD0PIDEF; - } - } - } - else - { - if(epnum == 0) - { - USB->DOEP0CTL &= ~(DEPCTL_WO_BITMASK | USB_DOEP0CTL_STALL); - } - else - { - USB->DOEP[epnum - 1].CTL &= ~(DEPCTL_WO_BITMASK | USB_DOEP_CTL_STALL); - - /* Required by USB spec to reset DATA toggle bit to DATA0 on interrupt and bulk endpoints. */ - uint8_t eptype = (USB->DOEP[epnum - 1].CTL & _USB_DOEP_CTL_EPTYPE_MASK) >> _USB_DOEP_CTL_EPTYPE_SHIFT; - - if((eptype == _USB_DOEP_CTL_EPTYPE_BULK) || (eptype == _USB_DOEP_CTL_EPTYPE_INT)) - { - USB->DOEP[epnum - 1].CTL |= USB_DOEP_CTL_SETD0PIDEF; - } - } - } -} - -bool dcd_edpt_open(uint8_t rhport, tusb_desc_endpoint_t const * p_endpoint_desc) -{ - (void)rhport; - - uint8_t const epnum = tu_edpt_number(p_endpoint_desc->bEndpointAddress); - uint8_t const dir = tu_edpt_dir(p_endpoint_desc->bEndpointAddress); - - TU_ASSERT(epnum < EP_COUNT); - TU_ASSERT(epnum != 0); - - xfer_ctl_t *xfer = XFER_CTL_BASE(epnum, dir); - xfer->max_size = tu_edpt_packet_size(p_endpoint_desc); - - if(dir == TUSB_DIR_OUT) - { - USB->DOEP[epnum - 1].CTL |= USB_DOEP_CTL_USBACTEP | - (p_endpoint_desc->bmAttributes.xfer << _USB_DOEP_CTL_EPTYPE_SHIFT) | - (xfer->max_size << _USB_DOEP_CTL_MPS_SHIFT); - USB->DAINTMSK |= (1 << (_USB_DAINTMSK_OUTEPMSK0_SHIFT + epnum)); - } - else - { - uint8_t fifo_num = get_free_fifo(); - TU_ASSERT(fifo_num != 0); - - USB->DIEP[epnum - 1].CTL &= ~(_USB_DIEP_CTL_TXFNUM_MASK | _USB_DIEP_CTL_EPTYPE_MASK | USB_DIEP_CTL_SETD0PIDEF | _USB_DIEP_CTL_MPS_MASK); - USB->DIEP[epnum - 1].CTL |= USB_DIEP_CTL_USBACTEP | - (fifo_num << _USB_DIEP_CTL_TXFNUM_SHIFT) | - (p_endpoint_desc->bmAttributes.xfer << _USB_DIEP_CTL_EPTYPE_SHIFT) | - ((p_endpoint_desc->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS) ? USB_DIEP_CTL_SETD0PIDEF : 0) | - (xfer->max_size << 0); - - USB->DAINTMSK |= (1 << epnum); - - /* Both TXFD and TXSA are in unit of 32-bit words. */ - /* IN FIFO 0 was configured during enumeration, hence the "+ 16". */ - uint16_t const allocated_size = (USB->GRXFSIZ & _USB_GRXFSIZ_RXFDEP_MASK) + 16; - uint16_t const fifo_size = (EP_FIFO_SIZE/4 - allocated_size) / (EP_FIFO_NUM-1); - uint32_t const fifo_offset = allocated_size + fifo_size*(fifo_num-1); - - /* DIEPTXF starts at FIFO #1. */ - volatile uint32_t* usb_dieptxf = &USB->DIEPTXF1; - usb_dieptxf[epnum - 1] = (fifo_size << _USB_DIEPTXF1_INEPNTXFDEP_SHIFT) | fifo_offset; - } - return true; -} - -void dcd_edpt_close_all (uint8_t rhport) -{ - (void) rhport; - // TODO implement dcd_edpt_close_all() -} - -bool dcd_edpt_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, uint16_t total_bytes) -{ - (void)rhport; - - uint8_t const epnum = tu_edpt_number(ep_addr); - uint8_t const dir = tu_edpt_dir(ep_addr); - - xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); - xfer->buffer = buffer; - xfer->total_len = total_bytes; - xfer->queued_len = 0; - xfer->short_packet = false; - - uint16_t num_packets = (total_bytes / xfer->max_size); - uint8_t short_packet_size = total_bytes % xfer->max_size; - - // Zero-size packet is special case. - if(short_packet_size > 0 || (total_bytes == 0)) - { - num_packets++; - } - - // IN and OUT endpoint xfers are interrupt-driven, we just schedule them - // here. - if(dir == TUSB_DIR_IN) - { - if(epnum == 0) - { - // A full IN transfer (multiple packets, possibly) triggers XFRC. - USB->DIEP0TSIZ = (num_packets << _USB_DIEP0TSIZ_PKTCNT_SHIFT) | total_bytes; - USB->DIEP0CTL |= USB_DIEP0CTL_EPENA | USB_DIEP0CTL_CNAK; // Enable | CNAK - } - else - { - // A full IN transfer (multiple packets, possibly) triggers XFRC. - USB->DIEP[epnum - 1].TSIZ = (num_packets << _USB_DIEP_TSIZ_PKTCNT_SHIFT) | total_bytes; - USB->DIEP[epnum - 1].CTL |= USB_DIEP_CTL_EPENA | USB_DIEP_CTL_CNAK; // Enable | CNAK - } - - // Enable fifo empty interrupt only if there are something to put in the fifo. - if(total_bytes != 0) - { - USB->DIEPEMPMSK |= (1 << epnum); - } - } - else - { - if(epnum == 0) - { - // A full IN transfer (multiple packets, possibly) triggers XFRC. - USB->DOEP0TSIZ |= (1 << _USB_DOEP0TSIZ_PKTCNT_SHIFT) | ((xfer->max_size & _USB_DOEP0TSIZ_XFERSIZE_MASK) << _USB_DOEP0TSIZ_XFERSIZE_SHIFT); - USB->DOEP0CTL |= USB_DOEP0CTL_EPENA | USB_DOEP0CTL_CNAK; - } - else - { - // A full IN transfer (multiple packets, possibly) triggers XFRC. - USB->DOEP[epnum - 1].TSIZ |= (1 << _USB_DOEP_TSIZ_PKTCNT_SHIFT) | ((xfer->max_size & _USB_DOEP_TSIZ_XFERSIZE_MASK) << _USB_DOEP_TSIZ_XFERSIZE_SHIFT); - USB->DOEP[epnum - 1].CTL |= USB_DOEP_CTL_EPENA | USB_DOEP_CTL_CNAK; - } - } - return true; -} - -/*------------------------------------------------------------------*/ -/* IRQ */ -/*------------------------------------------------------------------*/ -void dcd_int_enable(uint8_t rhport) -{ - (void) rhport; - - NVIC_EnableIRQ(USB_IRQn); -} - -void dcd_int_disable(uint8_t rhport) -{ - (void) rhport; - - NVIC_DisableIRQ(USB_IRQn); -} - -static void receive_packet(xfer_ctl_t *xfer, uint16_t xfer_size) -{ - uint16_t remaining = xfer->total_len - xfer->queued_len; - uint16_t to_recv_size; - - if(remaining <= xfer->max_size) - { - /* Avoid buffer overflow. */ - to_recv_size = (xfer_size > remaining) ? remaining : xfer_size; - } - else - { - /* Room for full packet, choose recv_size based on what the microcontroller claims. */ - to_recv_size = (xfer_size > xfer->max_size) ? xfer->max_size : xfer_size; - } - - uint8_t to_recv_rem = to_recv_size % 4; - uint16_t to_recv_size_aligned = to_recv_size - to_recv_rem; - - /* Do not assume xfer buffer is aligned. */ - uint8_t *base = (xfer->buffer + xfer->queued_len); - - /* This for loop always runs at least once- skip if less than 4 bytes to collect. */ - if(to_recv_size >= 4) - { - for(uint16_t i = 0; i < to_recv_size_aligned; i += 4) - { - uint32_t tmp = (*USB->FIFO0D); - base[i] = tmp & 0x000000FF; - base[i + 1] = (tmp & 0x0000FF00) >> 8; - base[i + 2] = (tmp & 0x00FF0000) >> 16; - base[i + 3] = (tmp & 0xFF000000) >> 24; - } - } - - /* Do not read invalid bytes from RX FIFO. */ - if(to_recv_rem != 0) - { - uint32_t tmp = (*USB->FIFO0D); - uint8_t *last_32b_bound = base + to_recv_size_aligned; - - last_32b_bound[0] = tmp & 0x000000FF; - if(to_recv_rem > 1) - { - last_32b_bound[1] = (tmp & 0x0000FF00) >> 8; - } - if(to_recv_rem > 2) - { - last_32b_bound[2] = (tmp & 0x00FF0000) >> 16; - } - } - - xfer->queued_len += xfer_size; - - /* Per USB spec, a short OUT packet (including length 0) is always */ - /* indicative of the end of a transfer (at least for ctl, bulk, int). */ - xfer->short_packet = (xfer_size < xfer->max_size); -} - -static void transmit_packet(xfer_ctl_t *xfer, uint8_t fifo_num) -{ - uint16_t remaining; - if(fifo_num == 0) - { - remaining = (USB->DIEP0TSIZ & 0x7FFFFU) >> _USB_DIEP0TSIZ_XFERSIZE_SHIFT; - } - else - { - remaining = (USB->DIEP[fifo_num - 1].TSIZ & 0x7FFFFU) >> _USB_DIEP_TSIZ_XFERSIZE_SHIFT; - } - xfer->queued_len = xfer->total_len - remaining; - - uint16_t to_xfer_size = (remaining > xfer->max_size) ? xfer->max_size : remaining; - uint8_t to_xfer_rem = to_xfer_size % 4; - uint16_t to_xfer_size_aligned = to_xfer_size - to_xfer_rem; - - /* Buffer might not be aligned to 32b, so we need to force alignment by copying to a temp var. */ - uint8_t *base = (xfer->buffer + xfer->queued_len); - - /* This for loop always runs at least once- skip if less than 4 bytes to send off. */ - if(to_xfer_size >= 4) - { - for(uint16_t i = 0; i < to_xfer_size_aligned; i += 4) - { - uint32_t tmp = base[i] | (base[i + 1] << 8) | (base[i + 2] << 16) | (base[i + 3] << 24); - *tx_fifo[fifo_num] = tmp; - } - } - - /* Do not read beyond end of buffer if not divisible by 4. */ - if(to_xfer_rem != 0) - { - uint32_t tmp = 0; - uint8_t *last_32b_bound = base + to_xfer_size_aligned; - - tmp |= last_32b_bound[0]; - if(to_xfer_rem > 1) - { - tmp |= (last_32b_bound[1] << 8); - } - if(to_xfer_rem > 2) - { - tmp |= (last_32b_bound[2] << 16); - } - - *tx_fifo[fifo_num] = tmp; - } -} - -static void read_rx_fifo(void) -{ - /* - * Pop control word off FIFO (completed xfers will have 2 control words, - * we only pop one ctl word each interrupt). - */ - uint32_t const ctl_word = USB->GRXSTSP; - uint8_t const pktsts = (ctl_word & _USB_GRXSTSP_PKTSTS_MASK) >> _USB_GRXSTSP_PKTSTS_SHIFT; - uint8_t const epnum = (ctl_word & _USB_GRXSTSP_CHNUM_MASK ) >> _USB_GRXSTSP_CHNUM_SHIFT; - uint16_t const bcnt = (ctl_word & _USB_GRXSTSP_BCNT_MASK ) >> _USB_GRXSTSP_BCNT_SHIFT; - - switch(pktsts) - { - case 0x01: /* Global OUT NAK (Interrupt) */ - break; - - case 0x02: - { - /* Out packet recvd */ - xfer_ctl_t *xfer = XFER_CTL_BASE(epnum, TUSB_DIR_OUT); - receive_packet(xfer, bcnt); - } - break; - - case 0x03: - /* Out packet done (Interrupt) */ - break; - - case 0x04: - /* Step 2: Setup transaction completed (Interrupt) */ - /* After this event, OEPINT interrupt will occur with SETUP bit set */ - if(epnum == 0) - { - USB->DOEP0TSIZ |= (1 << _USB_DOEP0TSIZ_SUPCNT_SHIFT); - } - - break; - - case 0x06: - { - /* Step1: Setup data packet received */ - - /* - * We can receive up to three setup packets in succession, but - * only the last one is valid. Therefore we just overwrite it - */ - _setup_packet[0] = (*USB->FIFO0D); - _setup_packet[1] = (*USB->FIFO0D); - } - break; - - default: - /* Invalid, breakpoint. */ - TU_BREAKPOINT(); - break; - } -} - -static void handle_epout_ints(void) -{ - // GINTSTS will be cleared with DAINT == 0 - // DAINT for a given EP clears when DOEPINTx is cleared. - // DOEPINT will be cleared when DAINT's out bits are cleared. - - for(uint8_t n = 0; n < EP_COUNT; n++) - { - xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_OUT); - - if(n == 0) - { - if(USB->DAINT & (1 << (_USB_DAINT_OUTEPINT0_SHIFT + n))) - { - // SETUP packet Setup Phase done. - if((USB->DOEP0INT & USB_DOEP0INT_SETUP)) - { - USB->DOEP0INT = USB_DOEP0INT_STUPPKTRCVD | USB_DOEP0INT_SETUP; // clear - dcd_event_setup_received(0, (uint8_t *)&_setup_packet[0], true); - } - - // OUT XFER complete (single packet).q - if(USB->DOEP0INT & USB_DOEP0INT_XFERCOMPL) - { - USB->DOEP0INT = USB_DOEP0INT_XFERCOMPL; - - // Transfer complete if short packet or total len is transferred - if(xfer->short_packet || (xfer->queued_len == xfer->total_len)) - { - xfer->short_packet = false; - dcd_event_xfer_complete(0, n, xfer->queued_len, XFER_RESULT_SUCCESS, true); - } - else - { - // Schedule another packet to be received. - USB->DOEP0TSIZ |= (1 << _USB_DOEP0TSIZ_PKTCNT_SHIFT) | ((xfer->max_size & _USB_DOEP0TSIZ_XFERSIZE_MASK) << _USB_DOEP0TSIZ_XFERSIZE_SHIFT); - USB->DOEP0CTL |= USB_DOEP0CTL_EPENA | USB_DOEP0CTL_CNAK; - } - } - } - } - else - { - if(USB->DAINT & (1 << (_USB_DAINT_OUTEPINT0_SHIFT + n))) - { - // SETUP packet Setup Phase done. - if((USB->DOEP[n - 1].INT & USB_DOEP_INT_SETUP)) - { - USB->DOEP[n - 1].INT = USB_DOEP_INT_STUPPKTRCVD | USB_DOEP_INT_SETUP; // clear - dcd_event_setup_received(0, (uint8_t *)&_setup_packet[0], true); - } - - // OUT XFER complete (single packet).q - if(USB->DOEP[n - 1].INT & USB_DOEP_INT_XFERCOMPL) - { - USB->DOEP[n - 1].INT = USB_DOEP_INT_XFERCOMPL; - - // Transfer complete if short packet or total len is transferred - if(xfer->short_packet || (xfer->queued_len == xfer->total_len)) - { - xfer->short_packet = false; - dcd_event_xfer_complete(0, n, xfer->queued_len, XFER_RESULT_SUCCESS, true); - } - else - { - // Schedule another packet to be received. - USB->DOEP[n - 1].TSIZ |= (1 << _USB_DOEP_TSIZ_PKTCNT_SHIFT) | ((xfer->max_size & _USB_DOEP_TSIZ_XFERSIZE_MASK) << _USB_DOEP_TSIZ_XFERSIZE_SHIFT); - USB->DOEP[n - 1].CTL |= USB_DOEP_CTL_EPENA | USB_DOEP_CTL_CNAK; - } - } - } - } - } -} - -static void handle_epin_ints(void) -{ - - for(uint32_t n = 0; n < EP_COUNT; n++) - { - xfer_ctl_t *xfer = &xfer_status[n][TUSB_DIR_IN]; - - if(n == 0) - { - if(USB->DAINT & (1 << n)) - { - /* IN XFER complete (entire xfer). */ - if(USB->DIEP0INT & USB_DIEP0INT_XFERCOMPL) - { - USB->DIEP0INT = USB_DIEP0INT_XFERCOMPL; - dcd_event_xfer_complete(0, n | TUSB_DIR_IN_MASK, xfer->total_len, XFER_RESULT_SUCCESS, true); - } - - /* XFER FIFO empty */ - if(USB->DIEP0INT & USB_DIEP0INT_TXFEMP) - { - USB->DIEP0INT = USB_DIEP0INT_TXFEMP; - transmit_packet(xfer, n); - - /* Turn off TXFE if all bytes are written. */ - if(xfer->queued_len == xfer->total_len) - { - USB->DIEPEMPMSK &= ~(1 << n); - } - } - - /* XFER Timeout */ - if(USB->DIEP0INT & USB_DIEP0INT_TIMEOUT) - { - /* Clear interrupt or enpoint will hang. */ - USB->DIEP0INT = USB_DIEP0INT_TIMEOUT; - } - } - } - else - { - if(USB->DAINT & (1 << n)) - { - /* IN XFER complete (entire xfer). */ - if(USB->DIEP[n - 1].INT & USB_DIEP_INT_XFERCOMPL) - { - USB->DIEP[n - 1].INT = USB_DIEP_INT_XFERCOMPL; - dcd_event_xfer_complete(0, n | TUSB_DIR_IN_MASK, xfer->total_len, XFER_RESULT_SUCCESS, true); - } - - /* XFER FIFO empty */ - if(USB->DIEP[n - 1].INT & USB_DIEP_INT_TXFEMP) - { - USB->DIEP[n - 1].INT = USB_DIEP_INT_TXFEMP; - transmit_packet(xfer, n); - - /* Turn off TXFE if all bytes are written. */ - if(xfer->queued_len == xfer->total_len) - { - USB->DIEPEMPMSK &= ~(1 << n); - } - } - - /* XFER Timeout */ - if(USB->DIEP[n - 1].INT & USB_DIEP_INT_TIMEOUT) - { - /* Clear interrupt or enpoint will hang. */ - USB->DIEP[n - 1].INT = USB_DIEP_INT_TIMEOUT; - } - } - } - } -} - -void dcd_int_handler(uint8_t rhport) -{ - (void) rhport; - - const uint32_t int_status = USB->GINTSTS; - - /* USB Reset */ - if(int_status & USB_GINTSTS_USBRST) - { - /* start of reset */ - USB->GINTSTS = USB_GINTSTS_USBRST; - /* FIFOs will be reassigned when the endpoints are reopen */ - _allocated_fifos = 1; - bus_reset(); - } - - /* Reset detected Interrupt */ - if(int_status & USB_GINTSTS_RESETDET) - { - USB->GINTSTS = USB_GINTSTS_RESETDET; - bus_reset(); - } - - /* Enumeration Done */ - if(int_status & USB_GINTSTS_ENUMDONE) - { - /* This interrupt is considered the end of reset. */ - USB->GINTSTS = USB_GINTSTS_ENUMDONE; - enum_done_processing(); - dcd_event_bus_signal(0, DCD_EVENT_BUS_RESET, true); - } - - /* OTG Interrupt */ - if(int_status & USB_GINTSTS_OTGINT) - { - /* OTG INT bit is read-only */ - - uint32_t const otg_int = USB->GOTGINT; - - if(otg_int & USB_GOTGINT_SESENDDET) - { - dcd_event_bus_signal(0, DCD_EVENT_UNPLUGGED, true); - } - - USB->GOTGINT = otg_int; - } - - #if USE_SOF - if(int_status & USB_GINTSTS_SOF) - { - USB->GINTSTS = USB_GINTSTS_SOF; - dcd_event_bus_signal(0, DCD_EVENT_SOF, true); - } - #endif - - /* RxFIFO Non-Empty */ - if(int_status & USB_GINTSTS_RXFLVL) - { - /* RXFLVL bit is read-only */ - - /* Mask out RXFLVL while reading data from FIFO */ - USB->GINTMSK &= ~USB_GINTMSK_RXFLVLMSK; - read_rx_fifo(); - USB->GINTMSK |= USB_GINTMSK_RXFLVLMSK; - } - - /* OUT Endpoints Interrupt */ - if(int_status & USB_GINTMSK_OEPINTMSK) - { - /* OEPINT is read-only */ - handle_epout_ints(); - } - - /* IN Endpoints Interrupt */ - if(int_status & USB_GINTMSK_IEPINTMSK) - { - /* IEPINT bit read-only */ - handle_epin_ints(); - } - - /* unhandled */ - USB->GINTSTS |= USB_GINTSTS_CURMOD | - USB_GINTSTS_MODEMIS | - USB_GINTSTS_OTGINT | - USB_GINTSTS_NPTXFEMP | - USB_GINTSTS_GINNAKEFF | - USB_GINTSTS_GOUTNAKEFF | - USB_GINTSTS_ERLYSUSP | - USB_GINTSTS_USBSUSP | - USB_GINTSTS_ISOOUTDROP | - USB_GINTSTS_EOPF | - USB_GINTSTS_EPMIS | - USB_GINTSTS_INCOMPISOIN | - USB_GINTSTS_INCOMPLP | - USB_GINTSTS_FETSUSP | - USB_GINTSTS_PTXFEMP; -} - -#endif diff --git a/src/portable/synopsys/dwc2/dwc2_efm32.h b/src/portable/synopsys/dwc2/dwc2_efm32.h new file mode 100644 index 000000000..ee4c3c715 --- /dev/null +++ b/src/portable/synopsys/dwc2/dwc2_efm32.h @@ -0,0 +1,87 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2021 Rafael Silva (@perigoso) + * 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 _DWC2_EFM32_H_ +#define _DWC2_EFM32_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#include "em_device.h" + +// EFM32 has custom control register before DWC registers +#define DWC2_REG_BASE (USB_BASE + offsetof(USB_TypeDef, GOTGCTL)) +#define DWC2_EP_MAX 7 +#define DWC2_EP_FIFO_SIZE 2048 + +TU_ATTR_ALWAYS_INLINE +static inline void dwc2_dcd_int_enable(uint8_t rhport) +{ + (void) rhport; + NVIC_EnableIRQ(USB_IRQn); +} + +TU_ATTR_ALWAYS_INLINE +static inline void dwc2_dcd_int_disable (uint8_t rhport) +{ + (void) rhport; + NVIC_DisableIRQ(USB_IRQn); +} + +static inline void dwc2_remote_wakeup_delay(void) +{ + // try to delay for 1 ms +// uint32_t count = SystemCoreClock / 1000; +// while ( count-- ) __NOP(); +} + +// MCU specific PHY init, called BEFORE core reset +static inline void dwc2_phy_init(dwc2_regs_t * dwc2, uint8_t hs_phy_type) +{ + (void) dwc2; + (void) hs_phy_type; + + // Enable PHY + USB->ROUTE = USB_ROUTE_PHYPEN; +} + +// MCU specific PHY update, it is called AFTER init() and core reset +static inline void dwc2_phy_update(dwc2_regs_t * dwc2, uint8_t hs_phy_type) +{ + (void) dwc2; + (void) hs_phy_type; + + // EFM32 Manual: turn around must be 5 (reset & default value) + // dwc2->gusbcfg = (dwc2->gusbcfg & ~GUSBCFG_TRDT_Msk) | (5u << GUSBCFG_TRDT_Pos); +} + +#ifdef __cplusplus +} +#endif + +#endif From 215e0595ab568215a7d0a0c927b076bd02951fa6 Mon Sep 17 00:00:00 2001 From: hathach Date: Sun, 31 Oct 2021 00:09:40 +0700 Subject: [PATCH 38/51] change F207 to use new dwc2 --- hw/bsp/stm32f207nucleo/board.mk | 2 +- hw/bsp/stm32f7/boards/stm32f767nucleo/board.mk | 3 +++ src/portable/synopsys/dwc2/dcd_dwc2.c | 6 +++--- 3 files changed, 7 insertions(+), 4 deletions(-) diff --git a/hw/bsp/stm32f207nucleo/board.mk b/hw/bsp/stm32f207nucleo/board.mk index 2b979f3d8..fa7d28399 100644 --- a/hw/bsp/stm32f207nucleo/board.mk +++ b/hw/bsp/stm32f207nucleo/board.mk @@ -21,7 +21,7 @@ CFLAGS += -Wno-error=sign-compare LD_FILE = hw/bsp/$(BOARD)/STM32F207ZGTx_FLASH.ld SRC_C += \ - src/portable/st/synopsys/dcd_synopsys.c \ + src/portable/synopsys/dwc2/dcd_dwc2.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 \ diff --git a/hw/bsp/stm32f7/boards/stm32f767nucleo/board.mk b/hw/bsp/stm32f7/boards/stm32f767nucleo/board.mk index 2400a4ba7..7710619e5 100644 --- a/hw/bsp/stm32f7/boards/stm32f767nucleo/board.mk +++ b/hw/bsp/stm32f7/boards/stm32f767nucleo/board.mk @@ -8,5 +8,8 @@ CFLAGS += \ LD_FILE = $(BOARD_PATH)/STM32F767ZITx_FLASH.ld SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f767xx.s +# For flash-jlink target +JLINK_DEVICE = stm32f767zi + # flash target using on-board stlink flash: flash-stlink diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 16780cba8..e2a999ac0 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -264,9 +264,9 @@ void print_dwc2_info(dwc2_regs_t * dwc2) dwc2_ghwcfg3_t const * hw_cfg3 = &dwc2->ghwcfg3_bm; dwc2_ghwcfg4_t const * hw_cfg4 = &dwc2->ghwcfg4_bm; - TU_LOG_HEX(DWC2_DEBUG, dwc2->gotgctl); - TU_LOG_HEX(DWC2_DEBUG, dwc2->gusbcfg); - TU_LOG_HEX(DWC2_DEBUG, dwc2->dcfg); +// TU_LOG_HEX(DWC2_DEBUG, dwc2->gotgctl); +// TU_LOG_HEX(DWC2_DEBUG, dwc2->gusbcfg); +// TU_LOG_HEX(DWC2_DEBUG, dwc2->dcfg); TU_LOG_HEX(DWC2_DEBUG, dwc2->guid); TU_LOG_HEX(DWC2_DEBUG, dwc2->gsnpsid); TU_LOG_HEX(DWC2_DEBUG, dwc2->ghwcfg1); From 4ea8f1441dda442d784ee57f39a0adc75bf69e56 Mon Sep 17 00:00:00 2001 From: hathach Date: Sun, 31 Oct 2021 00:19:17 +0700 Subject: [PATCH 39/51] correct freertos port for efm32gg --- examples/device/cdc_msc_freertos/.skip.MCU_EFM32GG12 | 0 examples/device/hid_composite_freertos/.skip.MCU_EFM32GG12 | 0 hw/bsp/sltb009a/board.mk | 6 +----- 3 files changed, 1 insertion(+), 5 deletions(-) delete mode 100644 examples/device/cdc_msc_freertos/.skip.MCU_EFM32GG12 delete mode 100644 examples/device/hid_composite_freertos/.skip.MCU_EFM32GG12 diff --git a/examples/device/cdc_msc_freertos/.skip.MCU_EFM32GG12 b/examples/device/cdc_msc_freertos/.skip.MCU_EFM32GG12 deleted file mode 100644 index e69de29bb..000000000 diff --git a/examples/device/hid_composite_freertos/.skip.MCU_EFM32GG12 b/examples/device/hid_composite_freertos/.skip.MCU_EFM32GG12 deleted file mode 100644 index e69de29bb..000000000 diff --git a/hw/bsp/sltb009a/board.mk b/hw/bsp/sltb009a/board.mk index 7a046b34b..f5c240ca2 100644 --- a/hw/bsp/sltb009a/board.mk +++ b/hw/bsp/sltb009a/board.mk @@ -34,12 +34,8 @@ INC += \ $(TOP)/$(SILABS_CMSIS)/Include \ $(TOP)/hw/bsp/$(BOARD) -# For TinyUSB port source -VENDOR = silabs -CHIP_FAMILY = efm32 - # For freeRTOS port source -FREERTOS_PORT = ARM_CM4 +FREERTOS_PORT = ARM_CM3 # For flash-jlink target JLINK_DEVICE = EFM32GG12B810F1024 From aa682d730123a1191782b1a160ce25ea20580ee6 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 2 Nov 2021 13:52:30 +0700 Subject: [PATCH 40/51] add fix for stm32l4 (version 3.10a) which generate transfer complete when setup recieved and control out data complete --- hw/bsp/stm32l476disco/board.mk | 6 +- hw/bsp/stm32l476disco/stm32l476disco.c | 8 +- src/device/dcd_attr.h | 1 + src/portable/synopsys/dwc2/dcd_dwc2.c | 151 +++++++++++++++++-------- src/portable/synopsys/dwc2/dwc2_type.h | 11 ++ 5 files changed, 122 insertions(+), 55 deletions(-) diff --git a/hw/bsp/stm32l476disco/board.mk b/hw/bsp/stm32l476disco/board.mk index 28824efdc..8d9e267cf 100644 --- a/hw/bsp/stm32l476disco/board.mk +++ b/hw/bsp/stm32l476disco/board.mk @@ -21,8 +21,9 @@ CFLAGS += -Wno-error=maybe-uninitialized -Wno-error=cast-align # All source paths should be relative to the top level. LD_FILE = hw/bsp/$(BOARD)/STM32L476VGTx_FLASH.ld +#src/portable/st/synopsys/dcd_synopsys.c SRC_C += \ - src/portable/st/synopsys/dcd_synopsys.c \ + src/portable/synopsys/dwc2/dcd_dwc2.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 \ @@ -52,5 +53,4 @@ JLINK_DEVICE = stm32l476vg STM32Prog = STM32_Programmer_CLI # flash target using on-board stlink -flash: $(BUILD)/$(PROJECT).elf - $(STM32Prog) --connect port=swd --write $< --go +flash: flash-stlink diff --git a/hw/bsp/stm32l476disco/stm32l476disco.c b/hw/bsp/stm32l476disco/stm32l476disco.c index b18846685..bc1b6c929 100644 --- a/hw/bsp/stm32l476disco/stm32l476disco.c +++ b/hw/bsp/stm32l476disco/stm32l476disco.c @@ -186,8 +186,12 @@ void board_init(void) /* Enable USB FS Clock */ __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - // Enable VBUS sense (B device) via pin PA9 - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; +// // Enable VBUS sense (B device) via pin PA9 +// USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; + + // L476Disco use general GPIO PC11 for VBUS sensing instead of dedicated PA9 as others + // Disable VBUS Sense and force device mode + USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; } //--------------------------------------------------------------------+ diff --git a/src/device/dcd_attr.h b/src/device/dcd_attr.h index 70854f9c6..952a8b8c8 100644 --- a/src/device/dcd_attr.h +++ b/src/device/dcd_attr.h @@ -125,6 +125,7 @@ #elif TU_CHECK_MCU(OPT_MCU_STM32L4) #if defined (STM32L475xx) || defined (STM32L476xx) || \ defined (STM32L485xx) || defined (STM32L486xx) || defined (STM32L496xx) || \ + defined (STM32L4A6xx) || defined (STM32L4P5xx) || defined (STM32L4Q5xx) || \ defined (STM32L4R5xx) || defined (STM32L4R7xx) || defined (STM32L4R9xx) || \ defined (STM32L4S5xx) || defined (STM32L4S7xx) || defined (STM32L4S9xx) #define DCD_ATTR_ENDPOINT_MAX 6 diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index e2a999ac0..83abc635b 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -123,8 +123,8 @@ static void bus_reset(uint8_t rhport) dwc2->epout[n].doepctl |= DOEPCTL_SNAK; } - // 2. Un-mask interrupt bits - dwc2->daintmsk = (1 << DAINTMSK_OEPM_Pos) | (1 << DAINTMSK_IEPM_Pos); + // 2. Set up interrupt mask + dwc2->daintmsk = TU_BIT(DAINTMSK_OEPM_Pos) | TU_BIT(DAINTMSK_IEPM_Pos); dwc2->doepmsk = DOEPMSK_STUPM | DOEPMSK_XFRCM; dwc2->diepmsk = DIEPMSK_TOM | DIEPMSK_XFRCM; @@ -472,9 +472,6 @@ void dcd_init (uint8_t rhport) // Restart PHY clock dwc2->pcgctl &= ~(PCGCTL_STOPPCLK | PCGCTL_GATEHCLK | PCGCTL_PWRCLMP | PCGCTL_RSTPDWNMODULE); - // Force device mode - dwc2->gusbcfg = (dwc2->gusbcfg & ~GUSBCFG_FHMOD) | GUSBCFG_FDMOD; - /* Set HS/FS Timeout Calibration to 7 (max available value). * The number of PHY clocks that the application programs in * this field is added to the high/full speed interpacket timeout @@ -485,13 +482,16 @@ void dcd_init (uint8_t rhport) */ dwc2->gusbcfg |= (7ul << GUSBCFG_TOCAL_Pos); + // Force device mode + dwc2->gusbcfg = (dwc2->gusbcfg & ~GUSBCFG_FHMOD) | GUSBCFG_FDMOD; + + // Clear A override, force B Valid + dwc2->gotgctl = (dwc2->gotgctl & ~GOTGCTL_AVALOEN) | GOTGCTL_BVALOEN | GOTGCTL_BVALOVAL; + // If USB host misbehaves during status portion of control xfer // (non zero-length packet), send STALL back and discard. dwc2->dcfg |= DCFG_NZLSOHSK; - // Clear A,B, VBus valid override - dwc2->gotgctl &= ~(GOTGCTL_BVALOEN | GOTGCTL_AVALOEN | GOTGCTL_VBVALOEN); - // Clear all interrupts dwc2->gintsts |= dwc2->gintsts; dwc2->gotgint |= dwc2->gotgint; @@ -609,7 +609,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) (desc_edpt->bmAttributes.xfer != TUSB_XFER_ISOCHRONOUS ? DOEPCTL_SD0PID_SEVNFRM : 0) | (xfer->max_size << DOEPCTL_MPSIZ_Pos); - dwc2->daintmsk |= (1 << (DAINTMSK_OEPM_Pos + epnum)); + dwc2->daintmsk |= TU_BIT(DAINTMSK_OEPM_Pos + epnum); } else { @@ -696,19 +696,21 @@ bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t if(epnum == 0) { ep0_pending[dir] = total_bytes; + // Schedule the first transaction for EP0 transfer edpt_schedule_packets(rhport, epnum, dir, 1, ep0_pending[dir]); - return true; } + else + { + uint16_t num_packets = (total_bytes / xfer->max_size); + uint16_t const short_packet_size = total_bytes % xfer->max_size; - uint16_t num_packets = (total_bytes / xfer->max_size); - uint16_t const short_packet_size = total_bytes % xfer->max_size; + // Zero-size packet is special case. + if ( (short_packet_size > 0) || (total_bytes == 0) ) num_packets++; - // Zero-size packet is special case. - if ( short_packet_size > 0 || (total_bytes == 0) ) num_packets++; - - // Schedule packets to be sent within interrupt - edpt_schedule_packets(rhport, epnum, dir, num_packets, total_bytes); + // Schedule packets to be sent within interrupt + edpt_schedule_packets(rhport, epnum, dir, num_packets, total_bytes); + } return true; } @@ -924,21 +926,49 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t const * static void handle_rxflvl_irq(uint8_t rhport) { dwc2_regs_t * dwc2 = DWC2_REG(rhport); - volatile uint32_t * rx_fifo = dwc2->fifo[0]; + volatile uint32_t const * rx_fifo = dwc2->fifo[0]; // Pop control word off FIFO - uint32_t ctl_word = dwc2->grxstsp; - uint8_t pktsts = (ctl_word & GRXSTSP_PKTSTS_Msk ) >> GRXSTSP_PKTSTS_Pos; - uint8_t epnum = (ctl_word & GRXSTSP_EPNUM_Msk ) >> GRXSTSP_EPNUM_Pos; - uint16_t bcnt = (ctl_word & GRXSTSP_BCNT_Msk ) >> GRXSTSP_BCNT_Pos; + uint32_t const ctl_word = dwc2->grxstsp; + uint8_t const pktsts = (ctl_word & GRXSTSP_PKTSTS_Msk ) >> GRXSTSP_PKTSTS_Pos; + uint8_t const epnum = (ctl_word & GRXSTSP_EPNUM_Msk ) >> GRXSTSP_EPNUM_Pos; + uint16_t const bcnt = (ctl_word & GRXSTSP_BCNT_Msk ) >> GRXSTSP_BCNT_Pos; + + dwc2_epout_t* epout = &dwc2->epout[epnum]; + +#if CFG_TUSB_DEBUG >= (DWC2_DEBUG + 1) + const char * pktsts_str[] = + { + "ASSERT", "Global NAK (ISR)", "Out Data Received", "Out Transfer Complete (ISR)", + "Setup Complete (ISR)", "ASSERT", "Setup Data Received" + }; + TU_LOG_LOCATION(); + TU_LOG(DWC2_DEBUG, " EP %02X, Byte Count %u, %s\r\n", epnum, bcnt, pktsts_str[pktsts]); + TU_LOG(DWC2_DEBUG, " daint = %08lX, doepint = %04lX\r\n", dwc2->daint, epout->doepint); +#endif switch ( pktsts ) { - case 0x01: // Global OUT NAK (Interrupt) + // Global OUT NAK: do nothign + case GRXSTS_PKTSTS_GLOBALOUTNAK: break; + + case GRXSTS_PKTSTS_SETUPRX: + // Setup packet received + + // We can receive up to three setup packets in succession, but + // only the last one is valid. + _setup_packet[0] = (*rx_fifo); + _setup_packet[1] = (*rx_fifo); break; - case 0x02: // Out packet received + case GRXSTS_PKTSTS_SETUPDONE: + // Setup packet done (Interrupt) + epout->doeptsiz |= (3 << DOEPTSIZ_STUPCNT_Pos); + break; + + case GRXSTS_PKTSTS_OUTRX: { + // Out packet received xfer_ctl_t *xfer = XFER_CTL_BASE(epnum, TUSB_DIR_OUT); // Read packet off RxFIFO @@ -959,7 +989,7 @@ static void handle_rxflvl_irq(uint8_t rhport) // Truncate transfer length in case of short packet if ( bcnt < xfer->max_size ) { - xfer->total_len -= (dwc2->epout[epnum].doeptsiz & DOEPTSIZ_XFRSIZ_Msk) >> DOEPTSIZ_XFRSIZ_Pos; + xfer->total_len -= (epout->doeptsiz & DOEPTSIZ_XFRSIZ_Msk) >> DOEPTSIZ_XFRSIZ_Pos; if ( epnum == 0 ) { xfer->total_len -= ep0_pending[TUSB_DIR_OUT]; @@ -969,18 +999,28 @@ static void handle_rxflvl_irq(uint8_t rhport) } break; - case 0x03: // Out packet done (Interrupt) - break; + // Out packet done (Interrupt) + case GRXSTS_PKTSTS_OUTDONE: + // Occurred on STM32L47 with dwc2 version 3.10a but not found on other version like 2.80a or 3.30a + // May (or not) be 3.10a specific feature/bug or depending on MCU configuration + // XFRC complete is additionally generated when + // - setup packet is received + // - complete the data stage of control write is complete + if ((epnum == 0) && (bcnt == 0) && (dwc2->gsnpsid >= DWC2_CORE_REV_3_00a)) + { + if (epout->doepint & DOEPINT_STPKTRX) + { + // skip this "no-data" transfer complete event + // STPKTRX will be clear later by setup received handler + epout->doepint = DOEPINT_XFRC; + } - case 0x04: // Setup packet done (Interrupt) - dwc2->epout[epnum].doeptsiz |= (3 << DOEPTSIZ_STUPCNT_Pos); - break; - - case 0x06: // Setup packet recvd - // We can receive up to three setup packets in succession, but - // only the last one is valid. - _setup_packet[0] = (*rx_fifo); - _setup_packet[1] = (*rx_fifo); + if (epout->doepint & DOEPINT_OTEPSPR) + { + // skip this "no-data" transfer complete event + epout->doepint = DOEPINT_XFRC | DOEPINT_OTEPSPR; + } + } break; default: // Invalid @@ -992,27 +1032,38 @@ static void handle_rxflvl_irq(uint8_t rhport) static void handle_epout_irq (uint8_t rhport) { dwc2_regs_t *dwc2 = DWC2_REG(rhport); - dwc2_epout_t* epout = dwc2->epout; // DAINT for a given EP clears when DOEPINTx is cleared. // OEPINT will be cleared when DAINT's out bits are cleared. for ( uint8_t n = 0; n < DWC2_EP_MAX; n++ ) { - xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_OUT); - - if ( dwc2->daint & (1 << (DAINT_OEPINT_Pos + n)) ) + if ( dwc2->daint & TU_BIT(DAINT_OEPINT_Pos + n) ) { + dwc2_epout_t* epout = &dwc2->epout[n]; + + uint32_t const doepint = epout->doepint; + // SETUP packet Setup Phase done. - if ( epout[n].doepint & DOEPINT_STUP ) + if ( doepint & DOEPINT_STUP ) { - epout[n].doepint = DOEPINT_STUP; - dcd_event_setup_received(rhport, (uint8_t*) &_setup_packet[0], true); + uint32_t clear_flag = DOEPINT_STUP; + + // STPKTRX is only available for version from 3_00a + if ((doepint & DOEPINT_STPKTRX) && (dwc2->gsnpsid >= DWC2_CORE_REV_3_00a)) + { + clear_flag |= DOEPINT_STPKTRX; + } + + epout->doepint = clear_flag; + dcd_event_setup_received(rhport, (uint8_t*) _setup_packet, true); } // OUT XFER complete - if ( epout[n].doepint & DOEPINT_XFRC ) + if ( epout->doepint & DOEPINT_XFRC ) { - epout[n].doepint = DOEPINT_XFRC; + epout->doepint = DOEPINT_XFRC; + + xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_OUT); // EP0 can only handle one packet if ( (n == 0) && ep0_pending[TUSB_DIR_OUT] ) @@ -1038,11 +1089,11 @@ static void handle_epin_irq (uint8_t rhport) // IEPINT will be cleared when DAINT's out bits are cleared. for ( uint8_t n = 0; n < DWC2_EP_MAX; n++ ) { - xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_IN); - - if ( dwc2->daint & (1 << (DAINT_IEPINT_Pos + n)) ) + if ( dwc2->daint & TU_BIT(DAINT_IEPINT_Pos + n) ) { // IN XFER complete (entire xfer). + xfer_ctl_t *xfer = XFER_CTL_BASE(n, TUSB_DIR_IN); + if ( epin[n].diepint & DIEPINT_XFRC ) { epin[n].diepint = DIEPINT_XFRC; @@ -1215,14 +1266,14 @@ void dcd_int_handler(uint8_t rhport) // OUT endpoint interrupt handling. if(int_status & GINTSTS_OEPINT) { - // OEPINT is read-only + // OEPINT is read-only, clear using DOEPINTn handle_epout_irq(rhport); } // IN endpoint interrupt handling. if(int_status & GINTSTS_IEPINT) { - // IEPINT bit read-only + // IEPINT bit read-only, clear using DIEPINTn handle_epin_irq(rhport); } diff --git a/src/portable/synopsys/dwc2/dwc2_type.h b/src/portable/synopsys/dwc2/dwc2_type.h index 583a7274a..6e52ebc7b 100644 --- a/src/portable/synopsys/dwc2/dwc2_type.h +++ b/src/portable/synopsys/dwc2/dwc2_type.h @@ -907,6 +907,17 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size"); #define GRXSTSP_PKTSTS_Msk (0xFUL << GRXSTSP_PKTSTS_Pos) // 0x001E0000 */ #define GRXSTSP_PKTSTS GRXSTSP_PKTSTS_Msk // OUT EP interrupt mask bits */ +#define GRXSTS_PKTSTS_GLOBALOUTNAK 1 +#define GRXSTS_PKTSTS_OUTRX 2 +#define GRXSTS_PKTSTS_HCHIN 2 +#define GRXSTS_PKTSTS_OUTDONE 3 +#define GRXSTS_PKTSTS_HCHIN_XFER_COMP 3 +#define GRXSTS_PKTSTS_SETUPDONE 4 +#define GRXSTS_PKTSTS_DATATOGGLEERR 5 +#define GRXSTS_PKTSTS_SETUPRX 6 +#define GRXSTS_PKTSTS_HCHHALTED 7 + + /******************** Bit definition for DAINTMSK register ********************/ #define DAINTMSK_IEPM_Pos (0U) #define DAINTMSK_IEPM_Msk (0xFFFFUL << DAINTMSK_IEPM_Pos) // 0x0000FFFF */ From b80942987346bc3731fb3b40696065be039d59a9 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 2 Nov 2021 14:51:15 +0700 Subject: [PATCH 41/51] minor clean up --- src/portable/synopsys/dwc2/dcd_dwc2.c | 40 +++++++++++++-------------- 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 83abc635b..9750757aa 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -936,16 +936,16 @@ static void handle_rxflvl_irq(uint8_t rhport) dwc2_epout_t* epout = &dwc2->epout[epnum]; -#if CFG_TUSB_DEBUG >= (DWC2_DEBUG + 1) - const char * pktsts_str[] = - { - "ASSERT", "Global NAK (ISR)", "Out Data Received", "Out Transfer Complete (ISR)", - "Setup Complete (ISR)", "ASSERT", "Setup Data Received" - }; - TU_LOG_LOCATION(); - TU_LOG(DWC2_DEBUG, " EP %02X, Byte Count %u, %s\r\n", epnum, bcnt, pktsts_str[pktsts]); - TU_LOG(DWC2_DEBUG, " daint = %08lX, doepint = %04lX\r\n", dwc2->daint, epout->doepint); -#endif +//#if CFG_TUSB_DEBUG >= DWC2_DEBUG +// const char * pktsts_str[] = +// { +// "ASSERT", "Global NAK (ISR)", "Out Data Received", "Out Transfer Complete (ISR)", +// "Setup Complete (ISR)", "ASSERT", "Setup Data Received" +// }; +// TU_LOG_LOCATION(); +// TU_LOG(DWC2_DEBUG, " EP %02X, Byte Count %u, %s\r\n", epnum, bcnt, pktsts_str[pktsts]); +// TU_LOG(DWC2_DEBUG, " daint = %08lX, doepint = %04X\r\n", (unsigned long) dwc2->daint, (unsigned int) epout->doepint); +//#endif switch ( pktsts ) { @@ -1008,17 +1008,19 @@ static void handle_rxflvl_irq(uint8_t rhport) // - complete the data stage of control write is complete if ((epnum == 0) && (bcnt == 0) && (dwc2->gsnpsid >= DWC2_CORE_REV_3_00a)) { - if (epout->doepint & DOEPINT_STPKTRX) - { - // skip this "no-data" transfer complete event - // STPKTRX will be clear later by setup received handler - epout->doepint = DOEPINT_XFRC; - } + uint32_t doepint = epout->doepint; - if (epout->doepint & DOEPINT_OTEPSPR) + if (doepint & (DOEPINT_STPKTRX | DOEPINT_OTEPSPR)) { // skip this "no-data" transfer complete event - epout->doepint = DOEPINT_XFRC | DOEPINT_OTEPSPR; + // Note: STPKTRX will be clear later by setup received handler + uint32_t clear_flags = DOEPINT_XFRC; + + if (doepint & DOEPINT_OTEPSPR) clear_flags |= DOEPINT_OTEPSPR; + + epout->doepint = clear_flags; + + // TU_LOG(DWC2_DEBUG, " FIX extra transfer complete on setup/data compete\r\n"); } } break; @@ -1163,8 +1165,6 @@ void dcd_int_handler(uint8_t rhport) uint32_t const int_status = dwc2->gintsts & dwc2->gintmsk; -// TU_LOG_HEX(DWC2_DEBUG, int_status); - if(int_status & GINTSTS_USBRST) { // USBRST is start of reset. From 7e688947265075afdaa343e69ec29a2b2cac5f33 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 2 Nov 2021 15:15:54 +0700 Subject: [PATCH 42/51] grouping stm32L4 family in bsp --- .../stm32l476_disco}/STM32L476VGTx_FLASH.ld | 0 .../boards/stm32l476_disco/board.h} | 151 +------ .../stm32l4/boards/stm32l476_disco/board.mk | 10 + .../stm32l4p5_nucleo/STM32L4P5ZGTX_FLASH.ld | 200 +++++++++ .../stm32l4/boards/stm32l4p5_nucleo/board.h | 137 ++++++ .../stm32l4/boards/stm32l4p5_nucleo/board.mk | 10 + .../stm32l4r5_nucleo}/STM32L4RXxI_FLASH.ld | 0 .../stm32l4/boards/stm32l4r5_nucleo/board.h | 137 ++++++ .../stm32l4/boards/stm32l4r5_nucleo/board.mk | 14 + .../stm32l4r5nucleo.c => stm32l4/family.c} | 139 ++---- .../board.mk => stm32l4/family.mk} | 15 +- .../stm32l4xx_hal_conf.h | 0 hw/bsp/stm32l476disco/board.mk | 56 --- hw/bsp/stm32l4r5nucleo/stm32l4xx_hal_conf.h | 419 ------------------ src/portable/synopsys/dwc2/dcd_dwc2.c | 2 +- 15 files changed, 561 insertions(+), 729 deletions(-) rename hw/bsp/{stm32l476disco => stm32l4/boards/stm32l476_disco}/STM32L476VGTx_FLASH.ld (100%) rename hw/bsp/{stm32l476disco/stm32l476disco.c => stm32l4/boards/stm32l476_disco/board.h} (59%) create mode 100644 hw/bsp/stm32l4/boards/stm32l476_disco/board.mk create mode 100644 hw/bsp/stm32l4/boards/stm32l4p5_nucleo/STM32L4P5ZGTX_FLASH.ld create mode 100644 hw/bsp/stm32l4/boards/stm32l4p5_nucleo/board.h create mode 100644 hw/bsp/stm32l4/boards/stm32l4p5_nucleo/board.mk rename hw/bsp/{stm32l4r5nucleo => stm32l4/boards/stm32l4r5_nucleo}/STM32L4RXxI_FLASH.ld (100%) create mode 100644 hw/bsp/stm32l4/boards/stm32l4r5_nucleo/board.h create mode 100644 hw/bsp/stm32l4/boards/stm32l4r5_nucleo/board.mk rename hw/bsp/{stm32l4r5nucleo/stm32l4r5nucleo.c => stm32l4/family.c} (55%) rename hw/bsp/{stm32l4r5nucleo/board.mk => stm32l4/family.mk} (81%) rename hw/bsp/{stm32l476disco => stm32l4}/stm32l4xx_hal_conf.h (100%) delete mode 100644 hw/bsp/stm32l476disco/board.mk delete mode 100644 hw/bsp/stm32l4r5nucleo/stm32l4xx_hal_conf.h diff --git a/hw/bsp/stm32l476disco/STM32L476VGTx_FLASH.ld b/hw/bsp/stm32l4/boards/stm32l476_disco/STM32L476VGTx_FLASH.ld similarity index 100% rename from hw/bsp/stm32l476disco/STM32L476VGTx_FLASH.ld rename to hw/bsp/stm32l4/boards/stm32l476_disco/STM32L476VGTx_FLASH.ld diff --git a/hw/bsp/stm32l476disco/stm32l476disco.c b/hw/bsp/stm32l4/boards/stm32l476_disco/board.h similarity index 59% rename from hw/bsp/stm32l476disco/stm32l476disco.c rename to hw/bsp/stm32l4/boards/stm32l476_disco/board.h index bc1b6c929..42c657d5e 100644 --- a/hw/bsp/stm32l476disco/stm32l476disco.c +++ b/hw/bsp/stm32l4/boards/stm32l476_disco/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,21 +24,12 @@ * This file is part of the TinyUSB stack. */ -#include "../board.h" +#ifndef BOARD_H_ +#define BOARD_H_ -#include "stm32l4xx_hal.h" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ +#ifdef __cplusplus + extern "C" { +#endif #define LED_PORT GPIOB #define LED_PIN GPIO_PIN_2 @@ -48,15 +39,16 @@ void OTG_FS_IRQHandler(void) #define BUTTON_PIN GPIO_PIN_0 #define BUTTON_STATE_ACTIVE 1 +#define UART_DEV USART2 +#define UART_CLK_EN __HAL_RCC_USART2_CLK_ENABLE +#define UART_GPIO_PORT GPIOD +#define UART_GPIO_AF GPIO_AF7_USART2 +#define UART_TX_PIN GPIO_PIN_5 +#define UART_RX_PIN GPIO_PIN_6 -// 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_GPIOB_CLK_ENABLE(); // LED - __HAL_RCC_GPIOC_CLK_ENABLE(); // VBUS pin -} - +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ /** * @brief System Clock Configuration @@ -80,7 +72,7 @@ static void all_rcc_clk_enable(void) * @param None * @retval None */ -static void SystemClock_Config(void) +static inline void board_clock_init(void) { RCC_ClkInitTypeDef RCC_ClkInitStruct; RCC_OscInitTypeDef RCC_OscInitStruct; @@ -131,116 +123,17 @@ static void SystemClock_Config(void) HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4); } -void board_init(void) +static inline void board_vbus_sense_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 - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable USB power on Pwrctrl CR2 register */ - HAL_PWREx_EnableVddUSB(); - - 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 - /* 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_FREQ_VERY_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure VBUS Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_11; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - - /* Enable USB FS Clock */ - __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - -// // Enable VBUS sense (B device) via pin PA9 -// USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; - // L476Disco use general GPIO PC11 for VBUS sensing instead of dedicated PA9 as others // Disable VBUS Sense and force device mode USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; + + USB_OTG_FS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN | USB_OTG_GOTGCTL_BVALOVAL; } -//--------------------------------------------------------------------+ -// 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; -} +#ifdef __cplusplus + } #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) -{ - -} +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32l4/boards/stm32l476_disco/board.mk b/hw/bsp/stm32l4/boards/stm32l476_disco/board.mk new file mode 100644 index 000000000..e7b8557a5 --- /dev/null +++ b/hw/bsp/stm32l4/boards/stm32l476_disco/board.mk @@ -0,0 +1,10 @@ +CFLAGS += \ + -DSTM32L476xx \ + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/STM32L476VGTx_FLASH.ld + +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32l476xx.s + +# For flash-jlink target +JLINK_DEVICE = stm32l476vg diff --git a/hw/bsp/stm32l4/boards/stm32l4p5_nucleo/STM32L4P5ZGTX_FLASH.ld b/hw/bsp/stm32l4/boards/stm32l4p5_nucleo/STM32L4P5ZGTX_FLASH.ld new file mode 100644 index 000000000..c1a490a70 --- /dev/null +++ b/hw/bsp/stm32l4/boards/stm32l4p5_nucleo/STM32L4P5ZGTX_FLASH.ld @@ -0,0 +1,200 @@ +/* +****************************************************************************** +** +** File : LinkerScript.ld +** +** Author : Auto-generated by STM32CubeIDE +** +** Abstract : Linker script for STM32L4P5ZGTx Device from STM32L4PLUS series +** 1024Kbytes ROM +** 320Kbytes RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** Distribution: The file is distributed as is without any warranty +** of any kind. +** +***************************************************************************** +** @attention +** +**

© COPYRIGHT(c) 2019 STMicroelectronics

+** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** 1. Redistributions of source code must retain the above copyright notice, +** this list of conditions and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright notice, +** this list of conditions and the following disclaimer in the documentation +** and/or other materials provided with the distribution. +** 3. Neither the name of STMicroelectronics nor the names of its contributors +** may be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(RAM) + 0x0001FFFF; /* end of "SRAM1" Ram type memory */ + +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Memories definition */ +MEMORY +{ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 320K + ROM (rx) : ORIGIN = 0x08000000, LENGTH = 1024K +} + +/* Sections */ +SECTIONS +{ + /* The startup code into "ROM" Rom type memory */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >ROM + + /* The program code and other data into "ROM" Rom type memory */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >ROM + + /* Constant data into "ROM" Rom type memory */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >ROM + + .ARM.extab : { + . = ALIGN(4); + *(.ARM.extab* .gnu.linkonce.armextab.*) + . = ALIGN(4); + } >ROM + + .ARM : { + . = ALIGN(4); + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + . = ALIGN(4); + } >ROM + + .preinit_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + . = ALIGN(4); + } >ROM + + .init_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + . = ALIGN(4); + } >ROM + + .fini_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + . = ALIGN(4); + } >ROM + + /* Used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections into "RAM" Ram type memory */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + + } >RAM AT> ROM + + /* Uninitialized data section into "RAM" Ram type memory */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + /* Remove information from the compiler libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/hw/bsp/stm32l4/boards/stm32l4p5_nucleo/board.h b/hw/bsp/stm32l4/boards/stm32l4p5_nucleo/board.h new file mode 100644 index 000000000..1df389aed --- /dev/null +++ b/hw/bsp/stm32l4/boards/stm32l4p5_nucleo/board.h @@ -0,0 +1,137 @@ +/* + * 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 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 LPUART1 +#define UART_CLK_EN __HAL_RCC_LPUART1_CLK_ENABLE +#define UART_GPIO_PORT GPIOG +#define UART_GPIO_AF GPIO_AF8_LPUART1 +#define UART_TX_PIN GPIO_PIN_7 +#define UART_RX_PIN GPIO_PIN_8 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (MSI) + * SYSCLK(Hz) = 120000000 + * HCLK(Hz) = 120000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 1 + * APB2 Prescaler = 1 + * MSI Frequency(Hz) = 48000000 + * PLL_M = 12 + * PLL_N = 60 + * PLL_P = 2 + * PLL_Q = 2 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale1 mode + * Flash Latency(WS) = 5 + * The USB clock configuration from PLLSAI: + * PLLSAIP = 8 FIXME + * PLLSAIN = 384 FIXME + * PLLSAIQ = 7 FIXME + * @param None + * @retval None + */ + +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0}; + + /* Activate PLL with MSI , stabilizied via PLL by LSE */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_MSI; + RCC_OscInitStruct.MSIState = RCC_MSI_ON; + RCC_OscInitStruct.LSEState = RCC_LSE_ON; + RCC_OscInitStruct.MSIClockRange = RCC_MSIRANGE_11; + RCC_OscInitStruct.MSICalibrationValue = RCC_MSICALIBRATION_DEFAULT; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_MSI; + RCC_OscInitStruct.PLL.PLLM = 12; + RCC_OscInitStruct.PLL.PLLN = 60; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 2; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Enable MSI Auto-calibration through LSE */ + HAL_RCCEx_EnableMSIPLLMode(); + + /* Select MSI output as USB clock source */ + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB; + PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_MSI; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); + + /* Select MSI output as USB clock source */ + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_LPUART1; + PeriphClkInitStruct.Lpuart1ClockSelection = RCC_LPUART1CLKSOURCE_PCLK1; + 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; + // Avoid overshoot and start with HCLK 60 MHz + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV2; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3); + + /* AHB prescaler divider at 1 as second step */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); +} + +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/stm32l4/boards/stm32l4p5_nucleo/board.mk b/hw/bsp/stm32l4/boards/stm32l4p5_nucleo/board.mk new file mode 100644 index 000000000..8252dd838 --- /dev/null +++ b/hw/bsp/stm32l4/boards/stm32l4p5_nucleo/board.mk @@ -0,0 +1,10 @@ +CFLAGS += \ + -DSTM32L4P5xx \ + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/STM32L4P5ZGTX_FLASH.ld + +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32l4p5xx.s + +# For flash-jlink target +JLINK_DEVICE = stm32l4p5zg diff --git a/hw/bsp/stm32l4r5nucleo/STM32L4RXxI_FLASH.ld b/hw/bsp/stm32l4/boards/stm32l4r5_nucleo/STM32L4RXxI_FLASH.ld similarity index 100% rename from hw/bsp/stm32l4r5nucleo/STM32L4RXxI_FLASH.ld rename to hw/bsp/stm32l4/boards/stm32l4r5_nucleo/STM32L4RXxI_FLASH.ld diff --git a/hw/bsp/stm32l4/boards/stm32l4r5_nucleo/board.h b/hw/bsp/stm32l4/boards/stm32l4r5_nucleo/board.h new file mode 100644 index 000000000..1df389aed --- /dev/null +++ b/hw/bsp/stm32l4/boards/stm32l4r5_nucleo/board.h @@ -0,0 +1,137 @@ +/* + * 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 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 LPUART1 +#define UART_CLK_EN __HAL_RCC_LPUART1_CLK_ENABLE +#define UART_GPIO_PORT GPIOG +#define UART_GPIO_AF GPIO_AF8_LPUART1 +#define UART_TX_PIN GPIO_PIN_7 +#define UART_RX_PIN GPIO_PIN_8 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (MSI) + * SYSCLK(Hz) = 120000000 + * HCLK(Hz) = 120000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 1 + * APB2 Prescaler = 1 + * MSI Frequency(Hz) = 48000000 + * PLL_M = 12 + * PLL_N = 60 + * PLL_P = 2 + * PLL_Q = 2 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale1 mode + * Flash Latency(WS) = 5 + * The USB clock configuration from PLLSAI: + * PLLSAIP = 8 FIXME + * PLLSAIN = 384 FIXME + * PLLSAIQ = 7 FIXME + * @param None + * @retval None + */ + +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0}; + + /* Activate PLL with MSI , stabilizied via PLL by LSE */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_MSI; + RCC_OscInitStruct.MSIState = RCC_MSI_ON; + RCC_OscInitStruct.LSEState = RCC_LSE_ON; + RCC_OscInitStruct.MSIClockRange = RCC_MSIRANGE_11; + RCC_OscInitStruct.MSICalibrationValue = RCC_MSICALIBRATION_DEFAULT; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_MSI; + RCC_OscInitStruct.PLL.PLLM = 12; + RCC_OscInitStruct.PLL.PLLN = 60; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 2; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Enable MSI Auto-calibration through LSE */ + HAL_RCCEx_EnableMSIPLLMode(); + + /* Select MSI output as USB clock source */ + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB; + PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_MSI; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); + + /* Select MSI output as USB clock source */ + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_LPUART1; + PeriphClkInitStruct.Lpuart1ClockSelection = RCC_LPUART1CLKSOURCE_PCLK1; + 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; + // Avoid overshoot and start with HCLK 60 MHz + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV2; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3); + + /* AHB prescaler divider at 1 as second step */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); +} + +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/stm32l4/boards/stm32l4r5_nucleo/board.mk b/hw/bsp/stm32l4/boards/stm32l4r5_nucleo/board.mk new file mode 100644 index 000000000..3d7fa227b --- /dev/null +++ b/hw/bsp/stm32l4/boards/stm32l4r5_nucleo/board.mk @@ -0,0 +1,14 @@ +CFLAGS += \ + -DHSE_VALUE=8000000 \ + -DSTM32L4R5xx \ + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/STM32L4RXxI_FLASH.ld + +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32l4r5xx.s + +# For flash-jlink target +JLINK_DEVICE = stm32l4r5zi + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32l4r5nucleo/stm32l4r5nucleo.c b/hw/bsp/stm32l4/family.c similarity index 55% rename from hw/bsp/stm32l4r5nucleo/stm32l4r5nucleo.c rename to hw/bsp/stm32l4/family.c index 8c661b602..c15be98e5 100644 --- a/hw/bsp/stm32l4r5nucleo/stm32l4r5nucleo.c +++ b/hw/bsp/stm32l4/family.c @@ -26,9 +26,9 @@ * This file is part of the TinyUSB stack. */ -#include "../board.h" - #include "stm32l4xx_hal.h" +#include "bsp/board.h" +#include "board.h" //--------------------------------------------------------------------+ // Forward USB interrupt events to TinyUSB IRQ Handler @@ -42,119 +42,22 @@ void OTG_FS_IRQHandler(void) // 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 LPUART1 -#define UART_GPIO_PORT GPIOG -#define UART_GPIO_AF GPIO_AF8_LPUART1 -#define UART_TX_PIN GPIO_PIN_7 -#define UART_RX_PIN GPIO_PIN_8 - 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_GPIOG_CLK_ENABLE(); // Uart TX, RX - __HAL_RCC_LPUART1_CLK_ENABLE(); // LPUart1 module -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (MSI) - * SYSCLK(Hz) = 120000000 - * HCLK(Hz) = 120000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 1 - * APB2 Prescaler = 1 - * MSI Frequency(Hz) = 48000000 - * PLL_M = 12 - * PLL_N = 60 - * PLL_P = 2 - * PLL_Q = 2 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 5 - * The USB clock configuration from PLLSAI: - * PLLSAIP = 8 FIXME - * PLLSAIN = 384 FIXME - * PLLSAIQ = 7 FIXME - * @param None - * @retval None - */ -void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0}; - - /* Activate PLL with MSI , stabilizied via PLL by LSE */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_MSI; - RCC_OscInitStruct.MSIState = RCC_MSI_ON; - RCC_OscInitStruct.LSEState = RCC_LSE_ON; - RCC_OscInitStruct.MSIClockRange = RCC_MSIRANGE_11; - RCC_OscInitStruct.MSICalibrationValue = RCC_MSICALIBRATION_DEFAULT; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_MSI; - RCC_OscInitStruct.PLL.PLLM = 12; - RCC_OscInitStruct.PLL.PLLN = 60; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 2; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Enable MSI Auto-calibration through LSE */ - HAL_RCCEx_EnableMSIPLLMode(); - - /* Select MSI output as USB clock source */ - PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB; - PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_MSI; - HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); - - /* Select MSI output as USB clock source */ - PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_LPUART1; - PeriphClkInitStruct.Lpuart1ClockSelection = RCC_LPUART1CLKSOURCE_PCLK1; - 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; - // Avoid overshoot and start with HCLK 60 MHz - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV2; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3); - - /* AHB prescaler divider at 1 as second step */ - RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); -} - void board_init(void) { - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - /* Enable voltage range 1 boost mode for frequency above 80 Mhz */ - HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1_BOOST); + board_clock_init(); - /* Set tick interrupt priority, default HAL value is intentionally invalid - and that prevents PLL initialization in HAL_RCC_OscConfig() */ - - HAL_InitTick((1UL << __NVIC_PRIO_BITS) - 1UL); - - SystemClock_Config(); - all_rcc_clk_enable(); + // Enable All GPIOs clocks + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOB_CLK_ENABLE(); + __HAL_RCC_GPIOC_CLK_ENABLE(); + __HAL_RCC_GPIOD_CLK_ENABLE(); + __HAL_RCC_GPIOE_CLK_ENABLE(); + __HAL_RCC_GPIOF_CLK_ENABLE(); + __HAL_RCC_GPIOG_CLK_ENABLE(); + __HAL_RCC_GPIOH_CLK_ENABLE(); + UART_CLK_EN(); #if CFG_TUSB_OS == OPT_OS_NONE // 1ms tick timer @@ -164,6 +67,15 @@ void board_init(void) //NVIC_SetPriority(USB0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY ); #endif + /* Enable USB power on Pwrctrl CR2 register */ + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + +#if defined(PWR_CR5_R1MODE) + /* Enable voltage range 1 boost mode for frequency above 80 Mhz */ + HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1_BOOST); +#endif + /* Enable USB power on Pwrctrl CR2 register */ HAL_PWREx_EnableVddUSB(); @@ -192,7 +104,7 @@ void board_init(void) GPIO_InitStruct.Alternate = UART_GPIO_AF; HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); - UartHandle.Instance = UARTx; + UartHandle.Instance = UART_DEV; UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; UartHandle.Init.WordLength = UART_WORDLENGTH_8B; UartHandle.Init.StopBits = UART_STOPBITS_1; @@ -201,7 +113,7 @@ void board_init(void) UartHandle.Init.Mode = UART_MODE_TX_RX; UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; UartHandle.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE; - UartHandle.Init.ClockPrescaler = UART_PRESCALER_DIV1; + //UartHandle.Init.ClockPrescaler = UART_PRESCALER_DIV1; UartHandle.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT; HAL_UART_Init(&UartHandle); @@ -231,8 +143,7 @@ void board_init(void) /* 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_vbus_sense_init(); } //--------------------------------------------------------------------+ diff --git a/hw/bsp/stm32l4r5nucleo/board.mk b/hw/bsp/stm32l4/family.mk similarity index 81% rename from hw/bsp/stm32l4r5nucleo/board.mk rename to hw/bsp/stm32l4/family.mk index 12a291d0a..d6f55e5f9 100644 --- a/hw/bsp/stm32l4r5nucleo/board.mk +++ b/hw/bsp/stm32l4/family.mk @@ -4,6 +4,8 @@ DEPS_SUBMODULES += lib/CMSIS_5 hw/mcu/st/cmsis_device_$(ST_FAMILY) hw/mcu/st/stm ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver +include $(TOP)/$(BOARD_PATH)/board.mk + CFLAGS += \ -flto \ -mthumb \ @@ -12,18 +14,14 @@ CFLAGS += \ -mfloat-abi=hard \ -mfpu=fpv4-sp-d16 \ -nostdlib -nostartfiles \ - -DHSE_VALUE=8000000 \ - -DSTM32L4R5xx \ -DCFG_TUSB_MCU=OPT_MCU_STM32L4 # suppress warning caused by vendor mcu driver CFLAGS += -Wno-error=maybe-uninitialized -Wno-error=cast-align -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32L4RXxI_FLASH.ld - +#src/portable/st/synopsys/dcd_synopsys.c SRC_C += \ - src/portable/st/synopsys/dcd_synopsys.c \ + src/portable/synopsys/dwc2/dcd_dwc2.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 \ @@ -34,14 +32,11 @@ SRC_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_stm32l4r5xx.s - INC += \ $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ $(TOP)/$(ST_CMSIS)/Include \ $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) + $(TOP)/$(BOARD_PATH) # For freeRTOS port source FREERTOS_PORT = ARM_CM4F diff --git a/hw/bsp/stm32l476disco/stm32l4xx_hal_conf.h b/hw/bsp/stm32l4/stm32l4xx_hal_conf.h similarity index 100% rename from hw/bsp/stm32l476disco/stm32l4xx_hal_conf.h rename to hw/bsp/stm32l4/stm32l4xx_hal_conf.h diff --git a/hw/bsp/stm32l476disco/board.mk b/hw/bsp/stm32l476disco/board.mk deleted file mode 100644 index 8d9e267cf..000000000 --- a/hw/bsp/stm32l476disco/board.mk +++ /dev/null @@ -1,56 +0,0 @@ -ST_FAMILY = l4 -DEPS_SUBMODULES += lib/CMSIS_5 hw/mcu/st/cmsis_device_$(ST_FAMILY) hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m4 \ - -mfloat-abi=hard \ - -mfpu=fpv4-sp-d16 \ - -nostdlib -nostartfiles \ - -DSTM32L476xx \ - -DCFG_TUSB_MCU=OPT_MCU_STM32L4 - -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=maybe-uninitialized -Wno-error=cast-align - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32L476VGTx_FLASH.ld - -#src/portable/st/synopsys/dcd_synopsys.c -SRC_C += \ - src/portable/synopsys/dwc2/dcd_dwc2.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_pwr.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_pwr_ex.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_stm32l476xx.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM4F - -# For flash-jlink target -JLINK_DEVICE = stm32l476vg - -# Path to STM32 Cube Programmer CLI, should be added into system path -STM32Prog = STM32_Programmer_CLI - -# flash target using on-board stlink -flash: flash-stlink diff --git a/hw/bsp/stm32l4r5nucleo/stm32l4xx_hal_conf.h b/hw/bsp/stm32l4r5nucleo/stm32l4xx_hal_conf.h deleted file mode 100644 index 470ef1290..000000000 --- a/hw/bsp/stm32l4r5nucleo/stm32l4xx_hal_conf.h +++ /dev/null @@ -1,419 +0,0 @@ -/** - ****************************************************************************** - * @file stm32l4xx_hal_conf.h - * @author MCD Application Team - * @brief HAL configuration template file. - * This file should be copied to the application folder and renamed - * to stm32l4xx_hal_conf.h. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32L4xx_HAL_CONF_H -#define __STM32L4xx_HAL_CONF_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/* ########################## Module Selection ############################## */ -/** - * @brief This is the list of modules to be used in the HAL driver - */ -#define HAL_MODULE_ENABLED -/* #define HAL_ADC_MODULE_ENABLED */ -/* #define HAL_CAN_MODULE_ENABLED */ -/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ -/* #define HAL_COMP_MODULE_ENABLED */ -#define HAL_CORTEX_MODULE_ENABLED -/* #define HAL_CRC_MODULE_ENABLED */ -/* #define HAL_CRYP_MODULE_ENABLED */ -/* #define HAL_DAC_MODULE_ENABLED */ -/* #define HAL_DFSDM_MODULE_ENABLED */ -#define HAL_DMA_MODULE_ENABLED -/* #define HAL_FIREWALL_MODULE_ENABLED */ -#define HAL_FLASH_MODULE_ENABLED -/* #define HAL_NAND_MODULE_ENABLED */ -// #define HAL_NOR_MODULE_ENABLED -// #define HAL_SRAM_MODULE_ENABLED -/* #define HAL_HCD_MODULE_ENABLED */ -#define HAL_GPIO_MODULE_ENABLED -//#define HAL_I2C_MODULE_ENABLED -/* #define HAL_IRDA_MODULE_ENABLED */ -/* #define HAL_IWDG_MODULE_ENABLED */ -//#define HAL_LCD_MODULE_ENABLED -/* #define HAL_LPTIM_MODULE_ENABLED */ -/* #define HAL_OPAMP_MODULE_ENABLED */ -//#define HAL_PCD_MODULE_ENABLED -#define HAL_PWR_MODULE_ENABLED -/* #define HAL_QSPI_MODULE_ENABLED */ -#define HAL_RCC_MODULE_ENABLED -/* #define HAL_RNG_MODULE_ENABLED */ -/* #define HAL_RTC_MODULE_ENABLED */ -//#define HAL_SAI_MODULE_ENABLED -//#define HAL_SD_MODULE_ENABLED -/* #define HAL_SMARTCARD_MODULE_ENABLED */ -/* #define HAL_SMBUS_MODULE_ENABLED */ -/* #define HAL_SPI_MODULE_ENABLED */ -/* #define HAL_SWPMI_MODULE_ENABLED */ -/* #define HAL_TIM_MODULE_ENABLED */ -/* #define HAL_TSC_MODULE_ENABLED */ -#define HAL_UART_MODULE_ENABLED -/* #define HAL_USART_MODULE_ENABLED */ -/* #define HAL_WWDG_MODULE_ENABLED */ - - -/* ########################## Oscillator Values adaptation ####################*/ -/** - * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. - * This value is used by the RCC HAL module to compute the system frequency - * (when HSE is used as system clock source, directly or through the PLL). - */ -#if !defined (HSE_VALUE) - #define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */ -#endif /* HSE_VALUE */ - -#if !defined (HSE_STARTUP_TIMEOUT) - #define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */ -#endif /* HSE_STARTUP_TIMEOUT */ - -/** - * @brief Internal Multiple Speed oscillator (MSI) default value. - * This value is the default MSI range value after Reset. - */ -#if !defined (MSI_VALUE) - #define MSI_VALUE 4000000U /*!< Value of the Internal oscillator in Hz*/ -#endif /* MSI_VALUE */ - -/** - * @brief Internal High Speed oscillator (HSI) value. - * This value is used by the RCC HAL module to compute the system frequency - * (when HSI is used as system clock source, directly or through the PLL). - */ -#if !defined (HSI_VALUE) - #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/ -#endif /* HSI_VALUE */ - -/** - * @brief Internal High Speed oscillator (HSI48) value for USB FS, SDMMC and RNG. - * This internal oscillator is mainly dedicated to provide a high precision clock to - * the USB peripheral by means of a special Clock Recovery System (CRS) circuitry. - * When the CRS is not used, the HSI48 RC oscillator runs on it default frequency - * which is subject to manufacturing process variations. - */ -#if !defined (HSI48_VALUE) - #define HSI48_VALUE 48000000U /*!< Value of the Internal High Speed oscillator for USB FS/SDMMC/RNG in Hz. - The real value my vary depending on manufacturing process variations.*/ -#endif /* HSI48_VALUE */ - -/** - * @brief Internal Low Speed oscillator (LSI) value. - */ -#if !defined (LSI_VALUE) - #define LSI_VALUE 32000U /*!< LSI Typical Value in Hz*/ -#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz - The real value may vary depending on the variations - in voltage and temperature.*/ -/** - * @brief External Low Speed oscillator (LSE) value. - * This value is used by the UART, RTC HAL module to compute the system frequency - */ -#if !defined (LSE_VALUE) - #define LSE_VALUE 32768U /*!< Value of the External oscillator in Hz*/ -#endif /* LSE_VALUE */ - -#if !defined (LSE_STARTUP_TIMEOUT) - #define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */ -#endif /* HSE_STARTUP_TIMEOUT */ - -/** - * @brief External clock source for SAI1 peripheral - * This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source - * frequency. - */ -#if !defined (EXTERNAL_SAI1_CLOCK_VALUE) - #define EXTERNAL_SAI1_CLOCK_VALUE 48000U /*!< Value of the SAI1 External clock source in Hz*/ -#endif /* EXTERNAL_SAI1_CLOCK_VALUE */ - -/** - * @brief External clock source for SAI2 peripheral - * This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source - * frequency. - */ -#if !defined (EXTERNAL_SAI2_CLOCK_VALUE) - #define EXTERNAL_SAI2_CLOCK_VALUE 48000U /*!< Value of the SAI2 External clock source in Hz*/ -#endif /* EXTERNAL_SAI2_CLOCK_VALUE */ - -/* Tip: To avoid modifying this file each time you need to use different HSE, - === you can define the HSE value in your toolchain compiler preprocessor. */ - -/* ########################### System Configuration ######################### */ -/** - * @brief This is the HAL system configuration section - */ -#define VDD_VALUE 3300U /*!< Value of VDD in mv */ -#define TICK_INT_PRIORITY 0U /*!< tick interrupt priority */ -#define USE_RTOS 0U -#define PREFETCH_ENABLE 0U -#define INSTRUCTION_CACHE_ENABLE 1U -#define DATA_CACHE_ENABLE 1U - -#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ -#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ -#define USE_HAL_COMP_REGISTER_CALLBACKS 0U /* COMP register callback disabled */ -#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ -#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ -#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ -#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ -#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ -#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ -#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ -#define USE_HAL_FDCAN_REGISTER_CALLBACKS 0U /* FDCAN register callback disabled */ -#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ -#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ -#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ -#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ -#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ -#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ -#define USE_HAL_HRTIM_REGISTER_CALLBACKS 0U /* HRTIM register callback disabled */ -#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ -#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ -#define USE_HAL_JPEG_REGISTER_CALLBACKS 0U /* JPEG register callback disabled */ -#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ -#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ -#define USE_HAL_MDIOS_REGISTER_CALLBACKS 0U /* MDIO register callback disabled */ -#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U /* MDIO register callback disabled */ -#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ -#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ -#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ -#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ -#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ -#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ -#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ -#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 ############################## */ -/** - * @brief Uncomment the line below to expanse the "assert_param" macro in the - * HAL drivers code - */ -/* #define USE_FULL_ASSERT 1U */ - -/* ################## SPI peripheral configuration ########################## */ - -/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver - * Activated: CRC code is present inside driver - * Deactivated: CRC code cleaned from driver - */ - -#define USE_SPI_CRC 1U - -/* Includes ------------------------------------------------------------------*/ -/** - * @brief Include module's header file - */ - -#ifdef HAL_RCC_MODULE_ENABLED - #include "stm32l4xx_hal_rcc.h" -#endif /* HAL_RCC_MODULE_ENABLED */ - -#ifdef HAL_GPIO_MODULE_ENABLED - #include "stm32l4xx_hal_gpio.h" -#endif /* HAL_GPIO_MODULE_ENABLED */ - -#ifdef HAL_DMA_MODULE_ENABLED - #include "stm32l4xx_hal_dma.h" -#endif /* HAL_DMA_MODULE_ENABLED */ - -#ifdef HAL_DFSDM_MODULE_ENABLED - #include "stm32l4xx_hal_dfsdm.h" -#endif /* HAL_DFSDM_MODULE_ENABLED */ - -#ifdef HAL_CORTEX_MODULE_ENABLED - #include "stm32l4xx_hal_cortex.h" -#endif /* HAL_CORTEX_MODULE_ENABLED */ - -#ifdef HAL_ADC_MODULE_ENABLED - #include "stm32l4xx_hal_adc.h" -#endif /* HAL_ADC_MODULE_ENABLED */ - -#ifdef HAL_CAN_MODULE_ENABLED - #include "stm32l4xx_hal_can.h" -#endif /* HAL_CAN_MODULE_ENABLED */ - -#ifdef HAL_CAN_LEGACY_MODULE_ENABLED - #include "Legacy/stm32l4xx_hal_can_legacy.h" -#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ - -#ifdef HAL_COMP_MODULE_ENABLED - #include "stm32l4xx_hal_comp.h" -#endif /* HAL_COMP_MODULE_ENABLED */ - -#ifdef HAL_CRC_MODULE_ENABLED - #include "stm32l4xx_hal_crc.h" -#endif /* HAL_CRC_MODULE_ENABLED */ - -#ifdef HAL_CRYP_MODULE_ENABLED - #include "stm32l4xx_hal_cryp.h" -#endif /* HAL_CRYP_MODULE_ENABLED */ - -#ifdef HAL_DAC_MODULE_ENABLED - #include "stm32l4xx_hal_dac.h" -#endif /* HAL_DAC_MODULE_ENABLED */ - -#ifdef HAL_FIREWALL_MODULE_ENABLED - #include "stm32l4xx_hal_firewall.h" -#endif /* HAL_FIREWALL_MODULE_ENABLED */ - -#ifdef HAL_FLASH_MODULE_ENABLED - #include "stm32l4xx_hal_flash.h" -#endif /* HAL_FLASH_MODULE_ENABLED */ - -#ifdef HAL_SRAM_MODULE_ENABLED - #include "stm32l4xx_hal_sram.h" -#endif /* HAL_SRAM_MODULE_ENABLED */ - -#ifdef HAL_NOR_MODULE_ENABLED - #include "stm32l4xx_hal_nor.h" -#endif /* HAL_NOR_MODULE_ENABLED */ - -#ifdef HAL_NAND_MODULE_ENABLED - #include "stm32l4xx_hal_nand.h" -#endif /* HAL_NAND_MODULE_ENABLED */ - -#ifdef HAL_I2C_MODULE_ENABLED - #include "stm32l4xx_hal_i2c.h" -#endif /* HAL_I2C_MODULE_ENABLED */ - -#ifdef HAL_IWDG_MODULE_ENABLED - #include "stm32l4xx_hal_iwdg.h" -#endif /* HAL_IWDG_MODULE_ENABLED */ - -#ifdef HAL_LCD_MODULE_ENABLED - #include "stm32l4xx_hal_lcd.h" -#endif /* HAL_LCD_MODULE_ENABLED */ - -#ifdef HAL_LPTIM_MODULE_ENABLED -#include "stm32l4xx_hal_lptim.h" -#endif /* HAL_LPTIM_MODULE_ENABLED */ - -#ifdef HAL_OPAMP_MODULE_ENABLED -#include "stm32l4xx_hal_opamp.h" -#endif /* HAL_OPAMP_MODULE_ENABLED */ - -#ifdef HAL_PWR_MODULE_ENABLED - #include "stm32l4xx_hal_pwr.h" -#endif /* HAL_PWR_MODULE_ENABLED */ - -#ifdef HAL_QSPI_MODULE_ENABLED - #include "stm32l4xx_hal_qspi.h" -#endif /* HAL_QSPI_MODULE_ENABLED */ - -#ifdef HAL_RNG_MODULE_ENABLED - #include "stm32l4xx_hal_rng.h" -#endif /* HAL_RNG_MODULE_ENABLED */ - -#ifdef HAL_RTC_MODULE_ENABLED - #include "stm32l4xx_hal_rtc.h" -#endif /* HAL_RTC_MODULE_ENABLED */ - -#ifdef HAL_SAI_MODULE_ENABLED - #include "stm32l4xx_hal_sai.h" -#endif /* HAL_SAI_MODULE_ENABLED */ - -#ifdef HAL_SD_MODULE_ENABLED - #include "stm32l4xx_hal_sd.h" -#endif /* HAL_SD_MODULE_ENABLED */ - -#ifdef HAL_SMBUS_MODULE_ENABLED - #include "stm32l4xx_hal_smbus.h" -#endif /* HAL_SMBUS_MODULE_ENABLED */ - -#ifdef HAL_SPI_MODULE_ENABLED - #include "stm32l4xx_hal_spi.h" -#endif /* HAL_SPI_MODULE_ENABLED */ - -#ifdef HAL_SWPMI_MODULE_ENABLED - #include "stm32l4xx_hal_swpmi.h" -#endif /* HAL_SWPMI_MODULE_ENABLED */ - -#ifdef HAL_TIM_MODULE_ENABLED - #include "stm32l4xx_hal_tim.h" -#endif /* HAL_TIM_MODULE_ENABLED */ - -#ifdef HAL_TSC_MODULE_ENABLED - #include "stm32l4xx_hal_tsc.h" -#endif /* HAL_TSC_MODULE_ENABLED */ - -#ifdef HAL_UART_MODULE_ENABLED - #include "stm32l4xx_hal_uart.h" -#endif /* HAL_UART_MODULE_ENABLED */ - -#ifdef HAL_USART_MODULE_ENABLED - #include "stm32l4xx_hal_usart.h" -#endif /* HAL_USART_MODULE_ENABLED */ - -#ifdef HAL_IRDA_MODULE_ENABLED - #include "stm32l4xx_hal_irda.h" -#endif /* HAL_IRDA_MODULE_ENABLED */ - -#ifdef HAL_SMARTCARD_MODULE_ENABLED - #include "stm32l4xx_hal_smartcard.h" -#endif /* HAL_SMARTCARD_MODULE_ENABLED */ - -#ifdef HAL_WWDG_MODULE_ENABLED - #include "stm32l4xx_hal_wwdg.h" -#endif /* HAL_WWDG_MODULE_ENABLED */ - -#ifdef HAL_PCD_MODULE_ENABLED - #include "stm32l4xx_hal_pcd.h" -#endif /* HAL_PCD_MODULE_ENABLED */ - -#ifdef HAL_HCD_MODULE_ENABLED - #include "stm32l4xx_hal_hcd.h" -#endif /* HAL_HCD_MODULE_ENABLED */ - -/* Exported macro ------------------------------------------------------------*/ -#ifdef USE_FULL_ASSERT -/** - * @brief The assert_param macro is used for function's parameters check. - * @param expr: If expr is false, it calls assert_failed function - * which reports the name of the source file and the source - * line number of the call that failed. - * If expr is true, it returns no value. - * @retval None - */ - #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) -/* Exported functions ------------------------------------------------------- */ - void assert_failed(uint8_t *file, uint32_t line); -#else - #define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32L4xx_HAL_CONF_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index 9750757aa..a850d4e15 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -59,7 +59,7 @@ #define DWC2_REG(_port) ((dwc2_regs_t*) DWC2_REG_BASE) // Debug level for DWC2 -#define DWC2_DEBUG 1 +#define DWC2_DEBUG 2 static TU_ATTR_ALIGNED(4) uint32_t _setup_packet[2]; From 4431ced598ca8ee1f07d6acd7f1424f17755c155 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 2 Nov 2021 16:20:39 +0700 Subject: [PATCH 43/51] add L4 to ci, update doc --- .github/workflows/build.yml | 1 + README.rst | 2 +- docs/reference/supported.rst | 39 +++++++++++++++++++++++++++++++----- 3 files changed, 36 insertions(+), 6 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index b16cf3f87..53a1628a0 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -56,6 +56,7 @@ jobs: - 'stm32f4' - 'stm32f7' - 'stm32h7' + - 'stm32l4' steps: - name: Setup Python uses: actions/setup-python@v2 diff --git a/README.rst b/README.rst index 11804ccd1..329c0da53 100644 --- a/README.rst +++ b/README.rst @@ -47,7 +47,7 @@ The stack supports the following MCUs: - **Renesas:** RX63N, RX65N - **Silabs:** EFM32GG12 - **Sony:** CXD56 -- **ST:** STM32 series: L0, L1, F0, F1, F2, F3, F4, F7, H7 both FullSpeed and HighSpeed +- **ST:** STM32 series: L0, L1, L4, F0, F1, F2, F3, F4, F7, H7 both FullSpeed and HighSpeed - **TI:** MSP430 - **ValentyUSB:** eptri diff --git a/docs/reference/supported.rst b/docs/reference/supported.rst index c8a441f18..ef924adb4 100644 --- a/docs/reference/supported.rst +++ b/docs/reference/supported.rst @@ -305,29 +305,58 @@ Sony ST STM32 -------- -- `Adafruit Feather STM32F405 `__ -- `Micro Python PyBoard v1.1 `__ -- `STLink-V3 Mini `__ -- `STM32 L035c8 Discovery `__ -- `STM32 L4R5zi Nucleo `__ +F0 +^^ - `STM32 F070rb Nucleo `__ - `STM32 F072 Evaluation `__ - `STM32 F072rb Discovery `__ + +F1 +^^ - `STM32 F103c8 Blue Pill `__ - `STM32 F103rc Mini v2.0 `__ + +F2 +^^ - `STM32 F207zg Nucleo `__ + +F3 +^^ - `STM32 F303vc Discovery `__ + +F4 +^^ +- `Adafruit Feather STM32F405 `__ +- `Micro Python PyBoard v1.1 `__ - `STM32 F401cc Black Pill `__ - `STM32 F407vg Discovery `__ - `STM32 F411ce Black Pill `__ - `STM32 F411ve Discovery `__ - `STM32 F412zg Discovery `__ - `STM32 F412zg Nucleo `__ + +F7 +^^ + +- `STLink-V3 Mini `__ - `STM32 F723e Discovery `__ - `STM32 F746zg Nucleo `__ - `STM32 F746g Discovery `__ - `STM32 F767zi Nucleo `__ - `STM32 F769i Discovery `__ + +L0 +^^ +- `STM32 L035c8 Discovery `__ + +L4 +^^ +- `STM32 L476vg Discovery `__ +- `STM32 L4P5zg Nucleo `__ +- `STM32 L4R5zi Nucleo `__ + +H7 +^^ - `STM32 H743zi Nucleo `__ - `STM32 H743i Evaluation `__ - `STM32 H745i Discovery `__ From 1046786acf0ab35bf41009b985f7627d6b859a48 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 2 Nov 2021 18:17:59 +0700 Subject: [PATCH 44/51] change broadcom submodule path from git to http --- .gitmodules | 3 +-- hw/bsp/raspberrypi4/family.mk | 2 ++ 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/.gitmodules b/.gitmodules index b86245990..79dec144e 100644 --- a/.gitmodules +++ b/.gitmodules @@ -129,5 +129,4 @@ url = https://github.com/hathach/mm32sdk.git [submodule "hw/mcu/broadcom"] path = hw/mcu/broadcom - url = git@github.com:adafruit/broadcom-peripherals.git - branch = main-build + url = https://github.com/adafruit/broadcom-peripherals.git diff --git a/hw/bsp/raspberrypi4/family.mk b/hw/bsp/raspberrypi4/family.mk index b0326c056..b1d14a6ec 100644 --- a/hw/bsp/raspberrypi4/family.mk +++ b/hw/bsp/raspberrypi4/family.mk @@ -43,5 +43,7 @@ SRC_S += $(MCU_DIR)/broadcom/boot.S $(BUILD)/kernel8.img: $(BUILD)/$(PROJECT).elf $(OBJCOPY) -O binary $^ $@ +# Copy to kernel to netboot drive or SD card +# Change destinaation to fit your need flash: $(BUILD)/kernel8.img @$(CP) $< /home/$(USER)/Documents/code/pi4_tinyusb/boot_cpy From 0e733ae14bf4c165abcd27ccb1408927b72a0047 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 2 Nov 2021 21:46:23 +0700 Subject: [PATCH 45/51] add pi4 to ci build in build_aarch64 --- .github/workflows/build_aarch64.yml | 67 +++++++++++++++++++ .../workflows/{build.yml => build_arm.yml} | 0 .gitmodules | 1 + .../device/audio_4_channel_mic/src/main.c | 2 +- examples/device/audio_test/src/main.c | 2 +- .../device/cdc_msc_freertos/.skip.MCU_BCM2711 | 0 .../hid_composite_freertos/.skip.MCU_BCM2711 | 0 hw/bsp/raspberrypi4/family.mk | 5 +- 8 files changed, 72 insertions(+), 5 deletions(-) create mode 100644 .github/workflows/build_aarch64.yml rename .github/workflows/{build.yml => build_arm.yml} (100%) create mode 100644 examples/device/cdc_msc_freertos/.skip.MCU_BCM2711 create mode 100644 examples/device/hid_composite_freertos/.skip.MCU_BCM2711 diff --git a/.github/workflows/build_aarch64.yml b/.github/workflows/build_aarch64.yml new file mode 100644 index 000000000..0cc7a5de1 --- /dev/null +++ b/.github/workflows/build_aarch64.yml @@ -0,0 +1,67 @@ +name: Build AArch64 + +on: + pull_request: + push: + release: + types: + - created + +jobs: + # --------------------------------------- + # Build AARCH64 family + # --------------------------------------- + build-arm: + runs-on: ubuntu-latest + strategy: + fail-fast: false + matrix: + family: + # Alphabetical order + - 'raspberrypi4' + steps: + - name: Setup Python + uses: actions/setup-python@v2 + + - name: Checkout TinyUSB + uses: actions/checkout@v2 + + - name: Checkout common submodules in lib + run: git submodule update --init lib/FreeRTOS-Kernel lib/lwip lib/sct_neopixel + + - name: Checkout hathach/linkermap + uses: actions/checkout@v2 + with: + repository: hathach/linkermap + path: linkermap + + - name: Set Toolchain URL + run: echo >> $GITHUB_ENV TOOLCHAIN_URL=https://developer.arm.com/-/media/Files/downloads/gnu-a/10.3-2021.07/binrel/gcc-arm-10.3-2021.07-x86_64-aarch64-none-elf.tar.xz + + - name: Cache Toolchain + uses: actions/cache@v2 + id: cache-toolchain + with: + path: ~/cache/ + key: ${{ runner.os }}-21-11-02-${{ env.TOOLCHAIN_URL }} + + - name: Install Toolchain + if: steps.cache-toolchain.outputs.cache-hit != 'true' + run: | + mkdir -p ~/cache/toolchain + wget --progress=dot:mega $TOOLCHAIN_URL -O toolchain.tar.gz + tar -C ~/cache/toolchain -xaf toolchain.tar.gz + + - name: Set Toolchain Path + run: echo >> $GITHUB_PATH `echo ~/cache/toolchain/*/bin` + + - name: Build + run: python3 tools/build_family.py ${{ matrix.family }} + + - name: Linker Map + run: | + pip install linkermap/ + for ex in `ls -d examples/device/*/`; do \ + find ${ex} -name *.map -print -quit | \ + xargs -I % sh -c 'echo "::group::%"; linkermap -v %; echo "::endgroup::"'; \ + done diff --git a/.github/workflows/build.yml b/.github/workflows/build_arm.yml similarity index 100% rename from .github/workflows/build.yml rename to .github/workflows/build_arm.yml diff --git a/.gitmodules b/.gitmodules index 79dec144e..a95e64ee6 100644 --- a/.gitmodules +++ b/.gitmodules @@ -130,3 +130,4 @@ [submodule "hw/mcu/broadcom"] path = hw/mcu/broadcom url = https://github.com/adafruit/broadcom-peripherals.git + branch = main-build diff --git a/examples/device/audio_4_channel_mic/src/main.c b/examples/device/audio_4_channel_mic/src/main.c index 983b87e5b..d085dd43a 100644 --- a/examples/device/audio_4_channel_mic/src/main.c +++ b/examples/device/audio_4_channel_mic/src/main.c @@ -141,7 +141,7 @@ void tud_resume_cb(void) void audio_task(void) { // Yet to be filled - e.g. put meas data into TX FIFOs etc. - asm("nop"); + // asm("nop"); } //--------------------------------------------------------------------+ diff --git a/examples/device/audio_test/src/main.c b/examples/device/audio_test/src/main.c index 9a2fdd3a1..ed13ce993 100644 --- a/examples/device/audio_test/src/main.c +++ b/examples/device/audio_test/src/main.c @@ -142,7 +142,7 @@ void tud_resume_cb(void) void audio_task(void) { // Yet to be filled - e.g. put meas data into TX FIFOs etc. - asm("nop"); + // asm("nop"); } //--------------------------------------------------------------------+ diff --git a/examples/device/cdc_msc_freertos/.skip.MCU_BCM2711 b/examples/device/cdc_msc_freertos/.skip.MCU_BCM2711 new file mode 100644 index 000000000..e69de29bb diff --git a/examples/device/hid_composite_freertos/.skip.MCU_BCM2711 b/examples/device/hid_composite_freertos/.skip.MCU_BCM2711 new file mode 100644 index 000000000..e69de29bb diff --git a/hw/bsp/raspberrypi4/family.mk b/hw/bsp/raspberrypi4/family.mk index b1d14a6ec..2e61b9e74 100644 --- a/hw/bsp/raspberrypi4/family.mk +++ b/hw/bsp/raspberrypi4/family.mk @@ -1,9 +1,8 @@ -UF2_FAMILY_ID = 0x57755a57 +MCU_DIR = hw/mcu/broadcom +DEPS_SUBMODULES += $(MCU_DIR) include $(TOP)/$(BOARD_PATH)/board.mk -MCU_DIR = hw/mcu/broadcom - CC = clang CFLAGS += \ From 28b177484d15971dc12ec76dfe71ffcae433835a Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 2 Nov 2021 22:27:00 +0700 Subject: [PATCH 46/51] skip net example for pi4 due to ssize_t conflict --- examples/device/net_lwip_webserver/.skip.MCU_BCM2711 | 1 + 1 file changed, 1 insertion(+) create mode 100644 examples/device/net_lwip_webserver/.skip.MCU_BCM2711 diff --git a/examples/device/net_lwip_webserver/.skip.MCU_BCM2711 b/examples/device/net_lwip_webserver/.skip.MCU_BCM2711 new file mode 100644 index 000000000..bdc68f5db --- /dev/null +++ b/examples/device/net_lwip_webserver/.skip.MCU_BCM2711 @@ -0,0 +1 @@ +tinyusb/lib/lwip/src/include/lwip/arch.h:202:13: error: conflicting types for 'ssize_t' \ No newline at end of file From e16506cb52d6d8e8b2a2e2910f10c32a89a6d322 Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 3 Nov 2021 12:24:10 +0700 Subject: [PATCH 47/51] clean up --- hw/bsp/raspberrypi4/family.c | 17 +++-------------- hw/bsp/raspberrypi4/family.mk | 3 +++ src/portable/synopsys/dwc2/dwc2_bcm.h | 5 +++++ 3 files changed, 11 insertions(+), 14 deletions(-) diff --git a/hw/bsp/raspberrypi4/family.c b/hw/bsp/raspberrypi4/family.c index ffeb05f9f..95b28c6fc 100644 --- a/hw/bsp/raspberrypi4/family.c +++ b/hw/bsp/raspberrypi4/family.c @@ -30,10 +30,9 @@ #include "broadcom/interrupts.h" #include "broadcom/io.h" #include "broadcom/mmu.h" +//#include "broadcom/caches.h" #include "broadcom/vcmailbox.h" -uint32_t SystemCoreClock = 700 * 1000 * 1000; - //--------------------------------------------------------------------+ // Forward USB interrupt events to TinyUSB IRQ Handler //--------------------------------------------------------------------+ @@ -49,11 +48,6 @@ void USB_IRQHandler(void) //--------------------------------------------------------------------+ // Board porting API //--------------------------------------------------------------------+ - -void print(const char* str) { - board_uart_write(str, strlen(str)); -} - void board_init(void) { gpio_initOutputPinWithPullNone(18); @@ -63,13 +57,14 @@ void board_init(void) gpio_setPinOutputBool(18, true); gpio_initOutputPinWithPullNone(42); setup_mmu_flat_map(); +// init_caches(); + // gpio_initOutputPinWithPullNone(23); // gpio_initOutputPinWithPullNone(24); // gpio_initOutputPinWithPullNone(25); gpio_setPinOutputBool(18, false); uart_init(); gpio_setPinOutputBool(18, true); - const char* greeting = "hello to gdb2\r\n"; gpio_setPinOutputBool(18, false); for (size_t i = 0; i < 5; i++) { // while (true) { @@ -92,7 +87,6 @@ void board_init(void) } // uart_writeText("hello from io\n"); // gpio_setPinOutputBool(24, true); - board_uart_write(greeting, strlen(greeting)); // gpio_setPinOutputBool(24, false); // gpio_setPinOutputBool(25, true); // print(); @@ -110,13 +104,8 @@ void board_init(void) // } // while (1) uart_update(); - printf("hello %d\r\n", 21); - // Turn on USB peripheral. - print("Turning on USB power\r\n"); - vcmailbox_set_power_state(VCMAILBOX_DEVICE_USB_HCD, true); - print("USB power on\r\n"); BP_SetPriority(USB_IRQn, 0x00); BP_ClearPendingIRQ(USB_IRQn); diff --git a/hw/bsp/raspberrypi4/family.mk b/hw/bsp/raspberrypi4/family.mk index 2e61b9e74..2a0a87788 100644 --- a/hw/bsp/raspberrypi4/family.mk +++ b/hw/bsp/raspberrypi4/family.mk @@ -6,6 +6,7 @@ include $(TOP)/$(BOARD_PATH)/board.mk CC = clang CFLAGS += \ + -mcpu=cortex-a72 \ -Wall \ -O0 \ -ffreestanding \ @@ -26,6 +27,8 @@ SRC_C += \ $(MCU_DIR)/broadcom/mmu.c \ $(MCU_DIR)/broadcom/vcmailbox.c +# $(MCU_DIR)/broadcom/caches.c \ + CROSS_COMPILE = aarch64-none-elf- SKIP_NANOLIB = 1 diff --git a/src/portable/synopsys/dwc2/dwc2_bcm.h b/src/portable/synopsys/dwc2/dwc2_bcm.h index 38d10930c..317e79cf7 100644 --- a/src/portable/synopsys/dwc2/dwc2_bcm.h +++ b/src/portable/synopsys/dwc2/dwc2_bcm.h @@ -32,11 +32,16 @@ #endif #include "broadcom/interrupts.h" +//#include "broadcom/caches.h" #define DWC2_REG_BASE 0xFE980000UL #define DWC2_EP_MAX 8 #define DWC2_EP_FIFO_SIZE 4096 +//#define dcache_clean(_addr, _size) data_clean(_addr, _size) +//#define dcache_invalidate(_addr, _size) data_invalidate(_addr, _size) +//#define dcache_clean_invalidate(_addr, _size) data_clean_and_invalidate(_addr, _size) + TU_ATTR_ALWAYS_INLINE static inline void dwc2_dcd_int_enable(uint8_t rhport) { From 0faff5a859cfd91f92a9b91f65a1d6a164f0a7be Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 3 Nov 2021 13:13:08 +0700 Subject: [PATCH 48/51] update broadcom peripherals to latest --- hw/bsp/raspberrypi4/family.c | 4 ++-- hw/bsp/raspberrypi4/family.mk | 2 +- hw/mcu/broadcom | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/hw/bsp/raspberrypi4/family.c b/hw/bsp/raspberrypi4/family.c index 95b28c6fc..7a7a0e9ff 100644 --- a/hw/bsp/raspberrypi4/family.c +++ b/hw/bsp/raspberrypi4/family.c @@ -30,7 +30,7 @@ #include "broadcom/interrupts.h" #include "broadcom/io.h" #include "broadcom/mmu.h" -//#include "broadcom/caches.h" +#include "broadcom/caches.h" #include "broadcom/vcmailbox.h" //--------------------------------------------------------------------+ @@ -57,7 +57,7 @@ void board_init(void) gpio_setPinOutputBool(18, true); gpio_initOutputPinWithPullNone(42); setup_mmu_flat_map(); -// init_caches(); + init_caches(); // gpio_initOutputPinWithPullNone(23); // gpio_initOutputPinWithPullNone(24); diff --git a/hw/bsp/raspberrypi4/family.mk b/hw/bsp/raspberrypi4/family.mk index 2a0a87788..475cfa4ff 100644 --- a/hw/bsp/raspberrypi4/family.mk +++ b/hw/bsp/raspberrypi4/family.mk @@ -25,9 +25,9 @@ SRC_C += \ $(MCU_DIR)/broadcom/interrupts.c \ $(MCU_DIR)/broadcom/io.c \ $(MCU_DIR)/broadcom/mmu.c \ + $(MCU_DIR)/broadcom/caches.c \ $(MCU_DIR)/broadcom/vcmailbox.c -# $(MCU_DIR)/broadcom/caches.c \ CROSS_COMPILE = aarch64-none-elf- diff --git a/hw/mcu/broadcom b/hw/mcu/broadcom index 55cd6f798..d126323fc 160000 --- a/hw/mcu/broadcom +++ b/hw/mcu/broadcom @@ -1 +1 @@ -Subproject commit 55cd6f798a45cac905d7bf81baa2bcbf7de7c42e +Subproject commit d126323fc77e81d1f18677a439685a4754ea02aa From b51d038b656688b6150470d23752a306ee150da3 Mon Sep 17 00:00:00 2001 From: hathach Date: Thu, 4 Nov 2021 12:30:11 +0700 Subject: [PATCH 49/51] fix issue with bcm2711 caching issue by ading ISB() after dwc2_dcd_int_enable90 also add hwcfg_list for reference --- src/portable/synopsys/dwc2/dcd_dwc2.c | 16 +- src/portable/synopsys/dwc2/dwc2_bcm.h | 10 +- src/portable/synopsys/dwc2/hwcfg_list.md | 722 +++++++++++++++++++++++ 3 files changed, 743 insertions(+), 5 deletions(-) create mode 100644 src/portable/synopsys/dwc2/hwcfg_list.md diff --git a/src/portable/synopsys/dwc2/dcd_dwc2.c b/src/portable/synopsys/dwc2/dcd_dwc2.c index a850d4e15..3967f225e 100644 --- a/src/portable/synopsys/dwc2/dcd_dwc2.c +++ b/src/portable/synopsys/dwc2/dcd_dwc2.c @@ -56,11 +56,25 @@ // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ +// DWC2 registers #define DWC2_REG(_port) ((dwc2_regs_t*) DWC2_REG_BASE) // Debug level for DWC2 #define DWC2_DEBUG 2 +#ifndef dcache_clean +#define dcache_clean(_addr, _size) +#endif + +#ifndef dcache_invalidate +#define dcache_invalidate(_addr, _size) +#endif + +#ifndef dcache_clean_invalidate +#define dcache_clean_invalidate(_addr, _size) +#endif + + static TU_ATTR_ALIGNED(4) uint32_t _setup_packet[2]; typedef struct { @@ -71,7 +85,7 @@ typedef struct { uint8_t interval; } xfer_ctl_t; -xfer_ctl_t xfer_status[DWC2_EP_MAX][2]; +static xfer_ctl_t xfer_status[DWC2_EP_MAX][2]; #define XFER_CTL_BASE(_ep, _dir) (&xfer_status[_ep][_dir]) // EP0 transfers are limited to 1 packet - larger sizes has to be split diff --git a/src/portable/synopsys/dwc2/dwc2_bcm.h b/src/portable/synopsys/dwc2/dwc2_bcm.h index 317e79cf7..0263d19ba 100644 --- a/src/portable/synopsys/dwc2/dwc2_bcm.h +++ b/src/portable/synopsys/dwc2/dwc2_bcm.h @@ -32,21 +32,22 @@ #endif #include "broadcom/interrupts.h" -//#include "broadcom/caches.h" +#include "broadcom/caches.h" #define DWC2_REG_BASE 0xFE980000UL #define DWC2_EP_MAX 8 #define DWC2_EP_FIFO_SIZE 4096 -//#define dcache_clean(_addr, _size) data_clean(_addr, _size) -//#define dcache_invalidate(_addr, _size) data_invalidate(_addr, _size) -//#define dcache_clean_invalidate(_addr, _size) data_clean_and_invalidate(_addr, _size) +#define dcache_clean(_addr, _size) data_clean(_addr, _size) +#define dcache_invalidate(_addr, _size) data_invalidate(_addr, _size) +#define dcache_clean_invalidate(_addr, _size) data_clean_and_invalidate(_addr, _size) TU_ATTR_ALWAYS_INLINE static inline void dwc2_dcd_int_enable(uint8_t rhport) { (void) rhport; BP_EnableIRQ(USB_IRQn); + __asm__ volatile("isb"); } TU_ATTR_ALWAYS_INLINE @@ -54,6 +55,7 @@ static inline void dwc2_dcd_int_disable (uint8_t rhport) { (void) rhport; BP_DisableIRQ(USB_IRQn); + __asm__ volatile("isb"); } static inline void dwc2_remote_wakeup_delay(void) diff --git a/src/portable/synopsys/dwc2/hwcfg_list.md b/src/portable/synopsys/dwc2/hwcfg_list.md new file mode 100644 index 000000000..495a30fd0 --- /dev/null +++ b/src/portable/synopsys/dwc2/hwcfg_list.md @@ -0,0 +1,722 @@ +# DWC2 Hardware Configuration Registers + +## Broadcom BCM2711 (Pi4) + +dwc2->guid = 2708A000 +dwc2->gsnpsid = 4F54280A +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 228DDD50 +hw_cfg2->op_mode = 0 +hw_cfg2->arch = 2 +hw_cfg2->point2point = 0 +hw_cfg2->hs_phy_type = 1 +hw_cfg2->fs_phy_type = 1 +hw_cfg2->num_dev_ep = 7 +hw_cfg2->num_host_ch = 7 +hw_cfg2->period_channel_support = 1 +hw_cfg2->enable_dynamic_fifo = 1 +hw_cfg2->mul_cpu_int = 0 +hw_cfg2->nperiod_tx_q_depth = 2 +hw_cfg2->host_period_tx_q_depth = 2 +hw_cfg2->dev_token_q_depth = 8 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = FF000E8 +hw_cfg3->xfer_size_width = 8 +hw_cfg3->packet_size_width = 6 +hw_cfg3->otg_enable = 1 +hw_cfg3->i2c_enable = 0 +hw_cfg3->vendor_ctrl_itf = 0 +hw_cfg3->optional_feature_removed = 0 +hw_cfg3->synch_reset = 0 +hw_cfg3->otg_adp_support = 0 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 0 +hw_cfg3->lpm_mode = 0 +hw_cfg3->total_fifo_size = 4080 + +dwc2->ghwcfg4 = 1FF00020 +hw_cfg4->num_dev_period_in_ep = 0 +hw_cfg4->power_optimized = 0 +hw_cfg4->ahb_freq_min = 1 +hw_cfg4->hibernation = 0 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 0 +hw_cfg4->acg_enable = 0 +hw_cfg4->utmi_phy_data_width = 0 +hw_cfg4->dev_ctrl_ep_num = 0 +hw_cfg4->iddg_filter_enabled = 1 +hw_cfg4->vbus_valid_filter_enabled = 1 +hw_cfg4->a_valid_filter_enabled = 1 +hw_cfg4->b_valid_filter_enabled = 1 +hw_cfg4->dedicated_fifos = 1 +hw_cfg4->num_dev_in_eps = 15 +hw_cfg4->dma_desc_enable = 0 +hw_cfg4->dma_dynamic = 0 + +## EFM32GG FS + +dwc2->guid = 0 +dwc2->gsnpsid = 4F54330A +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 228F5910 +hw_cfg2->op_mode = 0 +hw_cfg2->arch = 2 +hw_cfg2->point2point = 0 +hw_cfg2->hs_phy_type = 0 +hw_cfg2->fs_phy_type = 1 +hw_cfg2->num_dev_ep = 6 +hw_cfg2->num_host_ch = 13 +hw_cfg2->period_channel_support = 1 +hw_cfg2->enable_dynamic_fifo = 1 +hw_cfg2->mul_cpu_int = 0 +hw_cfg2->nperiod_tx_q_depth = 2 +hw_cfg2->host_period_tx_q_depth = 2 +hw_cfg2->dev_token_q_depth = 8 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = 1F204E8 +hw_cfg3->xfer_size_width = 8 +hw_cfg3->packet_size_width = 6 +hw_cfg3->otg_enable = 1 +hw_cfg3->i2c_enable = 0 +hw_cfg3->vendor_ctrl_itf = 0 +hw_cfg3->optional_feature_removed = 1 +hw_cfg3->synch_reset = 0 +hw_cfg3->otg_adp_support = 0 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 0 +hw_cfg3->lpm_mode = 0 +hw_cfg3->total_fifo_size = 498 + +dwc2->ghwcfg4 = 1BF08030 +hw_cfg4->num_dev_period_in_ep = 0 +hw_cfg4->power_optimized = 1 +hw_cfg4->ahb_freq_min = 1 +hw_cfg4->hibernation = 0 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 0 +hw_cfg4->acg_enable = 0 +hw_cfg4->utmi_phy_data_width = 2 +hw_cfg4->dev_ctrl_ep_num = 0 +hw_cfg4->iddg_filter_enabled = 1 +hw_cfg4->vbus_valid_filter_enabled = 1 +hw_cfg4->a_valid_filter_enabled = 1 +hw_cfg4->b_valid_filter_enabled = 1 +hw_cfg4->dedicated_fifos = 1 +hw_cfg4->num_dev_in_eps = 13 +hw_cfg4->dma_desc_enable = 0 +hw_cfg4->dma_dynamic = 0 + +## ESP32-S2 Fullspeed + +dwc2->guid = 0 +dwc2->gsnpsid = 4F54400A +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 224DD930 +hw_cfg2->op_mode = 2 +hw_cfg2->arch = 3 +hw_cfg2->point2point = 0 +hw_cfg2->hs_phy_type = 1 +hw_cfg2->fs_phy_type = 2 +hw_cfg2->num_dev_ep = 6 +hw_cfg2->num_host_ch = 9 +hw_cfg2->period_channel_support = 0 +hw_cfg2->enable_dynamic_fifo = 1 +hw_cfg2->mul_cpu_int = 1 +hw_cfg2->nperiod_tx_q_depth = 1 +hw_cfg2->host_period_tx_q_depth = 2 +hw_cfg2->dev_token_q_depth = 22 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = C804B5 +hw_cfg3->xfer_size_width = 10 +hw_cfg3->packet_size_width = 5 +hw_cfg3->otg_enable = 0 +hw_cfg3->i2c_enable = 0 +hw_cfg3->vendor_ctrl_itf = 1 +hw_cfg3->optional_feature_removed = 0 +hw_cfg3->synch_reset = 1 +hw_cfg3->otg_adp_support = 1 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 1 +hw_cfg3->lpm_mode = 0 +hw_cfg3->total_fifo_size = 23130 + +dwc2->ghwcfg4 = D3F0A030 +hw_cfg4->num_dev_period_in_ep = 10 +hw_cfg4->power_optimized = 1 +hw_cfg4->ahb_freq_min = 0 +hw_cfg4->hibernation = 1 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 1 +hw_cfg4->acg_enable = 1 +hw_cfg4->utmi_phy_data_width = 1 +hw_cfg4->dev_ctrl_ep_num = 10 +hw_cfg4->iddg_filter_enabled = 1 +hw_cfg4->vbus_valid_filter_enabled = 0 +hw_cfg4->a_valid_filter_enabled = 1 +hw_cfg4->b_valid_filter_enabled = 0 +hw_cfg4->dedicated_fifos = 0 +hw_cfg4->num_dev_in_eps = 13 +hw_cfg4->dma_desc_enable = 0 +hw_cfg4->dma_dynamic = 1 + +## STM32F407 and STM32F207 + +STM32F407 and STM32F207 are exactly the same + +### STM32F407 Fullspeed + +dwc2->guid = 1200 +dwc2->gsnpsid = 4F54281A +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 229DCD20 +hw_cfg2->op_mode = 0 +hw_cfg2->arch = 0 +hw_cfg2->point2point = 1 +hw_cfg2->hs_phy_type = 0 +hw_cfg2->fs_phy_type = 1 +hw_cfg2->num_dev_ep = 3 +hw_cfg2->num_host_ch = 7 +hw_cfg2->period_channel_support = 1 +hw_cfg2->enable_dynamic_fifo = 1 +hw_cfg2->mul_cpu_int = 1 +hw_cfg2->nperiod_tx_q_depth = 2 +hw_cfg2->host_period_tx_q_depth = 2 +hw_cfg2->dev_token_q_depth = 8 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = 20001E8 +hw_cfg3->xfer_size_width = 8 +hw_cfg3->packet_size_width = 6 +hw_cfg3->otg_enable = 1 +hw_cfg3->i2c_enable = 1 +hw_cfg3->vendor_ctrl_itf = 0 +hw_cfg3->optional_feature_removed = 0 +hw_cfg3->synch_reset = 0 +hw_cfg3->otg_adp_support = 0 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 0 +hw_cfg3->lpm_mode = 0 +hw_cfg3->total_fifo_size = 512 + +dwc2->ghwcfg4 = FF08030 +hw_cfg4->num_dev_period_in_ep = 0 +hw_cfg4->power_optimized = 1 +hw_cfg4->ahb_freq_min = 1 +hw_cfg4->hibernation = 0 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 0 +hw_cfg4->acg_enable = 0 +hw_cfg4->utmi_phy_data_width = 2 +hw_cfg4->dev_ctrl_ep_num = 0 +hw_cfg4->iddg_filter_enabled = 1 +hw_cfg4->vbus_valid_filter_enabled = 1 +hw_cfg4->a_valid_filter_enabled = 1 +hw_cfg4->b_valid_filter_enabled = 1 +hw_cfg4->dedicated_fifos = 1 +hw_cfg4->num_dev_in_eps = 7 +hw_cfg4->dma_desc_enable = 0 +hw_cfg4->dma_dynamic = 0 + +### STM32F407 Highspeed + +dwc2->guid = 1100 +dwc2->gsnpsid = 4F54281A +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 229ED590 +hw_cfg2->op_mode = 0 +hw_cfg2->arch = 2 +hw_cfg2->point2point = 0 +hw_cfg2->hs_phy_type = 2 +hw_cfg2->fs_phy_type = 1 +hw_cfg2->num_dev_ep = 5 +hw_cfg2->num_host_ch = 11 +hw_cfg2->period_channel_support = 1 +hw_cfg2->enable_dynamic_fifo = 1 +hw_cfg2->mul_cpu_int = 1 +hw_cfg2->nperiod_tx_q_depth = 2 +hw_cfg2->host_period_tx_q_depth = 2 +hw_cfg2->dev_token_q_depth = 8 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = 3F403E8 +hw_cfg3->xfer_size_width = 8 +hw_cfg3->packet_size_width = 6 +hw_cfg3->otg_enable = 1 +hw_cfg3->i2c_enable = 1 +hw_cfg3->vendor_ctrl_itf = 1 +hw_cfg3->optional_feature_removed = 0 +hw_cfg3->synch_reset = 0 +hw_cfg3->otg_adp_support = 0 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 0 +hw_cfg3->lpm_mode = 0 +hw_cfg3->total_fifo_size = 1012 + +dwc2->ghwcfg4 = 17F00030 +hw_cfg4->num_dev_period_in_ep = 0 +hw_cfg4->power_optimized = 1 +hw_cfg4->ahb_freq_min = 1 +hw_cfg4->hibernation = 0 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 0 +hw_cfg4->acg_enable = 0 +hw_cfg4->utmi_phy_data_width = 0 +hw_cfg4->dev_ctrl_ep_num = 0 +hw_cfg4->iddg_filter_enabled = 1 +hw_cfg4->vbus_valid_filter_enabled = 1 +hw_cfg4->a_valid_filter_enabled = 1 +hw_cfg4->b_valid_filter_enabled = 1 +hw_cfg4->dedicated_fifos = 1 +hw_cfg4->num_dev_in_eps = 11 +hw_cfg4->dma_desc_enable = 0 +hw_cfg4->dma_dynamic = 0 + +## STM32F411 Fullspeed + +dwc2->guid = 1200 +dwc2->gsnpsid = 4F54281A +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 229DCD20 +hw_cfg2->op_mode = 0 +hw_cfg2->arch = 0 +hw_cfg2->point2point = 1 +hw_cfg2->hs_phy_type = 0 +hw_cfg2->fs_phy_type = 1 +hw_cfg2->num_dev_ep = 3 +hw_cfg2->num_host_ch = 7 +hw_cfg2->period_channel_support = 1 +hw_cfg2->enable_dynamic_fifo = 1 +hw_cfg2->mul_cpu_int = 1 +hw_cfg2->nperiod_tx_q_depth = 2 +hw_cfg2->host_period_tx_q_depth = 2 +hw_cfg2->dev_token_q_depth = 8 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = 20001E8 +hw_cfg3->xfer_size_width = 8 +hw_cfg3->packet_size_width = 6 +hw_cfg3->otg_enable = 1 +hw_cfg3->i2c_enable = 1 +hw_cfg3->vendor_ctrl_itf = 0 +hw_cfg3->optional_feature_removed = 0 +hw_cfg3->synch_reset = 0 +hw_cfg3->otg_adp_support = 0 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 0 +hw_cfg3->lpm_mode = 0 +hw_cfg3->total_fifo_size = 512 + +dwc2->ghwcfg4 = FF08030 +hw_cfg4->num_dev_period_in_ep = 0 +hw_cfg4->power_optimized = 1 +hw_cfg4->ahb_freq_min = 1 +hw_cfg4->hibernation = 0 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 0 +hw_cfg4->acg_enable = 0 +hw_cfg4->utmi_phy_data_width = 2 +hw_cfg4->dev_ctrl_ep_num = 0 +hw_cfg4->iddg_filter_enabled = 1 +hw_cfg4->vbus_valid_filter_enabled = 1 +hw_cfg4->a_valid_filter_enabled = 1 +hw_cfg4->b_valid_filter_enabled = 1 +hw_cfg4->dedicated_fifos = 1 +hw_cfg4->num_dev_in_eps = 7 +hw_cfg4->dma_desc_enable = 0 +hw_cfg4->dma_dynamic = 0 + +## STM32F412 FS + +dwc2->guid = 2000 +dwc2->gsnpsid = 4F54320A +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 229ED520 +hw_cfg2->op_mode = 0 +hw_cfg2->arch = 0 +hw_cfg2->point2point = 1 +hw_cfg2->hs_phy_type = 0 +hw_cfg2->fs_phy_type = 1 +hw_cfg2->num_dev_ep = 5 +hw_cfg2->num_host_ch = 11 +hw_cfg2->period_channel_support = 1 +hw_cfg2->enable_dynamic_fifo = 1 +hw_cfg2->mul_cpu_int = 1 +hw_cfg2->nperiod_tx_q_depth = 2 +hw_cfg2->host_period_tx_q_depth = 2 +hw_cfg2->dev_token_q_depth = 8 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = 200D1E8 +hw_cfg3->xfer_size_width = 8 +hw_cfg3->packet_size_width = 6 +hw_cfg3->otg_enable = 1 +hw_cfg3->i2c_enable = 1 +hw_cfg3->vendor_ctrl_itf = 0 +hw_cfg3->optional_feature_removed = 0 +hw_cfg3->synch_reset = 0 +hw_cfg3->otg_adp_support = 1 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 1 +hw_cfg3->lpm_mode = 1 +hw_cfg3->total_fifo_size = 512 + +dwc2->ghwcfg4 = 17F08030 +hw_cfg4->num_dev_period_in_ep = 0 +hw_cfg4->power_optimized = 1 +hw_cfg4->ahb_freq_min = 1 +hw_cfg4->hibernation = 0 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 0 +hw_cfg4->acg_enable = 0 +hw_cfg4->utmi_phy_data_width = 2 +hw_cfg4->dev_ctrl_ep_num = 0 +hw_cfg4->iddg_filter_enabled = 1 +hw_cfg4->vbus_valid_filter_enabled = 1 +hw_cfg4->a_valid_filter_enabled = 1 +hw_cfg4->b_valid_filter_enabled = 1 +hw_cfg4->dedicated_fifos = 1 +hw_cfg4->num_dev_in_eps = 11 +hw_cfg4->dma_desc_enable = 0 +hw_cfg4->dma_dynamic = 0 + +## STM32F723 + +### STM32F723 HighSpeed + +dwc2->guid = 3100 +dwc2->gsnpsid = 4F54330A +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 229FE1D0 +hw_cfg2->op_mode = 0 +hw_cfg2->arch = 2 +hw_cfg2->point2point = 0 +hw_cfg2->hs_phy_type = 3 +hw_cfg2->fs_phy_type = 1 +hw_cfg2->num_dev_ep = 8 +hw_cfg2->num_host_ch = 15 +hw_cfg2->period_channel_support = 1 +hw_cfg2->enable_dynamic_fifo = 1 +hw_cfg2->mul_cpu_int = 1 +hw_cfg2->nperiod_tx_q_depth = 2 +hw_cfg2->host_period_tx_q_depth = 2 +hw_cfg2->dev_token_q_depth = 8 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = 3EED2E8 +hw_cfg3->xfer_size_width = 8 +hw_cfg3->packet_size_width = 6 +hw_cfg3->otg_enable = 1 +hw_cfg3->i2c_enable = 0 +hw_cfg3->vendor_ctrl_itf = 1 +hw_cfg3->optional_feature_removed = 0 +hw_cfg3->synch_reset = 0 +hw_cfg3->otg_adp_support = 1 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 1 +hw_cfg3->lpm_mode = 1 +hw_cfg3->total_fifo_size = 1006 + +dwc2->ghwcfg4 = 23F00030 +hw_cfg4->num_dev_period_in_ep = 0 +hw_cfg4->power_optimized = 1 +hw_cfg4->ahb_freq_min = 1 +hw_cfg4->hibernation = 0 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 0 +hw_cfg4->acg_enable = 0 +hw_cfg4->utmi_phy_data_width = 0 +hw_cfg4->dev_ctrl_ep_num = 0 +hw_cfg4->iddg_filter_enabled = 1 +hw_cfg4->vbus_valid_filter_enabled = 1 +hw_cfg4->a_valid_filter_enabled = 1 +hw_cfg4->b_valid_filter_enabled = 1 +hw_cfg4->dedicated_fifos = 1 +hw_cfg4->num_dev_in_eps = 1 +hw_cfg4->dma_desc_enable = 1 +hw_cfg4->dma_dynamic = 0 + +### STM32F723 Fullspeed + +dwc2->guid = 3000 +dwc2->gsnpsid = 4F54330A +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 229ED520 +hw_cfg2->op_mode = 0 +hw_cfg2->arch = 0 +hw_cfg2->point2point = 1 +hw_cfg2->hs_phy_type = 0 +hw_cfg2->fs_phy_type = 1 +hw_cfg2->num_dev_ep = 5 +hw_cfg2->num_host_ch = 11 +hw_cfg2->period_channel_support = 1 +hw_cfg2->enable_dynamic_fifo = 1 +hw_cfg2->mul_cpu_int = 1 +hw_cfg2->nperiod_tx_q_depth = 2 +hw_cfg2->host_period_tx_q_depth = 2 +hw_cfg2->dev_token_q_depth = 8 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = 200D1E8 +hw_cfg3->xfer_size_width = 8 +hw_cfg3->packet_size_width = 6 +hw_cfg3->otg_enable = 1 +hw_cfg3->i2c_enable = 1 +hw_cfg3->vendor_ctrl_itf = 0 +hw_cfg3->optional_feature_removed = 0 +hw_cfg3->synch_reset = 0 +hw_cfg3->otg_adp_support = 1 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 1 +hw_cfg3->lpm_mode = 1 +hw_cfg3->total_fifo_size = 512 + +dwc2->ghwcfg4 = 17F08030 +hw_cfg4->num_dev_period_in_ep = 0 +hw_cfg4->power_optimized = 1 +hw_cfg4->ahb_freq_min = 1 +hw_cfg4->hibernation = 0 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 0 +hw_cfg4->acg_enable = 0 +hw_cfg4->utmi_phy_data_width = 2 +hw_cfg4->dev_ctrl_ep_num = 0 +hw_cfg4->iddg_filter_enabled = 1 +hw_cfg4->vbus_valid_filter_enabled = 1 +hw_cfg4->a_valid_filter_enabled = 1 +hw_cfg4->b_valid_filter_enabled = 1 +hw_cfg4->dedicated_fifos = 1 +hw_cfg4->num_dev_in_eps = 11 +hw_cfg4->dma_desc_enable = 0 +hw_cfg4->dma_dynamic = 0 + +## STM32F767 FS + +dwc2->guid = 2000 +dwc2->gsnpsid = 4F54320A +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 229ED520 +hw_cfg2->op_mode = 0 +hw_cfg2->arch = 0 +hw_cfg2->point2point = 1 +hw_cfg2->hs_phy_type = 0 +hw_cfg2->fs_phy_type = 1 +hw_cfg2->num_dev_ep = 5 +hw_cfg2->num_host_ch = 11 +hw_cfg2->period_channel_support = 1 +hw_cfg2->enable_dynamic_fifo = 1 +hw_cfg2->mul_cpu_int = 1 +hw_cfg2->nperiod_tx_q_depth = 2 +hw_cfg2->host_period_tx_q_depth = 2 +hw_cfg2->dev_token_q_depth = 8 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = 200D1E8 +hw_cfg3->xfer_size_width = 8 +hw_cfg3->packet_size_width = 6 +hw_cfg3->otg_enable = 1 +hw_cfg3->i2c_enable = 1 +hw_cfg3->vendor_ctrl_itf = 0 +hw_cfg3->optional_feature_removed = 0 +hw_cfg3->synch_reset = 0 +hw_cfg3->otg_adp_support = 1 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 1 +hw_cfg3->lpm_mode = 1 +hw_cfg3->total_fifo_size = 512 + +dwc2->ghwcfg4 = 17F08030 +hw_cfg4->num_dev_period_in_ep = 0 +hw_cfg4->power_optimized = 1 +hw_cfg4->ahb_freq_min = 1 +hw_cfg4->hibernation = 0 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 0 +hw_cfg4->acg_enable = 0 +hw_cfg4->utmi_phy_data_width = 2 +hw_cfg4->dev_ctrl_ep_num = 0 +hw_cfg4->iddg_filter_enabled = 1 +hw_cfg4->vbus_valid_filter_enabled = 1 +hw_cfg4->a_valid_filter_enabled = 1 +hw_cfg4->b_valid_filter_enabled = 1 +hw_cfg4->dedicated_fifos = 1 +hw_cfg4->num_dev_in_eps = 11 +hw_cfg4->dma_desc_enable = 0 +hw_cfg4->dma_dynamic = 0 + +## STM32H743 (both cores HS) + +dwc2->guid = 2300 +dwc2->gsnpsid = 4F54330A +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 229FE190 +hw_cfg2->op_mode = 0 +hw_cfg2->arch = 2 +hw_cfg2->point2point = 0 +hw_cfg2->hs_phy_type = 2 +hw_cfg2->fs_phy_type = 1 +hw_cfg2->num_dev_ep = 8 +hw_cfg2->num_host_ch = 15 +hw_cfg2->period_channel_support = 1 +hw_cfg2->enable_dynamic_fifo = 1 +hw_cfg2->mul_cpu_int = 1 +hw_cfg2->nperiod_tx_q_depth = 2 +hw_cfg2->host_period_tx_q_depth = 2 +hw_cfg2->dev_token_q_depth = 8 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = 3B8D2E8 +hw_cfg3->xfer_size_width = 8 +hw_cfg3->packet_size_width = 6 +hw_cfg3->otg_enable = 1 +hw_cfg3->i2c_enable = 0 +hw_cfg3->vendor_ctrl_itf = 1 +hw_cfg3->optional_feature_removed = 0 +hw_cfg3->synch_reset = 0 +hw_cfg3->otg_adp_support = 1 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 1 +hw_cfg3->lpm_mode = 1 +hw_cfg3->total_fifo_size = 952 + +dwc2->ghwcfg4 = E3F00030 +hw_cfg4->num_dev_period_in_ep = 0 +hw_cfg4->power_optimized = 1 +hw_cfg4->ahb_freq_min = 1 +hw_cfg4->hibernation = 0 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 0 +hw_cfg4->acg_enable = 0 +hw_cfg4->utmi_phy_data_width = 0 +hw_cfg4->dev_ctrl_ep_num = 0 +hw_cfg4->iddg_filter_enabled = 1 +hw_cfg4->vbus_valid_filter_enabled = 1 +hw_cfg4->a_valid_filter_enabled = 1 +hw_cfg4->b_valid_filter_enabled = 1 +hw_cfg4->dedicated_fifos = 1 +hw_cfg4->num_dev_in_eps = 1 +hw_cfg4->dma_desc_enable = 1 +hw_cfg4->dma_dynamic = 1 + +## STM32L476 FS + +dwc2->guid = 2000 +dwc2->gsnpsid = 4F54310A +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 229ED520 +hw_cfg2->op_mode = 0 +hw_cfg2->arch = 0 +hw_cfg2->point2point = 1 +hw_cfg2->hs_phy_type = 0 +hw_cfg2->fs_phy_type = 1 +hw_cfg2->num_dev_ep = 5 +hw_cfg2->num_host_ch = 11 +hw_cfg2->period_channel_support = 1 +hw_cfg2->enable_dynamic_fifo = 1 +hw_cfg2->mul_cpu_int = 1 +hw_cfg2->nperiod_tx_q_depth = 2 +hw_cfg2->host_period_tx_q_depth = 2 +hw_cfg2->dev_token_q_depth = 8 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = 200D1E8 +hw_cfg3->xfer_size_width = 8 +hw_cfg3->packet_size_width = 6 +hw_cfg3->otg_enable = 1 +hw_cfg3->i2c_enable = 1 +hw_cfg3->vendor_ctrl_itf = 0 +hw_cfg3->optional_feature_removed = 0 +hw_cfg3->synch_reset = 0 +hw_cfg3->otg_adp_support = 1 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 1 +hw_cfg3->lpm_mode = 1 +hw_cfg3->total_fifo_size = 512 + +dwc2->ghwcfg4 = 17F08030 +hw_cfg4->num_dev_period_in_ep = 0 +hw_cfg4->power_optimized = 1 +hw_cfg4->ahb_freq_min = 1 +hw_cfg4->hibernation = 0 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 0 +hw_cfg4->acg_enable = 0 +hw_cfg4->utmi_phy_data_width = 2 +hw_cfg4->dev_ctrl_ep_num = 0 +hw_cfg4->iddg_filter_enabled = 1 +hw_cfg4->vbus_valid_filter_enabled = 1 +hw_cfg4->a_valid_filter_enabled = 1 +hw_cfg4->b_valid_filter_enabled = 1 +hw_cfg4->dedicated_fifos = 1 +hw_cfg4->num_dev_in_eps = 11 +hw_cfg4->dma_desc_enable = 0 +hw_cfg4->dma_dynamic = 0 + +## GD32VF103 Fullspeed + +dwc2->guid = 1000 +dwc2->gsnpsid = 0 +dwc2->ghwcfg1 = 0 + +dwc2->ghwcfg2 = 0 +hw_cfg2->op_mode = 0 +hw_cfg2->arch = 0 +hw_cfg2->point2point = 0 +hw_cfg2->hs_phy_type = 0 +hw_cfg2->fs_phy_type = 0 +hw_cfg2->num_dev_ep = 0 +hw_cfg2->num_host_ch = 0 +hw_cfg2->period_channel_support = 0 +hw_cfg2->enable_dynamic_fifo = 0 +hw_cfg2->mul_cpu_int = 0 +hw_cfg2->nperiod_tx_q_depth = 0 +hw_cfg2->host_period_tx_q_depth = 0 +hw_cfg2->dev_token_q_depth = 0 +hw_cfg2->otg_enable_ic_usb = 0 + +dwc2->ghwcfg3 = 0 +hw_cfg3->xfer_size_width = 0 +hw_cfg3->packet_size_width = 0 +hw_cfg3->otg_enable = 0 +hw_cfg3->i2c_enable = 0 +hw_cfg3->vendor_ctrl_itf = 0 +hw_cfg3->optional_feature_removed = 0 +hw_cfg3->synch_reset = 0 +hw_cfg3->otg_adp_support = 0 +hw_cfg3->otg_enable_hsic = 0 +hw_cfg3->battery_charger_support = 0 +hw_cfg3->lpm_mode = 0 +hw_cfg3->total_fifo_size = 0 + +dwc2->ghwcfg4 = 0 +hw_cfg4->num_dev_period_in_ep = 0 +hw_cfg4->power_optimized = 0 +hw_cfg4->ahb_freq_min = 0 +hw_cfg4->hibernation = 0 +hw_cfg4->service_interval_mode = 0 +hw_cfg4->ipg_isoc_en = 0 +hw_cfg4->acg_enable = 0 +hw_cfg4->utmi_phy_data_width = 0 +hw_cfg4->dev_ctrl_ep_num = 0 +hw_cfg4->iddg_filter_enabled = 0 +hw_cfg4->vbus_valid_filter_enabled = 0 +hw_cfg4->a_valid_filter_enabled = 0 +hw_cfg4->b_valid_filter_enabled = 0 +hw_cfg4->dedicated_fifos = 0 +hw_cfg4->num_dev_in_eps = 0 +hw_cfg4->dma_desc_enable = 0 +hw_cfg4->dma_dynamic = 0 From 4a8ac71711a70ccb122fdb59d731dc01cfed1464 Mon Sep 17 00:00:00 2001 From: hathach Date: Thu, 4 Nov 2021 12:31:16 +0700 Subject: [PATCH 50/51] Add timer1 on pi4 for blinky this get usb irq triggered even without ISB() in previous commit --- README.rst | 6 +-- hw/bsp/raspberrypi4/family.c | 77 ++++++++++++----------------------- hw/bsp/raspberrypi4/family.mk | 2 +- 3 files changed, 30 insertions(+), 55 deletions(-) diff --git a/README.rst b/README.rst index 329c0da53..1db022fc8 100644 --- a/README.rst +++ b/README.rst @@ -35,7 +35,7 @@ The stack supports the following MCUs: - **Dialog:** DA1469x - **Espressif:** ESP32-S2, ESP32-S3 - **MicroChip:** SAMD11, SAMD21, SAMD51, SAME5x, SAMG55, SAML21, SAML22, SAME7x -- **NordicSemi:** nRF52833, nRF52840 +- **NordicSemi:** nRF52833, nRF52840, nRF5340 - **Nuvoton:** NUC120, NUC121/NUC125, NUC126, NUC505 - **NXP:** @@ -45,9 +45,9 @@ The stack supports the following MCUs: - **Raspberry Pi:** RP2040 - **Renesas:** RX63N, RX65N -- **Silabs:** EFM32GG12 +- **Silabs:** EFM32GG - **Sony:** CXD56 -- **ST:** STM32 series: L0, L1, L4, F0, F1, F2, F3, F4, F7, H7 both FullSpeed and HighSpeed +- **ST:** STM32 series: L0, L1, L4, L4+, F0, F1, F2, F3, F4, F7, H7 - **TI:** MSP430 - **ValentyUSB:** eptri diff --git a/hw/bsp/raspberrypi4/family.c b/hw/bsp/raspberrypi4/family.c index 7a7a0e9ff..ba0b2700a 100644 --- a/hw/bsp/raspberrypi4/family.c +++ b/hw/bsp/raspberrypi4/family.c @@ -33,6 +33,14 @@ #include "broadcom/caches.h" #include "broadcom/vcmailbox.h" +// LED +#define LED_PIN 18 +#define LED_STATE_ON 1 + +// Button +#define BUTTON_PIN 16 +#define BUTTON_STATE_ACTIVE 0 + //--------------------------------------------------------------------+ // Forward USB interrupt events to TinyUSB IRQ Handler //--------------------------------------------------------------------+ @@ -50,63 +58,27 @@ void USB_IRQHandler(void) //--------------------------------------------------------------------+ void board_init(void) { - gpio_initOutputPinWithPullNone(18); - gpio_initOutputPinWithPullNone(19); - gpio_initOutputPinWithPullNone(20); - gpio_initOutputPinWithPullNone(21); - gpio_setPinOutputBool(18, true); - gpio_initOutputPinWithPullNone(42); setup_mmu_flat_map(); init_caches(); - // gpio_initOutputPinWithPullNone(23); - // gpio_initOutputPinWithPullNone(24); - // gpio_initOutputPinWithPullNone(25); - gpio_setPinOutputBool(18, false); + // LED + gpio_initOutputPinWithPullNone(LED_PIN); + board_led_write(true); + + // Button + // TODO + + // Uart uart_init(); - gpio_setPinOutputBool(18, true); - gpio_setPinOutputBool(18, false); - for (size_t i = 0; i < 5; i++) { - // while (true) { - for (size_t j = 0; j < 1000000; j++) { - __asm__("nop"); - } - gpio_setPinOutputBool(42, true); - gpio_setPinOutputBool(18, true); - gpio_setPinOutputBool(19, true); - gpio_setPinOutputBool(20, true); - gpio_setPinOutputBool(21, true); - for (size_t j = 0; j < 1000000; j++) { - __asm__("nop"); - } - gpio_setPinOutputBool(42, false); - gpio_setPinOutputBool(18, false); - gpio_setPinOutputBool(19, false); - gpio_setPinOutputBool(20, false); - gpio_setPinOutputBool(21, false); - } - // uart_writeText("hello from io\n"); - // gpio_setPinOutputBool(24, true); - // gpio_setPinOutputBool(24, false); - // gpio_setPinOutputBool(25, true); - // print(); - // gpio_setPinOutputBool(25, false); - // while (true) { - // // for (size_t i = 0; i < 5; i++) { - // for (size_t j = 0; j < 10000000000; j++) { - // __asm__("nop"); - // } - // gpio_setPinOutputBool(42, true); - // for (size_t j = 0; j < 10000000000; j++) { - // __asm__("nop"); - // } - // gpio_setPinOutputBool(42, false); - // } - // while (1) uart_update(); // Turn on USB peripheral. vcmailbox_set_power_state(VCMAILBOX_DEVICE_USB_HCD, true); + // Timer 1/1024 second tick + SYSTMR->CS_b.M1 = 1; + SYSTMR->C1 = SYSTMR->CLO + 977; + BP_EnableIRQ(TIMER_1_IRQn); + BP_SetPriority(USB_IRQn, 0x00); BP_ClearPendingIRQ(USB_IRQn); BP_EnableIRQ(USB_IRQn); @@ -115,7 +87,7 @@ void board_init(void) void board_led_write(bool state) { - gpio_setPinOutputBool(42, state); + gpio_setPinOutputBool(LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); } uint32_t board_button_read(void) @@ -145,9 +117,12 @@ int board_uart_write(void const * buf, int len) #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; -void SysTick_Handler (void) + +void TIMER_1_IRQHandler(void) { system_ticks++; + SYSTMR->C1 += 977; + SYSTMR->CS_b.M1 = 1; } uint32_t board_millis(void) diff --git a/hw/bsp/raspberrypi4/family.mk b/hw/bsp/raspberrypi4/family.mk index 475cfa4ff..c65070a71 100644 --- a/hw/bsp/raspberrypi4/family.mk +++ b/hw/bsp/raspberrypi4/family.mk @@ -48,4 +48,4 @@ $(BUILD)/kernel8.img: $(BUILD)/$(PROJECT).elf # Copy to kernel to netboot drive or SD card # Change destinaation to fit your need flash: $(BUILD)/kernel8.img - @$(CP) $< /home/$(USER)/Documents/code/pi4_tinyusb/boot_cpy + $(CP) $< /home/$(USER)/Documents/code/pi4_tinyusb/boot_cpy From 6cfdf697eba5b2af6ea383c2bed52557d7610893 Mon Sep 17 00:00:00 2001 From: hathach Date: Thu, 4 Nov 2021 12:42:28 +0700 Subject: [PATCH 51/51] add hint/question with ISB --- src/portable/synopsys/dwc2/dwc2_bcm.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/portable/synopsys/dwc2/dwc2_bcm.h b/src/portable/synopsys/dwc2/dwc2_bcm.h index 0263d19ba..fcec0b0d2 100644 --- a/src/portable/synopsys/dwc2/dwc2_bcm.h +++ b/src/portable/synopsys/dwc2/dwc2_bcm.h @@ -47,7 +47,7 @@ static inline void dwc2_dcd_int_enable(uint8_t rhport) { (void) rhport; BP_EnableIRQ(USB_IRQn); - __asm__ volatile("isb"); + __asm__ volatile("isb"); // needed if TIMER1 IRQ is not enabled !? } TU_ATTR_ALWAYS_INLINE @@ -55,7 +55,7 @@ static inline void dwc2_dcd_int_disable (uint8_t rhport) { (void) rhport; BP_DisableIRQ(USB_IRQn); - __asm__ volatile("isb"); + __asm__ volatile("isb"); // needed if TIMER1 IRQ is not enabled !? } static inline void dwc2_remote_wakeup_delay(void)