From 2499c9382d4ff0d67106f6dc6cd4a9dfbd0be20e Mon Sep 17 00:00:00 2001 From: Scott Shawcroft Date: Fri, 17 Sep 2021 16:51:34 -0700 Subject: [PATCH 1/9] 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 2/9] 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 3/9] 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 4/9] 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 5/9] 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 6/9] 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 7/9] 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 8/9] 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 9/9] 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)