aboutsummaryrefslogtreecommitdiff
path: root/circuitpython/lib/tinyusb/src/portable/sunxi
diff options
context:
space:
mode:
authorRaghuram Subramani <raghus2247@gmail.com>2022-06-19 19:47:51 +0530
committerRaghuram Subramani <raghus2247@gmail.com>2022-06-19 19:47:51 +0530
commit4fd287655a72b9aea14cdac715ad5b90ed082ed2 (patch)
tree65d393bc0e699dd12d05b29ba568e04cea666207 /circuitpython/lib/tinyusb/src/portable/sunxi
parent0150f70ce9c39e9e6dd878766c0620c85e47bed0 (diff)
add circuitpython code
Diffstat (limited to 'circuitpython/lib/tinyusb/src/portable/sunxi')
-rw-r--r--circuitpython/lib/tinyusb/src/portable/sunxi/dcd_sunxi_musb.c1211
-rw-r--r--circuitpython/lib/tinyusb/src/portable/sunxi/musb_def.h643
2 files changed, 1854 insertions, 0 deletions
diff --git a/circuitpython/lib/tinyusb/src/portable/sunxi/dcd_sunxi_musb.c b/circuitpython/lib/tinyusb/src/portable/sunxi/dcd_sunxi_musb.c
new file mode 100644
index 0000000..2751433
--- /dev/null
+++ b/circuitpython/lib/tinyusb/src/portable/sunxi/dcd_sunxi_musb.c
@@ -0,0 +1,1211 @@
+/*
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2021 Koji KITAYAMA
+ * Copyright (c) 2021 Tian Yunhao (t123yh)
+ * Copyright (c) 2021 Ha Thach (tinyusb.org)
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ *
+ * This file is part of the TinyUSB stack.
+ */
+
+#include <stdint.h>
+#include "tusb_option.h"
+
+#if CFG_TUD_ENABLED && CFG_TUSB_MCU == OPT_MCU_F1C100S
+
+#include "osal/osal.h"
+#include <f1c100s-irq.h>
+#include <device/dcd.h>
+#include "musb_def.h"
+#include "bsp/board.h"
+
+typedef uint32_t u32;
+typedef uint16_t u16;
+typedef uint8_t u8;
+
+
+#define REQUEST_TYPE_INVALID (0xFFu)
+
+typedef struct {
+ uint_fast16_t beg; /* offset of including first element */
+ uint_fast16_t end; /* offset of excluding the last element */
+} free_block_t;
+
+typedef struct TU_ATTR_PACKED
+{
+ void *buf; /* the start address of a transfer data buffer */
+ uint16_t length; /* the number of bytes in the buffer */
+ uint16_t remaining; /* the number of bytes remaining in the buffer */
+} pipe_state_t;
+
+typedef struct
+{
+ tusb_control_request_t setup_packet;
+ uint16_t remaining_ctrl; /* The number of bytes remaining in data stage of control transfer. */
+ int8_t status_out;
+ pipe_state_t pipe0;
+ pipe_state_t pipe[2][7]; /* pipe[direction][endpoint number - 1] */
+ uint16_t pipe_buf_is_fifo[2]; /* Bitmap. Each bit means whether 1:TU_FIFO or 0:POD. */
+} dcd_data_t;
+
+/*------------------------------------------------------------------
+ * SUNXI FUNCTION
+ *------------------------------------------------------------------*/
+
+static void usb_phy_write(int addr, int data, int len)
+{
+ int j = 0, usbc_bit = 0;
+ void *dest = (void *)USBC_REG_CSR(USBC0_BASE);
+
+ usbc_bit = 1 << (0 * 2);
+ for (j = 0; j < len; j++)
+ {
+ /* set the bit address to be written */
+ USBC_ClrBit_Mask_l(dest, 0xff << 8);
+ USBC_SetBit_Mask_l(dest, (addr + j) << 8);
+
+ USBC_ClrBit_Mask_l(dest, usbc_bit);
+ /* set data bit */
+ if (data & 0x1)
+ USBC_SetBit_Mask_l(dest, 1 << 7);
+ else
+ USBC_ClrBit_Mask_l(dest, 1 << 7);
+
+ USBC_SetBit_Mask_l(dest, usbc_bit);
+
+ USBC_ClrBit_Mask_l(dest, usbc_bit);
+
+ data >>= 1;
+ }
+}
+
+static void delay_ms(uint32_t ms)
+{
+#if CFG_TUSB_OS == OPT_OS_NONE
+ int now = board_millis();
+ while (board_millis() - now <= ms) asm("nop");
+#else
+ osal_task_delay(ms);
+#endif
+}
+
+static void USBC_HardwareReset(void)
+{
+ // Reset phy and controller
+ USBC_REG_set_bit_l(USBPHY_CLK_RST_BIT, USBPHY_CLK_REG);
+ USBC_REG_set_bit_l(BUS_RST_USB_BIT, BUS_CLK_RST_REG);
+ delay_ms(2);
+
+ USBC_REG_set_bit_l(USBPHY_CLK_GAT_BIT, USBPHY_CLK_REG);
+ USBC_REG_set_bit_l(USBPHY_CLK_RST_BIT, USBPHY_CLK_REG);
+
+ USBC_REG_set_bit_l(BUS_CLK_USB_BIT, BUS_CLK_GATE0_REG);
+ USBC_REG_set_bit_l(BUS_RST_USB_BIT, BUS_CLK_RST_REG);
+}
+
+static void USBC_PhyConfig(void)
+{
+ /* Regulation 45 ohms */
+ usb_phy_write(0x0c, 0x01, 1);
+
+ /* adjust PHY's magnitude and rate */
+ usb_phy_write(0x20, 0x14, 5);
+
+ /* threshold adjustment disconnect */
+ usb_phy_write(0x2a, 3, 2);
+
+ return;
+}
+
+static void USBC_ConfigFIFO_Base(void)
+{
+ u32 reg_value;
+
+ /* config usb fifo, 8kb mode */
+ reg_value = USBC_Readl(SUNXI_SRAMC_BASE + 0x04);
+ reg_value &= ~(0x03 << 0);
+ reg_value |= (1 << 0);
+ USBC_Writel(reg_value, SUNXI_SRAMC_BASE + 0x04);
+}
+
+static unsigned int USBC_WakeUp_ClearChangeDetect(unsigned int reg_val)
+{
+ unsigned int temp = reg_val;
+ /* vbus, id, dpdm, these bit is set 1 to clear, so we clear these bit when operate other bits */
+ temp &= ~(1 << USBC_BP_ISCR_VBUS_CHANGE_DETECT);
+ temp &= ~(1 << USBC_BP_ISCR_ID_CHANGE_DETECT);
+ temp &= ~(1 << USBC_BP_ISCR_DPDM_CHANGE_DETECT);
+
+ return temp;
+}
+
+static void USBC_EnableDpDmPullUp(void)
+{
+ u32 reg_val = USBC_Readl(USBC_REG_ISCR(USBC0_BASE));
+ reg_val |= (1 << USBC_BP_ISCR_DPDM_PULLUP_EN);
+ reg_val |= 3<<USBC_BP_ISCR_VBUS_VALID_SRC;
+ reg_val = USBC_WakeUp_ClearChangeDetect(reg_val);
+ USBC_Writel(reg_val, USBC_REG_ISCR(USBC0_BASE));
+}
+
+static void USBC_ForceIdToHigh(void)
+{
+ /* first write 00, then write 10 */
+ u32 reg_val = USBC_Readl(USBC_REG_ISCR(USBC0_BASE));
+ reg_val |= (0x03 << USBC_BP_ISCR_FORCE_ID);
+ reg_val = USBC_WakeUp_ClearChangeDetect(reg_val);
+ USBC_Writel(reg_val, USBC_REG_ISCR(USBC0_BASE));
+}
+
+static void USBC_ForceVbusValidToHigh(void)
+{
+ /* first write 00, then write 11 */
+ u32 reg_val = USBC_Readl(USBC_REG_ISCR(USBC0_BASE));
+ reg_val |= (0x03 << USBC_BP_ISCR_FORCE_VBUS_VALID);
+ reg_val = USBC_WakeUp_ClearChangeDetect(reg_val);
+ USBC_Writel(reg_val, USBC_REG_ISCR(USBC0_BASE));
+}
+
+void USBC_SelectBus(u32 io_type, u32 ep_type, u32 ep_index)
+{
+ u32 reg_val = 0;
+
+ reg_val = USBC_Readb(USBC_REG_VEND0(USBC0_BASE));
+ if (io_type == USBC_IO_TYPE_DMA) {
+ if (ep_type == USBC_EP_TYPE_TX) {
+ reg_val |= ((ep_index - 0x01) << 1) << USBC_BP_VEND0_DRQ_SEL; //drq_sel
+ reg_val |= 0x1<<USBC_BP_VEND0_BUS_SEL; //io_dma
+ } else {
+ reg_val |= ((ep_index << 1) - 0x01) << USBC_BP_VEND0_DRQ_SEL;
+ reg_val |= 0x1<<USBC_BP_VEND0_BUS_SEL;
+ }
+ } else {
+ //reg_val &= ~(0x1 << USBC_BP_VEND0_DRQ_SEL); //clear drq_sel, select pio
+ reg_val &= 0x00; // clear drq_sel, select pio
+ }
+
+ /* in 1667 1673 and later ic, FIFO_BUS_SEL bit(bit24 of reg0x40 for host/device)
+ * is fixed to 1, the hw guarantee that it's ok for cpu/inner_dma/outer_dma transfer */
+
+// reg_val |= 0x1<<USBC_BP_VEND0_BUS_SEL; //for 1663 set 1: enable dma, set 0: enable fifo
+
+ USBC_Writeb(reg_val, USBC_REG_VEND0(USBC0_BASE));
+}
+
+static void USBC_SelectActiveEp(u8 ep_index)
+{
+ USBC_Writeb(ep_index, USBC_REG_EPIND(USBC0_BASE));
+}
+
+static u8 USBC_GetActiveEp(void)
+{
+ return USBC_Readb(USBC_REG_EPIND(USBC0_BASE));
+}
+
+static void __USBC_Dev_ep0_SendStall(void)
+{
+ USBC_REG_set_bit_w(USBC_BP_CSR0_D_SEND_STALL, USBC_REG_CSR0(USBC0_BASE));
+}
+
+static void __USBC_Dev_ep0_ClearStall(void)
+{
+ USBC_REG_clear_bit_w(USBC_BP_CSR0_D_SEND_STALL, USBC_REG_CSR0(USBC0_BASE));
+ USBC_REG_clear_bit_w(USBC_BP_CSR0_D_SENT_STALL, USBC_REG_CSR0(USBC0_BASE));
+}
+
+static void USBC_Dev_Ctrl_ClearSetupEnd(void)
+{
+ USBC_REG_set_bit_w(USBC_BP_CSR0_D_SERVICED_SETUP_END, USBC_REG_CSR0(USBC0_BASE));
+}
+
+static void USBC_Dev_SetAddress(u8 address)
+{
+ USBC_Writeb(address, USBC_REG_FADDR(USBC0_BASE));
+}
+
+static void __USBC_Dev_Tx_SendStall(void)
+{
+ //send stall, and fifo is flushed automaticly
+ USBC_REG_set_bit_w(USBC_BP_TXCSR_D_SEND_STALL, USBC_REG_TXCSR(USBC0_BASE));
+}
+static u32 __USBC_Dev_Tx_IsEpStall(void)
+{
+ return USBC_REG_test_bit_w(USBC_BP_TXCSR_D_SENT_STALL, USBC_REG_TXCSR(USBC0_BASE));
+}
+static void __USBC_Dev_Tx_ClearStall(void)
+{
+ u32 reg_val = USBC_Readw(USBC_REG_TXCSR(USBC0_BASE));
+ reg_val &= ~((1 << USBC_BP_TXCSR_D_SENT_STALL)|(1 << USBC_BP_TXCSR_D_SEND_STALL)|(1<<USBC_BP_TXCSR_D_UNDER_RUN));
+ reg_val |= (1 << USBC_BP_TXCSR_D_CLEAR_DATA_TOGGLE);
+ USBC_Writew(reg_val, USBC_REG_TXCSR(USBC0_BASE));
+}
+
+static void __USBC_Dev_Rx_SendStall(void)
+{
+ USBC_REG_set_bit_w(USBC_BP_RXCSR_D_SEND_STALL, USBC_REG_RXCSR(USBC0_BASE));
+}
+
+static u32 __USBC_Dev_Rx_IsEpStall(void)
+{
+ return USBC_REG_test_bit_w(USBC_BP_RXCSR_D_SENT_STALL, USBC_REG_RXCSR(USBC0_BASE));
+}
+
+static void __USBC_Dev_Rx_ClearStall(void)
+{
+ u32 reg_val = USBC_Readw(USBC_REG_RXCSR(USBC0_BASE));
+ reg_val &= ~((1 << USBC_BP_RXCSR_D_SENT_STALL)|(1 << USBC_BP_RXCSR_D_SEND_STALL)|(1<<USBC_BP_RXCSR_D_OVERRUN));
+ reg_val |= (1 << USBC_BP_RXCSR_D_CLEAR_DATA_TOGGLE);
+ USBC_Writew(reg_val, USBC_REG_RXCSR(USBC0_BASE));
+}
+
+static tusb_speed_t USBC_Dev_QueryTransferMode(void)
+{
+ if (USBC_REG_test_bit_b(USBC_BP_POWER_D_HIGH_SPEED_FLAG, USBC_REG_PCTL(USBC0_BASE)))
+ return TUSB_SPEED_HIGH;
+ else
+ return TUSB_SPEED_FULL;
+}
+
+static void __USBC_Dev_ep0_ReadDataHalf(void)
+{
+ USBC_Writew(1<<USBC_BP_CSR0_D_SERVICED_RX_PKT_READY, USBC_REG_CSR0(USBC0_BASE));
+}
+
+static void __USBC_Dev_ep0_ReadDataComplete(void)
+{
+ USBC_Writew((1<<USBC_BP_CSR0_D_SERVICED_RX_PKT_READY) | (1<<USBC_BP_CSR0_D_DATA_END),
+ USBC_REG_CSR0(USBC0_BASE));
+}
+
+
+static void __USBC_Dev_ep0_WriteDataHalf(void)
+{
+ USBC_Writew(1<<USBC_BP_CSR0_D_TX_PKT_READY, USBC_REG_CSR0(USBC0_BASE));
+}
+
+static void __USBC_Dev_ep0_WriteDataComplete(void)
+{
+ USBC_Writew((1<<USBC_BP_CSR0_D_TX_PKT_READY) | (1<<USBC_BP_CSR0_D_DATA_END),
+ USBC_REG_CSR0(USBC0_BASE));
+}
+
+static void __USBC_Dev_Tx_WriteDataComplete(void)
+{
+ USBC_Writeb((1 << USBC_BP_TXCSR_D_TX_READY), USBC_REG_TXCSR(USBC0_BASE));
+}
+
+static void __USBC_Dev_Rx_ReadDataComplete(void)
+{
+ USBC_Writeb(0, USBC_REG_RXCSR(USBC0_BASE));
+}
+
+static u32 __USBC_Dev_Rx_IsReadDataReady(void)
+{
+ return USBC_REG_test_bit_w(USBC_BP_RXCSR_D_RX_PKT_READY, USBC_REG_RXCSR(USBC0_BASE));
+}
+
+/* open a tx ep's interrupt */
+static void USBC_INT_EnableTxEp(u8 ep_index)
+{
+ USBC_REG_set_bit_w(ep_index, USBC_REG_INTTxE(USBC0_BASE));
+}
+
+/* open a rx ep's interrupt */
+static void USBC_INT_EnableRxEp(u8 ep_index)
+{
+ USBC_REG_set_bit_w(ep_index, USBC_REG_INTRxE(USBC0_BASE));
+}
+
+/* close a tx ep's interrupt */
+static void USBC_INT_DisableTxEp(u8 ep_index)
+{
+ USBC_REG_clear_bit_w(ep_index, USBC_REG_INTTxE(USBC0_BASE));
+}
+
+/* close a rx ep's interrupt */
+static void USBC_INT_DisableRxEp(u8 ep_index)
+{
+ USBC_REG_clear_bit_w(ep_index, USBC_REG_INTRxE(USBC0_BASE));
+}
+
+/*------------------------------------------------------------------
+ * INTERNAL FUNCTION DECLARATION
+ *------------------------------------------------------------------*/
+
+static dcd_data_t _dcd;
+
+static inline free_block_t *find_containing_block(free_block_t *beg, free_block_t *end, uint_fast16_t addr)
+{
+ free_block_t *cur = beg;
+ for (; cur < end && ((addr < cur->beg) || (cur->end <= addr)); ++cur) ;
+ return cur;
+}
+
+static inline int update_free_block_list(free_block_t *blks, unsigned num, uint_fast16_t addr, uint_fast16_t size)
+{
+ free_block_t *p = find_containing_block(blks, blks + num, addr);
+ TU_ASSERT(p != blks + num, -2);
+ if (p->beg == addr) {
+ /* Shrink block */
+ p->beg = addr + size;
+ if (p->beg != p->end) return 0;
+ /* remove block */
+ free_block_t *end = blks + num;
+ while (p + 1 < end) {
+ *p = *(p + 1);
+ ++p;
+ }
+ return -1;
+ } else {
+ /* Split into 2 blocks */
+ free_block_t tmp = {
+ .beg = addr + size,
+ .end = p->end
+ };
+ p->end = addr;
+ if (p->beg == p->end) {
+ if (tmp.beg != tmp.end) {
+ *p = tmp;
+ return 0;
+ }
+ /* remove block */
+ free_block_t *end = blks + num;
+ while (p + 1 < end) {
+ *p = *(p + 1);
+ ++p;
+ }
+ return -1;
+ }
+ if (tmp.beg == tmp.end) return 0;
+ blks[num] = tmp;
+ return 1;
+ }
+}
+
+static inline unsigned free_block_size(free_block_t const *blk)
+{
+ return blk->end - blk->beg;
+}
+
+#if 0
+static inline void print_block_list(free_block_t const *blk, unsigned num)
+{
+ TU_LOG1("*************\n");
+ for (unsigned i = 0; i < num; ++i) {
+ TU_LOG1(" Blk%u %u %u\n", i, blk->beg, blk->end);
+ ++blk;
+ }
+}
+#else
+#define print_block_list(a,b)
+#endif
+
+#if CFG_TUSB_MCU == OPT_MCU_F1C100S
+#define USB_FIFO_SIZE_KB 4
+#else
+#error "Unsupported MCU"
+#endif
+
+static unsigned find_free_memory(uint_fast16_t size_in_log2_minus3)
+{
+ free_block_t free_blocks[2 * (TUP_DCD_ENDPOINT_MAX - 1)];
+ unsigned num_blocks = 1;
+ /* Backup current EP to restore later */
+ u8 backup_ep = USBC_GetActiveEp();
+
+ /* Initialize free memory block list */
+ free_blocks[0].beg = 64 / 8;
+ free_blocks[0].end = (USB_FIFO_SIZE_KB << 10) / 8; /* 2KiB / 8 bytes */
+ for (int i = 1; i < TUP_DCD_ENDPOINT_MAX; ++i) {
+ uint_fast16_t addr;
+ int num;
+ USBC_SelectActiveEp(i);
+ addr = USBC_Readw(USBC_REG_TXFIFOAD(USBC0_BASE));
+ if (addr) {
+ unsigned sz = USBC_Readb(USBC_REG_TXFIFOSZ(USBC0_BASE));
+ unsigned sft = (sz & USB_TXFIFOSZ_SIZE_M) + ((sz & USB_TXFIFOSZ_DPB) ? 1: 0);
+ num = update_free_block_list(free_blocks, num_blocks, addr, 1 << sft);
+ TU_ASSERT(-2 < num, 0);
+ num_blocks += num;
+ print_block_list(free_blocks, num_blocks);
+ }
+ addr = USBC_Readw(USBC_REG_RXFIFOAD(USBC0_BASE));
+ if (addr) {
+ unsigned sz = USBC_Readb(USBC_REG_RXFIFOSZ(USBC0_BASE));
+ unsigned sft = (sz & USB_RXFIFOSZ_SIZE_M) + ((sz & USB_RXFIFOSZ_DPB) ? 1: 0);
+ num = update_free_block_list(free_blocks, num_blocks, addr, 1 << sft);
+ TU_ASSERT(-2 < num, 0);
+ num_blocks += num;
+ print_block_list(free_blocks, num_blocks);
+ }
+ }
+ print_block_list(free_blocks, num_blocks);
+
+ USBC_SelectActiveEp(backup_ep);
+
+ /* Find the best fit memory block */
+ uint_fast16_t size_in_8byte_unit = 1 << size_in_log2_minus3;
+ free_block_t const *min = NULL;
+ uint_fast16_t min_sz = 0xFFFFu;
+ free_block_t const *end = &free_blocks[num_blocks];
+ for (free_block_t const *cur = &free_blocks[0]; cur < end; ++cur) {
+ uint_fast16_t sz = free_block_size(cur);
+ if (sz < size_in_8byte_unit) continue;
+ if (size_in_8byte_unit == sz) return cur->beg;
+ if (sz < min_sz) min = cur;
+ }
+ TU_ASSERT(min, 0);
+ return min->beg;
+}
+
+static void pipe_write_packet(void *buff, volatile void *fifo, unsigned cnt)
+{
+ u32 len = 0;
+ u32 i32 = 0;
+ u32 i8 = 0;
+ u8 *buf8 = 0;
+ u32 *buf32 = 0;
+
+ //--<1>-- adjust data
+ buf32 = buff;
+ len = cnt;
+
+ i32 = len >> 2;
+ i8 = len & 0x03;
+
+ //--<2>-- deal with 4byte part
+ while (i32--) {
+ USBC_Writel(*buf32++, fifo);
+ }
+
+ //--<3>-- deal with no 4byte part
+ buf8 = (u8 *)buf32;
+ while (i8--) {
+ USBC_Writeb(*buf8++, fifo);
+ }
+}
+
+static void pipe_read_packet(void *buff, volatile void *fifo, unsigned cnt)
+{
+ u32 len = 0;
+ u32 i32 = 0;
+ u32 i8 = 0;
+ u8 *buf8 = 0;
+ u32 *buf32 = 0;
+
+ //--<1>-- adjust data
+ buf32 = buff;
+ len = cnt;
+
+ i32 = len >> 2;
+ i8 = len & 0x03;
+
+ //--<2>-- deal with 4byte part
+ while (i32--) {
+ *buf32++ = USBC_Readl(fifo);
+ }
+
+ //--<3>-- deal with no 4byte part
+ buf8 = (u8 *)buf32;
+ while (i8--) {
+ *buf8++ = USBC_Readb(fifo);
+ }
+}
+
+static void pipe_read_write_packet_ff(tu_fifo_t *f, volatile void *fifo, unsigned len, unsigned dir)
+{
+ static const struct {
+ void (*tu_fifo_get_info)(tu_fifo_t *f, tu_fifo_buffer_info_t *info);
+ void (*tu_fifo_advance)(tu_fifo_t *f, uint16_t n);
+ void (*pipe_read_write)(void *buf, volatile void *fifo, unsigned len);
+ } ops[] = {
+ /* OUT */ {tu_fifo_get_write_info,tu_fifo_advance_write_pointer,pipe_read_packet},
+ /* IN */ {tu_fifo_get_read_info, tu_fifo_advance_read_pointer, pipe_write_packet},
+ };
+ tu_fifo_buffer_info_t info;
+ ops[dir].tu_fifo_get_info(f, &info);
+ unsigned total_len = len;
+ len = TU_MIN(total_len, info.len_lin);
+ ops[dir].pipe_read_write(info.ptr_lin, fifo, len);
+ unsigned rem = total_len - len;
+ if (rem) {
+ len = TU_MIN(rem, info.len_wrap);
+ ops[dir].pipe_read_write(info.ptr_wrap, fifo, len);
+ rem -= len;
+ }
+ ops[dir].tu_fifo_advance(f, total_len - rem);
+}
+
+/*------------------------------------------------------------------
+ * TRANSFER FUNCTION DECLARATION
+ *------------------------------------------------------------------*/
+
+static void process_setup_packet(uint8_t rhport)
+{
+ uint32_t *p = (uint32_t*)&_dcd.setup_packet;
+ p[0] = USBC_Readl(USBC_REG_EPFIFO0(USBC0_BASE));
+ p[1] = USBC_Readl(USBC_REG_EPFIFO0(USBC0_BASE));
+
+ _dcd.pipe0.buf = NULL;
+ _dcd.pipe0.length = 0;
+ _dcd.pipe0.remaining = 0;
+ dcd_event_setup_received(rhport, (const uint8_t*)(uintptr_t)&_dcd.setup_packet, true);
+
+ const unsigned len = _dcd.setup_packet.wLength;
+ _dcd.remaining_ctrl = len;
+ const unsigned dir_in = tu_edpt_dir(_dcd.setup_packet.bmRequestType);
+ /* Clear RX FIFO and reverse the transaction direction */
+ if (len && dir_in) __USBC_Dev_ep0_ReadDataHalf();
+}
+
+static bool handle_xfer_in(uint_fast8_t ep_addr)
+{
+ unsigned epnum_minus1 = tu_edpt_number(ep_addr) - 1;
+ pipe_state_t *pipe = &_dcd.pipe[tu_edpt_dir(ep_addr)][epnum_minus1];
+ const unsigned rem = pipe->remaining;
+
+ if (!rem) {
+ pipe->buf = NULL;
+ return true;
+ }
+
+ const unsigned mps = USBC_Readw(USBC_REG_TXMAXP(USBC0_BASE));
+ const unsigned len = TU_MIN(mps, rem);
+ uint8_t *buf = pipe->buf;
+ // TU_LOG1(" %p mps %d len %d rem %d\n", buf, mps, len, rem);
+ if (len) {
+ volatile void* addr = (volatile void*)(USBC_REG_EPFIFO1(USBC0_BASE) + (epnum_minus1 << 2));
+ if (_dcd.pipe_buf_is_fifo[TUSB_DIR_IN] & TU_BIT(epnum_minus1)) {
+ pipe_read_write_packet_ff((tu_fifo_t *)buf, addr, len, TUSB_DIR_IN);
+ } else {
+ pipe_write_packet(buf, addr, len);
+ pipe->buf = buf + len;
+ }
+ pipe->remaining = rem - len;
+ }
+ __USBC_Dev_Tx_WriteDataComplete();
+ // TU_LOG1(" TXCSRL%d = %x %d\n", epnum_minus1 + 1, regs->TXCSRL, rem - len);
+ return false;
+}
+
+static bool handle_xfer_out(uint_fast8_t ep_addr)
+{
+ unsigned epnum_minus1 = tu_edpt_number(ep_addr) - 1;
+ pipe_state_t *pipe = &_dcd.pipe[tu_edpt_dir(ep_addr)][epnum_minus1];
+ // TU_LOG1(" RXCSRL%d = %x\n", epnum_minus1 + 1, regs->RXCSRL);
+
+ TU_ASSERT(__USBC_Dev_Rx_IsReadDataReady());
+
+ const unsigned mps = USBC_Readw(USBC_REG_RXMAXP(USBC0_BASE));
+ const unsigned rem = pipe->remaining;
+ const unsigned vld = USBC_Readw(USBC_REG_RXCOUNT(USBC0_BASE));
+ const unsigned len = TU_MIN(TU_MIN(rem, mps), vld);
+ uint8_t *buf = pipe->buf;
+ if (len) {
+ volatile void* addr = (volatile void*)(USBC_REG_EPFIFO1(USBC0_BASE) + (epnum_minus1 << 2));
+ if (_dcd.pipe_buf_is_fifo[TUSB_DIR_OUT] & TU_BIT(epnum_minus1)) {
+ pipe_read_write_packet_ff((tu_fifo_t *)buf, addr, len, TUSB_DIR_OUT);
+ } else {
+ pipe_read_packet(buf, addr, len);
+ pipe->buf = buf + len;
+ }
+ pipe->remaining = rem - len;
+ }
+ if ((len < mps) || (rem == len)) {
+ pipe->buf = NULL;
+ return NULL != buf;
+ }
+ __USBC_Dev_Rx_ReadDataComplete();
+ return false;
+}
+
+static bool edpt_n_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t *buffer, uint16_t total_bytes)
+{
+ (void)rhport;
+
+ unsigned epnum_minus1 = tu_edpt_number(ep_addr) - 1;
+ unsigned dir_in = tu_edpt_dir(ep_addr);
+
+ pipe_state_t *pipe = &_dcd.pipe[dir_in][epnum_minus1];
+ pipe->buf = buffer;
+ pipe->length = total_bytes;
+ pipe->remaining = total_bytes;
+
+ USBC_SelectActiveEp(tu_edpt_number(ep_addr));
+
+ if (dir_in) {
+ handle_xfer_in(ep_addr);
+ } else {
+ if (__USBC_Dev_Rx_IsReadDataReady())
+ __USBC_Dev_Rx_ReadDataComplete();
+ }
+ return true;
+}
+
+static bool edpt0_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t *buffer, uint16_t total_bytes)
+{
+ (void)rhport;
+ TU_ASSERT(total_bytes <= 64); /* Current implementation supports for only up to 64 bytes. */
+
+ const unsigned req = _dcd.setup_packet.bmRequestType;
+ TU_ASSERT(req != REQUEST_TYPE_INVALID || total_bytes == 0);
+
+ USBC_SelectActiveEp(0);
+
+ if (req == REQUEST_TYPE_INVALID || _dcd.status_out) {
+ /* STATUS OUT stage.
+ * MUSB controller automatically handles STATUS OUT packets without
+ * software helps. We do not have to do anything. And STATUS stage
+ * may have already finished and received the next setup packet
+ * without calling this function, so we have no choice but to
+ * invoke the callback function of status packet here. */
+ // TU_LOG1(" STATUS OUT CSRL0 = %x\n", CSRL0);
+ _dcd.status_out = 0;
+ if (req == REQUEST_TYPE_INVALID) {
+ dcd_event_xfer_complete(rhport, ep_addr, total_bytes, XFER_RESULT_SUCCESS, false);
+ } else {
+ /* The next setup packet has already been received, it aborts
+ * invoking callback function to avoid confusing TUSB stack. */
+ TU_LOG1("Drop CONTROL_STAGE_ACK\n");
+ }
+ return true;
+ }
+ const unsigned dir_in = tu_edpt_dir(ep_addr);
+ if (tu_edpt_dir(req) == dir_in) { /* DATA stage */
+ TU_ASSERT(total_bytes <= _dcd.remaining_ctrl);
+ const unsigned rem = _dcd.remaining_ctrl;
+ const unsigned len = TU_MIN(TU_MIN(rem, 64), total_bytes);
+ if (dir_in) {
+ pipe_write_packet(buffer, (volatile void*) USBC_REG_EPFIFO0(USBC0_BASE), len);
+
+ _dcd.pipe0.buf = buffer + len;
+ _dcd.pipe0.length = len;
+ _dcd.pipe0.remaining = 0;
+
+ _dcd.remaining_ctrl = rem - len;
+ if ((len < 64) || (rem == len)) {
+ _dcd.setup_packet.bmRequestType = REQUEST_TYPE_INVALID; /* Change to STATUS/SETUP stage */
+ _dcd.status_out = 1;
+ /* Flush TX FIFO and reverse the transaction direction. */
+ __USBC_Dev_ep0_WriteDataComplete();
+ } else {
+ __USBC_Dev_ep0_WriteDataHalf();
+ }
+ // TU_LOG1(" IN CSRL0 = %x\n", CSRL0);
+ } else {
+ // TU_LOG1(" OUT CSRL0 = %x\n", CSRL0);
+ _dcd.pipe0.buf = buffer;
+ _dcd.pipe0.length = len;
+ _dcd.pipe0.remaining = len;
+ __USBC_Dev_ep0_ReadDataHalf();
+ }
+ } else if (dir_in) {
+ // TU_LOG1(" STATUS IN CSRL0 = %x\n", CSRL0);
+ _dcd.pipe0.buf = NULL;
+ _dcd.pipe0.length = 0;
+ _dcd.pipe0.remaining = 0;
+ /* Clear RX FIFO and reverse the transaction direction */
+ __USBC_Dev_ep0_ReadDataComplete();
+ }
+ return true;
+}
+
+static void process_ep0(uint8_t rhport)
+{
+ USBC_SelectActiveEp(0);
+ uint_fast8_t csrl = USBC_Readw(USBC_REG_CSR0(USBC0_BASE));
+
+ // TU_LOG1(" EP0 CSRL0 = %x\n", csrl);
+
+ if (csrl & USB_CSRL0_STALLED) {
+ /* Returned STALL packet to HOST. */
+ __USBC_Dev_ep0_ClearStall();
+ return;
+ }
+
+ unsigned req = _dcd.setup_packet.bmRequestType;
+ if (csrl & USB_CSRL0_SETEND) {
+ // TU_LOG1(" ABORT by the next packets\n");
+ USBC_Dev_Ctrl_ClearSetupEnd();
+ if (req != REQUEST_TYPE_INVALID && _dcd.pipe0.buf) {
+ /* DATA stage was aborted by receiving STATUS or SETUP packet. */
+ _dcd.pipe0.buf = NULL;
+ _dcd.setup_packet.bmRequestType = REQUEST_TYPE_INVALID;
+ dcd_event_xfer_complete(rhport,
+ req & TUSB_DIR_IN_MASK,
+ _dcd.pipe0.length - _dcd.pipe0.remaining,
+ XFER_RESULT_SUCCESS, true);
+ }
+ req = REQUEST_TYPE_INVALID;
+ if (!(csrl & USB_CSRL0_RXRDY)) return; /* Received SETUP packet */
+ }
+
+ if (csrl & USB_CSRL0_RXRDY) {
+ /* Received SETUP or DATA OUT packet */
+ if (req == REQUEST_TYPE_INVALID) {
+ /* SETUP */
+ TU_ASSERT(sizeof(tusb_control_request_t) == USBC_Readw(USBC_REG_COUNT0(USBC0_BASE)),);
+ process_setup_packet(rhport);
+ return;
+ }
+ if (_dcd.pipe0.buf) {
+ /* DATA OUT */
+ const unsigned vld = USBC_Readw(USBC_REG_COUNT0(USBC0_BASE));
+ const unsigned rem = _dcd.pipe0.remaining;
+ const unsigned len = TU_MIN(TU_MIN(rem, 64), vld);
+ pipe_read_packet(_dcd.pipe0.buf, (volatile void*)USBC_REG_EPFIFO0(USBC0_BASE), len);
+
+ _dcd.pipe0.remaining = rem - len;
+ _dcd.remaining_ctrl -= len;
+
+ _dcd.pipe0.buf = NULL;
+ dcd_event_xfer_complete(rhport,
+ tu_edpt_addr(0, TUSB_DIR_OUT),
+ _dcd.pipe0.length - _dcd.pipe0.remaining,
+ XFER_RESULT_SUCCESS, true);
+ }
+ return;
+ }
+
+ /* When CSRL0 is zero, it means that completion of sending a any length packet
+ * or receiving a zero length packet. */
+ if (req != REQUEST_TYPE_INVALID && !tu_edpt_dir(req)) {
+ /* STATUS IN */
+ if (*(const uint16_t*)(uintptr_t)&_dcd.setup_packet == 0x0500) {
+ /* The address must be changed on completion of the control transfer. */
+ USBC_Dev_SetAddress((uint8_t)_dcd.setup_packet.wValue);
+ }
+ _dcd.setup_packet.bmRequestType = REQUEST_TYPE_INVALID;
+ dcd_event_xfer_complete(rhport,
+ tu_edpt_addr(0, TUSB_DIR_IN),
+ _dcd.pipe0.length - _dcd.pipe0.remaining,
+ XFER_RESULT_SUCCESS, true);
+ return;
+ }
+ if (_dcd.pipe0.buf) {
+ /* DATA IN */
+ _dcd.pipe0.buf = NULL;
+ dcd_event_xfer_complete(rhport,
+ tu_edpt_addr(0, TUSB_DIR_IN),
+ _dcd.pipe0.length - _dcd.pipe0.remaining,
+ XFER_RESULT_SUCCESS, true);
+ }
+}
+
+static void process_edpt_n(uint8_t rhport, uint_fast8_t ep_addr)
+{
+ bool completed;
+ const unsigned dir_in = tu_edpt_dir(ep_addr);
+ const unsigned epn = tu_edpt_number(ep_addr);
+
+ USBC_SelectActiveEp(epn);
+
+ if (dir_in) {
+ // TU_LOG1(" TXCSRL%d = %x\n", epn_minus1 + 1, regs->TXCSRL);
+ if (__USBC_Dev_Tx_IsEpStall()) {
+ __USBC_Dev_Tx_ClearStall();
+ return;
+ }
+ completed = handle_xfer_in(ep_addr);
+ } else {
+ // TU_LOG1(" RXCSRL%d = %x\n", epn_minus1 + 1, regs->RXCSRL);
+ if (__USBC_Dev_Rx_IsEpStall()) {
+ __USBC_Dev_Rx_ClearStall();
+ return;
+ }
+ completed = handle_xfer_out(ep_addr);
+ }
+
+ if (completed) {
+ pipe_state_t *pipe = &_dcd.pipe[dir_in][tu_edpt_number(ep_addr) - 1];
+ dcd_event_xfer_complete(rhport, ep_addr,
+ pipe->length - pipe->remaining,
+ XFER_RESULT_SUCCESS, true);
+ }
+}
+
+static void process_bus_reset(uint8_t rhport)
+{
+ /* When bmRequestType is REQUEST_TYPE_INVALID(0xFF),
+ * a control transfer state is SETUP or STATUS stage. */
+ _dcd.setup_packet.bmRequestType = REQUEST_TYPE_INVALID;
+ _dcd.status_out = 0;
+ /* When pipe0.buf has not NULL, DATA stage works in progress. */
+ _dcd.pipe0.buf = NULL;
+
+ USBC_Writew(1, USBC_REG_INTTxE(USBC0_BASE)); /* Enable only EP0 */
+ USBC_Writew(0, USBC_REG_INTRxE(USBC0_BASE));
+
+ dcd_event_bus_reset(rhport, USBC_Dev_QueryTransferMode(), true);
+}
+
+/*------------------------------------------------------------------
+ * Device API
+ *------------------------------------------------------------------*/
+
+static void usb_isr_handler(void) {
+ dcd_int_handler(0);
+}
+
+void dcd_init(uint8_t rhport)
+{
+ dcd_disconnect(rhport);
+ USBC_HardwareReset();
+ USBC_PhyConfig();
+ USBC_ConfigFIFO_Base();
+ USBC_EnableDpDmPullUp();
+ USBC_ForceIdToHigh(); // Force device mode
+ USBC_ForceVbusValidToHigh();
+ USBC_SelectBus(USBC_IO_TYPE_PIO, 0, 0);
+ dcd_edpt_close_all(rhport);
+
+ #if TUD_OPT_HIGH_SPEED
+ USBC_REG_set_bit_b(USBC_BP_POWER_D_HIGH_SPEED_EN, USBC_REG_PCTL(USBC0_BASE));
+ #else
+ USBC_REG_clear_bit_b(USBC_BP_POWER_D_HIGH_SPEED_EN, USBC_REG_PCTL(USBC0_BASE));
+ #endif
+
+ USBC_Writeb((1 << USBC_BP_INTUSBE_EN_SUSPEND)
+ | (1 << USBC_BP_INTUSBE_EN_RESUME)
+ | (1 << USBC_BP_INTUSBE_EN_RESET)
+ | (1 << USBC_BP_INTUSBE_EN_SOF)
+ | (1 << USBC_BP_INTUSBE_EN_DISCONNECT)
+ , USBC_REG_INTUSBE(USBC0_BASE));
+ f1c100s_intc_clear_pend(F1C100S_IRQ_USBOTG);
+ f1c100s_intc_set_isr(F1C100S_IRQ_USBOTG, usb_isr_handler);
+
+ dcd_connect(rhport);
+}
+
+// Connect by enabling internal pull-up resistor on D+/D-
+void dcd_connect(uint8_t rhport)
+{
+ (void)rhport;
+ USBC_REG_set_bit_b(USBC_BP_POWER_D_SOFT_CONNECT, USBC_REG_PCTL(USBC0_BASE));
+}
+
+// Disconnect by disabling internal pull-up resistor on D+/D-
+void dcd_disconnect(uint8_t rhport)
+{
+ (void)rhport;
+ USBC_REG_clear_bit_b(USBC_BP_POWER_D_SOFT_CONNECT, USBC_REG_PCTL(USBC0_BASE));
+}
+
+void dcd_int_enable(uint8_t rhport)
+{
+ (void)rhport;
+ f1c100s_intc_enable_irq(F1C100S_IRQ_USBOTG);
+}
+
+static void musb_int_mask(void)
+{
+ f1c100s_intc_mask_irq(F1C100S_IRQ_USBOTG);
+}
+
+void dcd_int_disable(uint8_t rhport)
+{
+ (void)rhport;
+ f1c100s_intc_disable_irq(F1C100S_IRQ_USBOTG);
+}
+
+static void musb_int_unmask(void)
+{
+ f1c100s_intc_unmask_irq(F1C100S_IRQ_USBOTG);
+}
+
+// Receive Set Address request, mcu port must also include status IN response
+void dcd_set_address(uint8_t rhport, uint8_t dev_addr)
+{
+ (void)rhport;
+ (void)dev_addr;
+ _dcd.pipe0.buf = NULL;
+ _dcd.pipe0.length = 0;
+ _dcd.pipe0.remaining = 0;
+ /* Clear RX FIFO to return ACK. */
+ USBC_SelectActiveEp(0);
+ __USBC_Dev_ep0_ReadDataComplete();
+}
+
+// Wake up host
+void dcd_remote_wakeup(uint8_t rhport)
+{
+ (void)rhport;
+ USBC_REG_set_bit_b(USBC_BP_POWER_D_RESUME, USBC_REG_PCTL(USBC0_BASE));
+ delay_ms(10);
+ USBC_REG_clear_bit_b(USBC_BP_POWER_D_RESUME, USBC_REG_PCTL(USBC0_BASE));
+}
+
+//--------------------------------------------------------------------+
+// Endpoint API
+//--------------------------------------------------------------------+
+
+#ifndef __ARMCC_VERSION
+#define __clz __builtin_clz
+#endif
+
+// Configure endpoint's registers according to descriptor
+bool dcd_edpt_open(uint8_t rhport, tusb_desc_endpoint_t const * ep_desc)
+{
+ (void) rhport;
+
+ uint16_t reg_val;
+
+ const unsigned ep_addr = ep_desc->bEndpointAddress;
+ const unsigned epn = tu_edpt_number(ep_addr);
+ const unsigned dir_in = tu_edpt_dir(ep_addr);
+ const unsigned xfer = ep_desc->bmAttributes.xfer;
+ const unsigned mps = tu_edpt_packet_size(ep_desc);
+
+ TU_ASSERT(epn < TUP_DCD_ENDPOINT_MAX);
+
+ pipe_state_t *pipe = &_dcd.pipe[dir_in][epn - 1];
+ pipe->buf = NULL;
+ pipe->length = 0;
+ pipe->remaining = 0;
+
+ musb_int_mask();
+
+ // volatile hw_endpoint_t *regs = edpt_regs(epn - 1);
+ USBC_SelectActiveEp(epn);
+ if (dir_in) {
+ USBC_Writew(mps, USBC_REG_TXMAXP(USBC0_BASE));
+
+ reg_val = (1 << USBC_BP_TXCSR_D_MODE)
+ | (1 << USBC_BP_TXCSR_D_FLUSH_FIFO)
+ | (1 << USBC_BP_TXCSR_D_CLEAR_DATA_TOGGLE);
+ if (xfer == TUSB_XFER_ISOCHRONOUS)
+ reg_val |= (1 << USBC_BP_TXCSR_D_ISO);
+ USBC_Writew(reg_val, USBC_REG_TXCSR(USBC0_BASE));
+
+ USBC_INT_EnableTxEp(epn);
+ } else {
+ USBC_Writew(mps, USBC_REG_RXMAXP(USBC0_BASE));
+
+ reg_val = (1 << USBC_BP_RXCSR_D_FLUSH_FIFO)
+ | (1 << USBC_BP_RXCSR_D_CLEAR_DATA_TOGGLE);
+ if (xfer == TUSB_XFER_ISOCHRONOUS)
+ reg_val |= (1 << USBC_BP_RXCSR_D_ISO);
+ USBC_Writew(reg_val, USBC_REG_RXCSR(USBC0_BASE));
+
+ USBC_INT_EnableRxEp(epn);
+ }
+
+ /* Setup FIFO */
+ int size_in_log2_minus3 = 28 - TU_MIN(28, __clz((uint32_t)mps));
+ if ((8u << size_in_log2_minus3) < mps) ++size_in_log2_minus3;
+ unsigned addr = find_free_memory(size_in_log2_minus3);
+ TU_ASSERT(addr);
+
+ if (dir_in) {
+ USBC_Writew(addr, USBC_REG_TXFIFOAD(USBC0_BASE));
+ USBC_Writeb(size_in_log2_minus3, USBC_REG_TXFIFOSZ(USBC0_BASE));
+ } else {
+ USBC_Writew(addr, USBC_REG_RXFIFOAD(USBC0_BASE));
+ USBC_Writeb(size_in_log2_minus3, USBC_REG_RXFIFOSZ(USBC0_BASE));
+ }
+
+ musb_int_unmask();
+
+ return true;
+}
+
+void dcd_edpt_close_all(uint8_t rhport)
+{
+ (void) rhport;
+ musb_int_mask();
+ USBC_Writew(1, USBC_REG_INTTxE(USBC0_BASE)); /* Enable only EP0 */
+ USBC_Writew(0, USBC_REG_INTRxE(USBC0_BASE));
+ for (unsigned i = 1; i < TUP_DCD_ENDPOINT_MAX; ++i) {
+ USBC_SelectActiveEp(i);
+ USBC_Writew(0, USBC_REG_TXMAXP(USBC0_BASE));
+ USBC_Writew((1 << USBC_BP_TXCSR_D_MODE) | (1 << USBC_BP_TXCSR_D_CLEAR_DATA_TOGGLE) | (1 << USBC_BP_TXCSR_D_FLUSH_FIFO),
+ USBC_REG_TXCSR(USBC0_BASE));
+
+ USBC_Writew(0, USBC_REG_RXMAXP(USBC0_BASE));
+ USBC_Writew((1 << USBC_BP_RXCSR_D_CLEAR_DATA_TOGGLE) | (1 << USBC_BP_RXCSR_D_FLUSH_FIFO),
+ USBC_REG_RXCSR(USBC0_BASE));
+
+ USBC_Writew(0, USBC_REG_TXFIFOAD(USBC0_BASE));
+ USBC_Writeb(0, USBC_REG_TXFIFOSZ(USBC0_BASE));
+ USBC_Writew(0, USBC_REG_RXFIFOAD(USBC0_BASE));
+ USBC_Writeb(0, USBC_REG_RXFIFOSZ(USBC0_BASE));
+ }
+ musb_int_unmask();
+}
+
+void dcd_edpt_close(uint8_t rhport, uint8_t ep_addr)
+{
+ (void)rhport;
+ unsigned const epn = tu_edpt_number(ep_addr);
+ unsigned const dir_in = tu_edpt_dir(ep_addr);
+
+ musb_int_mask();
+ USBC_SelectActiveEp(epn);
+ if (dir_in) {
+ USBC_INT_DisableTxEp(epn);
+ USBC_Writew(0, USBC_REG_TXMAXP(USBC0_BASE));
+ USBC_Writew((1 << USBC_BP_TXCSR_D_MODE) | (1 << USBC_BP_TXCSR_D_CLEAR_DATA_TOGGLE) | (1 << USBC_BP_TXCSR_D_FLUSH_FIFO),
+ USBC_REG_TXCSR(USBC0_BASE));
+
+ USBC_Writew(0, USBC_REG_TXFIFOAD(USBC0_BASE));
+ USBC_Writeb(0, USBC_REG_TXFIFOSZ(USBC0_BASE));
+ } else {
+ USBC_INT_DisableRxEp(epn);
+ USBC_Writew(0, USBC_REG_RXMAXP(USBC0_BASE));
+ USBC_Writew((1 << USBC_BP_RXCSR_D_CLEAR_DATA_TOGGLE) | (1 << USBC_BP_RXCSR_D_FLUSH_FIFO),
+ USBC_REG_RXCSR(USBC0_BASE));
+
+ USBC_Writew(0, USBC_REG_RXFIFOAD(USBC0_BASE));
+ USBC_Writeb(0, USBC_REG_RXFIFOSZ(USBC0_BASE));
+ }
+ musb_int_unmask();
+}
+
+// Submit a transfer, When complete dcd_event_xfer_complete() is invoked to notify the stack
+bool dcd_edpt_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t total_bytes)
+{
+ (void)rhport;
+ bool ret;
+ // TU_LOG1("X %x %d\n", ep_addr, total_bytes);
+ unsigned const epnum = tu_edpt_number(ep_addr);
+ musb_int_mask();
+
+ if (epnum) {
+ _dcd.pipe_buf_is_fifo[tu_edpt_dir(ep_addr)] &= ~TU_BIT(epnum - 1);
+ ret = edpt_n_xfer(rhport, ep_addr, buffer, total_bytes);
+ } else {
+ ret = edpt0_xfer(rhport, ep_addr, buffer, total_bytes);
+ }
+ musb_int_unmask();
+ return ret;
+}
+
+// Submit a transfer where is managed by FIFO, When complete dcd_event_xfer_complete() is invoked to notify the stack - optional, however, must be listed in usbd.c
+bool dcd_edpt_xfer_fifo(uint8_t rhport, uint8_t ep_addr, tu_fifo_t * ff, uint16_t total_bytes)
+{
+ (void)rhport;
+ bool ret;
+ // TU_LOG1("X %x %d\n", ep_addr, total_bytes);
+ unsigned const epnum = tu_edpt_number(ep_addr);
+ TU_ASSERT(epnum);
+
+ musb_int_mask();
+ _dcd.pipe_buf_is_fifo[tu_edpt_dir(ep_addr)] |= TU_BIT(epnum - 1);
+ ret = edpt_n_xfer(rhport, ep_addr, (uint8_t*)ff, total_bytes);
+ musb_int_unmask();
+
+ return ret;
+}
+
+// Stall endpoint
+void dcd_edpt_stall(uint8_t rhport, uint8_t ep_addr)
+{
+ (void)rhport;
+ unsigned const epn = tu_edpt_number(ep_addr);
+ musb_int_mask();
+ USBC_SelectActiveEp(epn);
+ if (0 == epn) {
+ if (!ep_addr) { /* Ignore EP80 */
+ _dcd.setup_packet.bmRequestType = REQUEST_TYPE_INVALID;
+ _dcd.pipe0.buf = NULL;
+ __USBC_Dev_ep0_SendStall();
+ }
+ } else {
+ if (tu_edpt_dir(ep_addr)) { /* IN */
+ __USBC_Dev_Tx_SendStall();
+ } else { /* OUT */
+ TU_ASSERT(!__USBC_Dev_Rx_IsReadDataReady(),);
+ __USBC_Dev_Rx_SendStall();
+ }
+ }
+ musb_int_unmask();
+}
+
+// clear stall, data toggle is also reset to DATA0
+void dcd_edpt_clear_stall(uint8_t rhport, uint8_t ep_addr)
+{
+ (void)rhport;
+ unsigned const epn = tu_edpt_number(ep_addr);
+ musb_int_mask();
+ USBC_SelectActiveEp(epn);
+ if (0 != epn) {
+ if (tu_edpt_dir(ep_addr)) { /* IN */
+ __USBC_Dev_Tx_ClearStall();
+ } else { /* OUT */
+ __USBC_Dev_Rx_ClearStall();
+ }
+ }
+ musb_int_unmask();
+}
+
+
+void dcd_int_handler(uint8_t rhport)
+{
+ uint8_t is;
+ uint16_t txis, rxis;
+
+ is = USBC_Readb(USBC_REG_INTUSB(USBC0_BASE)); /* read interrupt status */
+ txis = USBC_Readw(USBC_REG_INTTx(USBC0_BASE)); /* read interrupt status */
+ rxis = USBC_Readw(USBC_REG_INTRx(USBC0_BASE)); /* read interrupt status */
+
+ is &= USBC_Readb(USBC_REG_INTUSBE(USBC0_BASE)); /* ignore disabled interrupts */
+ USBC_Writeb(is, USBC_REG_INTUSB(USBC0_BASE)); /* sunxi musb requires a write to interrupt register to clear */
+ if (is & USBC_INTUSB_DISCONNECT) {
+ dcd_event_bus_signal(rhport, DCD_EVENT_UNPLUGGED, true);
+ }
+ if (is & USBC_INTUSB_SOF) {
+ dcd_event_bus_signal(rhport, DCD_EVENT_SOF, true);
+ }
+ if (is & USBC_INTUSB_RESET) {
+ /* ep0 FADDR must be 0 when (re)entering peripheral mode */
+ USBC_SelectActiveEp(0);
+ USBC_Dev_SetAddress(0);
+ process_bus_reset(rhport);
+ }
+ if (is & USBC_INTUSB_RESUME) {
+ dcd_event_bus_signal(rhport, DCD_EVENT_RESUME, true);
+ }
+ if (is & USBC_INTUSB_SUSPEND) {
+ dcd_event_bus_signal(rhport, DCD_EVENT_SUSPEND, true);
+ }
+
+ txis &= USBC_Readw(USBC_REG_INTTxE(USBC0_BASE));
+ USBC_Writew(txis, USBC_REG_INTTx(USBC0_BASE));
+ if (txis & USBC_INTTx_FLAG_EP0) {
+ process_ep0(rhport);
+ txis &= ~TU_BIT(0);
+ }
+ while (txis) {
+ unsigned const num = __builtin_ctz(txis);
+ process_edpt_n(rhport, tu_edpt_addr(num, TUSB_DIR_IN));
+ txis &= ~TU_BIT(num);
+ }
+
+ rxis &= USBC_Readw(USBC_REG_INTRxE(USBC0_BASE));
+ USBC_Writew(rxis, USBC_REG_INTRx(USBC0_BASE));
+ while (rxis) {
+ unsigned const num = __builtin_ctz(rxis);
+ process_edpt_n(rhport, tu_edpt_addr(num, TUSB_DIR_OUT));
+ rxis &= ~TU_BIT(num);
+ }
+}
+
+#endif
diff --git a/circuitpython/lib/tinyusb/src/portable/sunxi/musb_def.h b/circuitpython/lib/tinyusb/src/portable/sunxi/musb_def.h
new file mode 100644
index 0000000..602b4f1
--- /dev/null
+++ b/circuitpython/lib/tinyusb/src/portable/sunxi/musb_def.h
@@ -0,0 +1,643 @@
+/*
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2021 Koji KITAYAMA
+ * Copyright (c) 2021 Tian Yunhao (t123yh)
+ * Copyright (c) 2021 Ha Thach (tinyusb.org)
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ *
+ * This file is part of the TinyUSB stack.
+ */
+
+#ifndef _TUSB_MUSB_DEF
+#define _TUSB_MUSB_DEF
+
+
+#define USBC_Readb(reg) (*(volatile unsigned char *)(reg))
+#define USBC_Readw(reg) (*(volatile unsigned short *)(reg))
+#define USBC_Readl(reg) (*(volatile unsigned long *)(reg))
+
+#define USBC_Writeb(value, reg) (*(volatile unsigned char *)(reg) = (value))
+#define USBC_Writew(value, reg) (*(volatile unsigned short *)(reg) = (value))
+#define USBC_Writel(value, reg) (*(volatile unsigned long *)(reg) = (value))
+
+
+#define USBC_SetBit_Mask_b(reg,mask) do { \
+ unsigned char _r = USBC_Readb(reg); \
+ _r |= (unsigned char)(mask); \
+ USBC_Writeb(_r,reg); \
+ }while(0)
+#define USBC_SetBit_Mask_w(reg,mask) do { \
+ unsigned short _r = USBC_Readw(reg); \
+ _r |= (unsigned short)(mask); \
+ USBC_Writew(_r,reg); \
+ }while(0)
+#define USBC_SetBit_Mask_l(reg,mask) do { \
+ unsigned int _r = USBC_Readl(reg); \
+ _r |= (unsigned int)(mask); \
+ USBC_Writel(_r,reg); \
+ }while(0)
+
+
+#define USBC_ClrBit_Mask_b(reg,mask) do { \
+ unsigned char _r = USBC_Readb(reg); \
+ _r &= (~(unsigned char)(mask)); \
+ USBC_Writeb(_r,reg); \
+ }while(0);
+#define USBC_ClrBit_Mask_w(reg,mask) do { \
+ unsigned short _r = USBC_Readw(reg); \
+ _r &= (~(unsigned short)(mask)); \
+ USBC_Writew(_r,reg); \
+ }while(0)
+#define USBC_ClrBit_Mask_l(reg,mask) do { \
+ unsigned int _r = USBC_Readl(reg); \
+ _r &= (~(unsigned int)(mask)); \
+ USBC_Writel(_r,reg); \
+ }while(0)
+#define USBC_REG_test_bit_b(bp, reg) (USBC_Readb(reg) & (1 << (bp)))
+#define USBC_REG_test_bit_w(bp, reg) (USBC_Readw(reg) & (1 << (bp)))
+#define USBC_REG_test_bit_l(bp, reg) (USBC_Readl(reg) & (1 << (bp)))
+
+#define USBC_REG_set_bit_b(bp, reg) (USBC_Writeb((USBC_Readb(reg) | (1 << (bp))) , (reg)))
+#define USBC_REG_set_bit_w(bp, reg) (USBC_Writew((USBC_Readw(reg) | (1 << (bp))) , (reg)))
+#define USBC_REG_set_bit_l(bp, reg) (USBC_Writel((USBC_Readl(reg) | (1 << (bp))) , (reg)))
+
+#define USBC_REG_clear_bit_b(bp, reg) (USBC_Writeb((USBC_Readb(reg) & (~ (1 << (bp)))) , (reg)))
+#define USBC_REG_clear_bit_w(bp, reg) (USBC_Writew((USBC_Readw(reg) & (~ (1 << (bp)))) , (reg)))
+#define USBC_REG_clear_bit_l(bp, reg) (USBC_Writel((USBC_Readl(reg) & (~ (1 << (bp)))) , (reg)))
+
+#define SW_UDC_EPNUMS 3
+
+#define SUNXI_SRAMC_BASE 0x01c00000
+//---------------------------------------------------------------
+// reg base
+//---------------------------------------------------------------
+#define USBC0_BASE 0x01c13000
+#define USBC1_BASE 0x01c14000
+#define USBC2_BASE 0x01c1E000
+
+//Some reg whithin musb
+#define USBPHY_CLK_REG 0x01c200CC
+#define USBPHY_CLK_RST_BIT 0
+#define USBPHY_CLK_GAT_BIT 1
+
+#define BUS_CLK_RST_REG 0x01c202c0 //Bus Clock Reset Register Bit24 : USB CLK RST
+#define BUS_RST_USB_BIT 24
+
+#define BUS_CLK_GATE0_REG 0x01c20060 //Bus Clock Gating Register Bit24 : USB CLK GATE 0: Mask 1 : Pass
+#define BUS_CLK_USB_BIT 24
+
+//#define USB_INTR
+
+#define NDMA_CFG_REG
+//-----------------------------------------------------------------------
+// musb reg offset
+//-----------------------------------------------------------------------
+
+#define USBC_REG_o_FADDR 0x0098
+#define USBC_REG_o_PCTL 0x0040
+#define USBC_REG_o_INTTx 0x0044
+#define USBC_REG_o_INTRx 0x0046
+#define USBC_REG_o_INTTxE 0x0048
+#define USBC_REG_o_INTRxE 0x004A
+#define USBC_REG_o_INTUSB 0x004C
+#define USBC_REG_o_INTUSBE 0x0050
+#define USBC_REG_o_FRNUM 0x0054
+#define USBC_REG_o_EPIND 0x0042
+#define USBC_REG_o_TMCTL 0x007C
+
+#define USBC_REG_o_TXMAXP 0x0080
+#define USBC_REG_o_CSR0 0x0082
+#define USBC_REG_o_TXCSR 0x0082
+#define USBC_REG_o_RXMAXP 0x0084
+#define USBC_REG_o_RXCSR 0x0086
+#define USBC_REG_o_COUNT0 0x0088
+#define USBC_REG_o_RXCOUNT 0x0088
+#define USBC_REG_o_EP0TYPE 0x008C
+#define USBC_REG_o_TXTYPE 0x008C
+#define USBC_REG_o_NAKLIMIT0 0x008D
+#define USBC_REG_o_TXINTERVAL 0x008D
+#define USBC_REG_o_RXTYPE 0x008E
+#define USBC_REG_o_RXINTERVAL 0x008F
+
+//#define USBC_REG_o_CONFIGDATA 0x001F //
+
+#define USBC_REG_o_EPFIFO0 0x0000
+#define USBC_REG_o_EPFIFO1 0x0004
+#define USBC_REG_o_EPFIFO2 0x0008
+#define USBC_REG_o_EPFIFO3 0x000C
+#define USBC_REG_o_EPFIFO4 0x0010
+#define USBC_REG_o_EPFIFO5 0x0014
+#define USBC_REG_o_EPFIFOx(n) (0x0000 + (n<<2))
+
+#define USBC_REG_o_DEVCTL 0x0041
+
+#define USBC_REG_o_TXFIFOSZ 0x0090
+#define USBC_REG_o_RXFIFOSZ 0x0094
+#define USBC_REG_o_TXFIFOAD 0x0092
+#define USBC_REG_o_RXFIFOAD 0x0096
+
+#define USBC_REG_o_VEND0 0x0043
+#define USBC_REG_o_VEND1 0x007D
+#define USBC_REG_o_VEND3 0x007E
+
+//#define USBC_REG_o_PHYCTL 0x006C
+#define USBC_REG_o_EPINFO 0x0078
+#define USBC_REG_o_RAMINFO 0x0079
+#define USBC_REG_o_LINKINFO 0x007A
+#define USBC_REG_o_VPLEN 0x007B
+#define USBC_REG_o_HSEOF 0x007C
+#define USBC_REG_o_FSEOF 0x007D
+#define USBC_REG_o_LSEOF 0x007E
+
+//new
+#define USBC_REG_o_FADDR0 0x0098
+#define USBC_REG_o_HADDR0 0x009A
+#define USBC_REG_o_HPORT0 0x009B
+#define USBC_REG_o_TXFADDRx 0x0098
+#define USBC_REG_o_TXHADDRx 0x009A
+#define USBC_REG_o_TXHPORTx 0x009B
+#define USBC_REG_o_RXFADDRx 0x009C
+#define USBC_REG_o_RXHADDRx 0x009E
+#define USBC_REG_o_RXHPORTx 0x009F
+
+
+#define USBC_REG_o_RPCOUNT 0x008A
+
+//new
+#define USBC_REG_o_ISCR 0x0400
+#define USBC_REG_o_PHYCTL 0x0404
+#define USBC_REG_o_PHYBIST 0x0408
+#define USBC_REG_o_PHYTUNE 0x040c
+
+#define USBC_REG_o_CSR 0x0410
+
+#define USBC_REG_o_PMU_IRQ 0x0800
+
+//-----------------------------------------------------------------------
+// registers
+//-----------------------------------------------------------------------
+
+#define USBC_REG_FADDR(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_FADDR )
+#define USBC_REG_PCTL(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_PCTL )
+#define USBC_REG_INTTx(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_INTTx )
+#define USBC_REG_INTRx(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_INTRx )
+#define USBC_REG_INTTxE(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_INTTxE )
+#define USBC_REG_INTRxE(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_INTRxE )
+#define USBC_REG_INTUSB(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_INTUSB )
+#define USBC_REG_INTUSBE(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_INTUSBE )
+#define USBC_REG_FRNUM(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_FRNUM )
+#define USBC_REG_EPIND(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_EPIND )
+#define USBC_REG_TMCTL(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_TMCTL )
+#define USBC_REG_TXMAXP(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_TXMAXP )
+
+#define USBC_REG_CSR0(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_CSR0 )
+#define USBC_REG_TXCSR(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_TXCSR )
+
+#define USBC_REG_RXMAXP(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_RXMAXP )
+#define USBC_REG_RXCSR(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_RXCSR )
+
+#define USBC_REG_COUNT0(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_COUNT0 )
+#define USBC_REG_RXCOUNT(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_RXCOUNT )
+
+#define USBC_REG_EP0TYPE(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_EP0TYPE )
+#define USBC_REG_TXTYPE(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_TXTYPE )
+
+#define USBC_REG_NAKLIMIT0(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_NAKLIMIT0 )
+#define USBC_REG_TXINTERVAL(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_TXINTERVAL )
+
+#define USBC_REG_RXTYPE(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_RXTYPE )
+#define USBC_REG_RXINTERVAL(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_RXINTERVAL )
+//#define USBC_REG_CONFIGDATA(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_CONFIGDATA )
+#define USBC_REG_EPFIFO0(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_EPFIFO0 )
+#define USBC_REG_EPFIFO1(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_EPFIFO1 )
+#define USBC_REG_EPFIFO2(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_EPFIFO2 )
+#define USBC_REG_EPFIFO3(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_EPFIFO3 )
+#define USBC_REG_EPFIFO4(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_EPFIFO4 )
+#define USBC_REG_EPFIFO5(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_EPFIFO5 )
+#define USBC_REG_EPFIFOx(usbc_base_addr, n) ((usbc_base_addr) + USBC_REG_o_EPFIFOx(n) )
+#define USBC_REG_DEVCTL(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_DEVCTL )
+#define USBC_REG_TXFIFOSZ(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_TXFIFOSZ )
+#define USBC_REG_RXFIFOSZ(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_RXFIFOSZ )
+#define USBC_REG_TXFIFOAD(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_TXFIFOAD )
+#define USBC_REG_RXFIFOAD(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_RXFIFOAD )
+#define USBC_REG_VEND0(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_VEND0 )
+#define USBC_REG_VEND1(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_VEND1 )
+#define USBC_REG_EPINFO(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_EPINFO )
+#define USBC_REG_RAMINFO(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_RAMINFO )
+#define USBC_REG_LINKINFO(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_LINKINFO )
+#define USBC_REG_VPLEN(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_VPLEN )
+#define USBC_REG_HSEOF(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_HSEOF )
+#define USBC_REG_FSEOF(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_FSEOF )
+#define USBC_REG_LSEOF(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_LSEOF )
+
+#define USBC_REG_FADDR0(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_FADDR0 )
+#define USBC_REG_HADDR0(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_HADDR0 )
+#define USBC_REG_HPORT0(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_HPORT0 )
+
+#define USBC_REG_TXFADDRx(usbc_base_addr, n) ((usbc_base_addr) + USBC_REG_o_TXFADDRx )
+#define USBC_REG_TXHADDRx(usbc_base_addr, n) ((usbc_base_addr) + USBC_REG_o_TXHADDRx )
+#define USBC_REG_TXHPORTx(usbc_base_addr, n) ((usbc_base_addr) + USBC_REG_o_TXHPORTx )
+#define USBC_REG_RXFADDRx(usbc_base_addr, n) ((usbc_base_addr) + USBC_REG_o_RXFADDRx )
+#define USBC_REG_RXHADDRx(usbc_base_addr, n) ((usbc_base_addr) + USBC_REG_o_RXHADDRx )
+#define USBC_REG_RXHPORTx(usbc_base_addr, n) ((usbc_base_addr) + USBC_REG_o_RXHPORTx )
+
+#define USBC_REG_RPCOUNTx(usbc_base_addr, n) ((usbc_base_addr) + USBC_REG_o_RPCOUNT )
+
+#define USBC_REG_ISCR(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_ISCR )
+#define USBC_REG_PHYCTL(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_PHYCTL )
+#define USBC_REG_PHYBIST(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_PHYBIST )
+#define USBC_REG_PHYTUNE(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_PHYTUNE )
+#define USBC_REG_PMU_IRQ(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_PMU_IRQ )
+#define USBC_REG_CSR(usbc_base_addr) ((usbc_base_addr) + USBC_REG_o_CSR)
+//-----------------------------------------------------------------------
+// bit position
+//-----------------------------------------------------------------------
+
+/* USB Power Control for Host only */
+#define USBC_BP_POWER_H_HIGH_SPEED_EN 5
+#define USBC_BP_POWER_H_HIGH_SPEED_FLAG 4
+#define USBC_BP_POWER_H_RESET 3
+#define USBC_BP_POWER_H_RESUME 2
+#define USBC_BP_POWER_H_SUSPEND 1
+#define USBC_BP_POWER_H_SUEPEND_EN 0
+
+/* USB Power Control for device only */
+#define USBC_BP_POWER_D_ISO_UPDATE_EN 7
+#define USBC_BP_POWER_D_SOFT_CONNECT 6
+#define USBC_BP_POWER_D_HIGH_SPEED_EN 5
+#define USBC_BP_POWER_D_HIGH_SPEED_FLAG 4
+#define USBC_BP_POWER_D_RESET_FLAG 3
+#define USBC_BP_POWER_D_RESUME 2
+#define USBC_BP_POWER_D_SUSPEND 1
+#define USBC_BP_POWER_D_ENABLE_SUSPENDM 0
+
+/* interrupt flags for ep0 and the Tx ep1~4 */
+#define USBC_BP_INTTx_FLAG_EP5 5
+#define USBC_BP_INTTx_FLAG_EP4 4
+#define USBC_BP_INTTx_FLAG_EP3 3
+#define USBC_BP_INTTx_FLAG_EP2 2
+#define USBC_BP_INTTx_FLAG_EP1 1
+#define USBC_BP_INTTx_FLAG_EP0 0
+
+/* interrupt flags for Rx ep1~4 */
+#define USBC_BP_INTRx_FLAG_EP5 5
+#define USBC_BP_INTRx_FLAG_EP4 4
+#define USBC_BP_INTRx_FLAG_EP3 3
+#define USBC_BP_INTRx_FLAG_EP2 2
+#define USBC_BP_INTRx_FLAG_EP1 1
+
+/* interrupt enable for Tx ep0~4 */
+#define USBC_BP_INTTxE_EN_EP5 5
+#define USBC_BP_INTTxE_EN_EP4 4
+#define USBC_BP_INTTxE_EN_EP3 3
+#define USBC_BP_INTTxE_EN_EP2 2
+#define USBC_BP_INTTxE_EN_EP1 1
+#define USBC_BP_INTTxE_EN_EP0 0
+
+/* interrupt enable for Rx ep1~4 */
+#define USBC_BP_INTRxE_EN_EP5 5
+#define USBC_BP_INTRxE_EN_EP4 4
+#define USBC_BP_INTRxE_EN_EP3 3
+#define USBC_BP_INTRxE_EN_EP2 2
+#define USBC_BP_INTRxE_EN_EP1 1
+
+/* USB interrupt */
+#define USBC_BP_INTUSB_VBUS_ERROR 7
+#define USBC_BP_INTUSB_SESSION_REQ 6
+#define USBC_BP_INTUSB_DISCONNECT 5
+#define USBC_BP_INTUSB_CONNECT 4
+#define USBC_BP_INTUSB_SOF 3
+#define USBC_BP_INTUSB_RESET 2
+#define USBC_BP_INTUSB_RESUME 1
+#define USBC_BP_INTUSB_SUSPEND 0
+
+/* USB interrupt enable */
+#define USBC_BP_INTUSBE_EN_VBUS_ERROR 7
+#define USBC_BP_INTUSBE_EN_SESSION_REQ 6
+#define USBC_BP_INTUSBE_EN_DISCONNECT 5
+#define USBC_BP_INTUSBE_EN_CONNECT 4
+#define USBC_BP_INTUSBE_EN_SOF 3
+#define USBC_BP_INTUSBE_EN_RESET 2
+#define USBC_BP_INTUSBE_EN_RESUME 1
+#define USBC_BP_INTUSBE_EN_SUSPEND 0
+
+/* Test Mode Control */
+#define USBC_BP_TMCTL_FORCE_HOST 7
+#define USBC_BP_TMCTL_FIFO_ACCESS 6
+#define USBC_BP_TMCTL_FORCE_FS 5
+#define USBC_BP_TMCTL_FORCE_HS 4
+#define USBC_BP_TMCTL_TEST_PACKET 3
+#define USBC_BP_TMCTL_TEST_K 2
+#define USBC_BP_TMCTL_TEST_J 1
+#define USBC_BP_TMCTL_TEST_SE0_NAK 0
+
+/* Tx Max packet */
+#define USBC_BP_TXMAXP_PACKET_COUNT 11
+#define USBC_BP_TXMAXP_MAXIMUM_PAYLOAD 0
+
+/* Control and Status Register for ep0 for Host only */
+#define USBC_BP_CSR0_H_DisPing 11
+#define USBC_BP_CSR0_H_FlushFIFO 8
+#define USBC_BP_CSR0_H_NAK_Timeout 7
+#define USBC_BP_CSR0_H_StatusPkt 6
+#define USBC_BP_CSR0_H_ReqPkt 5
+#define USBC_BP_CSR0_H_Error 4
+#define USBC_BP_CSR0_H_SetupPkt 3
+#define USBC_BP_CSR0_H_RxStall 2
+#define USBC_BP_CSR0_H_TxPkRdy 1
+#define USBC_BP_CSR0_H_RxPkRdy 0
+
+/* Control and Status Register for ep0 for device only */
+#define USBC_BP_CSR0_D_FLUSH_FIFO 8
+#define USBC_BP_CSR0_D_SERVICED_SETUP_END 7
+#define USBC_BP_CSR0_D_SERVICED_RX_PKT_READY 6
+#define USBC_BP_CSR0_D_SEND_STALL 5
+#define USBC_BP_CSR0_D_SETUP_END 4
+#define USBC_BP_CSR0_D_DATA_END 3
+#define USBC_BP_CSR0_D_SENT_STALL 2
+#define USBC_BP_CSR0_D_TX_PKT_READY 1
+#define USBC_BP_CSR0_D_RX_PKT_READY 0
+
+/* Tx ep Control and Status Register for Host only */
+#define USBC_BP_TXCSR_H_AUTOSET 15
+#define USBC_BP_TXCSR_H_RESERVED 14
+#define USBC_BP_TXCSR_H_MODE 13
+#define USBC_BP_TXCSR_H_DMA_REQ_EN 12
+#define USBC_BP_TXCSR_H_FORCE_DATA_TOGGLE 11
+#define USBC_BP_TXCSR_H_DMA_REQ_MODE 10
+#define USBC_BP_TXCSR_H_NAK_TIMEOUT 7
+#define USBC_BP_TXCSR_H_CLEAR_DATA_TOGGLE 6
+#define USBC_BP_TXCSR_H_TX_STALL 5
+#define USBC_BP_TXCSR_H_FLUSH_FIFO 3
+#define USBC_BP_TXCSR_H_ERROR 2
+#define USBC_BP_TXCSR_H_FIFO_NOT_EMPTY 1
+#define USBC_BP_TXCSR_H_TX_READY 0
+
+/* Tx ep Control and Status Register for Device only */
+#define USBC_BP_TXCSR_D_AUTOSET 15
+#define USBC_BP_TXCSR_D_ISO 14
+#define USBC_BP_TXCSR_D_MODE 13
+#define USBC_BP_TXCSR_D_DMA_REQ_EN 12
+#define USBC_BP_TXCSR_D_FORCE_DATA_TOGGLE 11
+#define USBC_BP_TXCSR_D_DMA_REQ_MODE 10
+#define USBC_BP_TXCSR_D_INCOMPLETE 7
+#define USBC_BP_TXCSR_D_CLEAR_DATA_TOGGLE 6
+#define USBC_BP_TXCSR_D_SENT_STALL 5
+#define USBC_BP_TXCSR_D_SEND_STALL 4
+#define USBC_BP_TXCSR_D_FLUSH_FIFO 3
+#define USBC_BP_TXCSR_D_UNDER_RUN 2
+#define USBC_BP_TXCSR_D_FIFO_NOT_EMPTY 1
+#define USBC_BP_TXCSR_D_TX_READY 0
+
+/* Rx Max Packet */
+#define USBC_BP_RXMAXP_PACKET_COUNT 11
+#define USBC_BP_RXMAXP_MAXIMUM_PAYLOAD 0
+
+/* Rx ep Control and Status Register for Host only */
+#define USBC_BP_RXCSR_H_AUTO_CLEAR 15
+#define USBC_BP_RXCSR_H_AUTO_REQ 14
+#define USBC_BP_RXCSR_H_DMA_REQ_EN 13
+#define USBC_BP_RXCSR_H_PID_ERROR 12
+#define USBC_BP_RXCSR_H_DMA_REQ_MODE 11
+
+#define USBC_BP_RXCSR_H_INCOMPLETE 8
+#define USBC_BP_RXCSR_H_CLEAR_DATA_TOGGLE 7
+#define USBC_BP_RXCSR_H_RX_STALL 6
+#define USBC_BP_RXCSR_H_REQ_PACKET 5
+#define USBC_BP_RXCSR_H_FLUSH_FIFO 4
+#define USBC_BP_RXCSR_H_NAK_TIMEOUT 3
+#define USBC_BP_RXCSR_H_ERROR 2
+#define USBC_BP_RXCSR_H_FIFO_FULL 1
+#define USBC_BP_RXCSR_H_RX_PKT_READY 0
+
+/* Rx ep Control and Status Register for Device only */
+#define USBC_BP_RXCSR_D_AUTO_CLEAR 15
+#define USBC_BP_RXCSR_D_ISO 14
+#define USBC_BP_RXCSR_D_DMA_REQ_EN 13
+#define USBC_BP_RXCSR_D_DISABLE_NYET 12
+#define USBC_BP_RXCSR_D_DMA_REQ_MODE 11
+
+#define USBC_BP_RXCSR_D_INCOMPLETE 8
+#define USBC_BP_RXCSR_D_CLEAR_DATA_TOGGLE 7
+#define USBC_BP_RXCSR_D_SENT_STALL 6
+#define USBC_BP_RXCSR_D_SEND_STALL 5
+#define USBC_BP_RXCSR_D_FLUSH_FIFO 4
+#define USBC_BP_RXCSR_D_DATA_ERROR 3
+#define USBC_BP_RXCSR_D_OVERRUN 2
+#define USBC_BP_RXCSR_D_FIFO_FULL 1
+#define USBC_BP_RXCSR_D_RX_PKT_READY 0
+
+/* Tx Type Register for host only */
+#define USBC_BP_TXTYPE_SPEED 6 //new
+#define USBC_BP_TXTYPE_PROROCOL 4
+#define USBC_BP_TXTYPE_TARGET_EP_NUM 0
+
+/* Rx Type Register for host only */
+#define USBC_BP_RXTYPE_SPEED 6 //new
+#define USBC_BP_RXTYPE_PROROCOL 4
+#define USBC_BP_RXTYPE_TARGET_EP_NUM 0
+
+/* Core Configueation */
+#define USBC_BP_CONFIGDATA_MPRXE 7
+#define USBC_BP_CONFIGDATA_MPTXE 6
+#define USBC_BP_CONFIGDATA_BIGENDIAN 5
+#define USBC_BP_CONFIGDATA_HBRXE 4
+#define USBC_BP_CONFIGDATA_HBTXE 3
+#define USBC_BP_CONFIGDATA_DYNFIFO_SIZING 2
+#define USBC_BP_CONFIGDATA_SOFTCONE 1
+#define USBC_BP_CONFIGDATA_UTMI_DATAWIDTH 0
+
+/* OTG Device Control */
+#define USBC_BP_DEVCTL_B_DEVICE 7
+#define USBC_BP_DEVCTL_FS_DEV 6
+#define USBC_BP_DEVCTL_LS_DEV 5
+
+#define USBC_BP_DEVCTL_VBUS 3
+#define USBC_BP_DEVCTL_HOST_MODE 2
+#define USBC_BP_DEVCTL_HOST_REQ 1
+#define USBC_BP_DEVCTL_SESSION 0
+
+/* Tx EP FIFO size control */
+#define USBC_BP_TXFIFOSZ_DPB 4
+#define USBC_BP_TXFIFOSZ_SZ 0
+
+/* Rx EP FIFO size control */
+#define USBC_BP_RXFIFOSZ_DPB 4
+#define USBC_BP_RXFIFOSZ_SZ 0
+
+/* vendor0 */
+#define USBC_BP_VEND0_DRQ_SEL 1
+#define USBC_BP_VEND0_BUS_SEL 0
+
+/* hub address */
+#define USBC_BP_HADDR_MULTI_TT 7
+
+/* Interface Status and Control */
+#define USBC_BP_ISCR_VBUS_VALID_FROM_DATA 30
+#define USBC_BP_ISCR_VBUS_VALID_FROM_VBUS 29
+#define USBC_BP_ISCR_EXT_ID_STATUS 28
+#define USBC_BP_ISCR_EXT_DM_STATUS 27
+#define USBC_BP_ISCR_EXT_DP_STATUS 26
+#define USBC_BP_ISCR_MERGED_VBUS_STATUS 25
+#define USBC_BP_ISCR_MERGED_ID_STATUS 24
+
+#define USBC_BP_ISCR_ID_PULLUP_EN 17
+#define USBC_BP_ISCR_DPDM_PULLUP_EN 16
+#define USBC_BP_ISCR_FORCE_ID 14
+#define USBC_BP_ISCR_FORCE_VBUS_VALID 12
+#define USBC_BP_ISCR_VBUS_VALID_SRC 10
+
+#define USBC_BP_ISCR_HOSC_EN 7
+#define USBC_BP_ISCR_VBUS_CHANGE_DETECT 6
+#define USBC_BP_ISCR_ID_CHANGE_DETECT 5
+#define USBC_BP_ISCR_DPDM_CHANGE_DETECT 4
+#define USBC_BP_ISCR_IRQ_ENABLE 3
+#define USBC_BP_ISCR_VBUS_CHANGE_DETECT_EN 2
+#define USBC_BP_ISCR_ID_CHANGE_DETECT_EN 1
+#define USBC_BP_ISCR_DPDM_CHANGE_DETECT_EN 0
+
+
+#define SUNXI_EHCI_AHB_ICHR8_EN (1 << 10)
+#define SUNXI_EHCI_AHB_INCR4_BURST_EN (1 << 9)
+#define SUNXI_EHCI_AHB_INCRX_ALIGN_EN (1 << 8)
+#define SUNXI_EHCI_ULPI_BYPASS_EN (1 << 0)
+//-----------------------------------------------------------------------
+// �Զ���
+//-----------------------------------------------------------------------
+
+/* usb��Դ���� */
+#define USBC_MAX_CTL_NUM 1
+#define USBC_MAX_EP_NUM 3 //ep0~2, ep�ĸ���
+#define USBC_MAX_FIFO_SIZE (2 * 1024)
+
+/* usb OTG mode */
+#define USBC_OTG_HOST 0
+#define USBC_OTG_DEVICE 1
+
+/* usb device type */
+#define USBC_DEVICE_HSDEV 0
+#define USBC_DEVICE_FSDEV 1
+#define USBC_DEVICE_LSDEV 2
+
+/* usb transfer type */
+#define USBC_TS_TYPE_IDLE 0
+#define USBC_TS_TYPE_CTRL 1
+#define USBC_TS_TYPE_ISO 2
+#define USBC_TS_TYPE_INT 3
+#define USBC_TS_TYPE_BULK 4
+
+/* usb transfer mode */
+#define USBC_TS_MODE_UNKOWN 0
+#define USBC_TS_MODE_LS 1
+#define USBC_TS_MODE_FS 2
+#define USBC_TS_MODE_HS 3
+
+/* usb Vbus status */
+#define USBC_VBUS_STATUS_BELOW_SESSIONEND 0
+#define USBC_VBUS_STATUS_ABOVE_SESSIONEND_BELOW_AVALID 1
+#define USBC_VBUS_STATUS_ABOVE_AVALID_BELOW_VBUSVALID 2
+#define USBC_VBUS_STATUS_ABOVE_VBUSVALID 3
+
+/* usb io type */
+#define USBC_IO_TYPE_PIO 0
+#define USBC_IO_TYPE_DMA 1
+
+/* usb ep type */
+#define USBC_EP_TYPE_IDLE 0
+#define USBC_EP_TYPE_EP0 1
+#define USBC_EP_TYPE_TX 2
+#define USBC_EP_TYPE_RX 3
+
+/* usb id type */
+#define USBC_ID_TYPE_DISABLE 0
+#define USBC_ID_TYPE_HOST 1
+#define USBC_ID_TYPE_DEVICE 2
+
+/* usb vbus valid type */
+#define USBC_VBUS_TYPE_DISABLE 0
+#define USBC_VBUS_TYPE_LOW 1
+#define USBC_VBUS_TYPE_HIGH 2
+
+/* usb a valid source */
+#define USBC_A_VALID_SOURCE_UTMI_AVALID 0
+#define USBC_A_VALID_SOURCE_UTMI_VBUS 1
+
+/* usb device switch */
+#define USBC_DEVICE_SWITCH_OFF 0
+#define USBC_DEVICE_SWITCH_ON 1
+
+/* usb fifo config mode */
+#define USBC_FIFO_MODE_4K 0
+#define USBC_FIFO_MODE_8K 1
+
+/*
+ **************************************************
+ * usb interrupt mask
+ *
+ **************************************************
+ */
+
+/* interrupt flags for ep0 and the Tx ep1~4 */
+#define USBC_INTTx_FLAG_EP5 (1 << USBC_BP_INTTx_FLAG_EP5)
+#define USBC_INTTx_FLAG_EP4 (1 << USBC_BP_INTTx_FLAG_EP4)
+#define USBC_INTTx_FLAG_EP3 (1 << USBC_BP_INTTx_FLAG_EP3)
+#define USBC_INTTx_FLAG_EP2 (1 << USBC_BP_INTTx_FLAG_EP2)
+#define USBC_INTTx_FLAG_EP1 (1 << USBC_BP_INTTx_FLAG_EP1)
+#define USBC_INTTx_FLAG_EP0 (1 << USBC_BP_INTTx_FLAG_EP0)
+
+/* interrupt flags for Rx ep1~4 */
+#define USBC_INTRx_FLAG_EP5 (1 << USBC_BP_INTRx_FLAG_EP5)
+#define USBC_INTRx_FLAG_EP4 (1 << USBC_BP_INTRx_FLAG_EP4)
+#define USBC_INTRx_FLAG_EP3 (1 << USBC_BP_INTRx_FLAG_EP3)
+#define USBC_INTRx_FLAG_EP2 (1 << USBC_BP_INTRx_FLAG_EP2)
+#define USBC_INTRx_FLAG_EP1 (1 << USBC_BP_INTRx_FLAG_EP1)
+
+/* USB interrupt */
+#define USBC_INTUSB_VBUS_ERROR (1 << USBC_BP_INTUSB_VBUS_ERROR)
+#define USBC_INTUSB_SESSION_REQ (1 << USBC_BP_INTUSB_SESSION_REQ)
+#define USBC_INTUSB_DISCONNECT (1 << USBC_BP_INTUSB_DISCONNECT)
+#define USBC_INTUSB_CONNECT (1 << USBC_BP_INTUSB_CONNECT)
+#define USBC_INTUSB_SOF (1 << USBC_BP_INTUSB_SOF)
+#define USBC_INTUSB_RESET (1 << USBC_BP_INTUSB_RESET)
+#define USBC_INTUSB_RESUME (1 << USBC_BP_INTUSB_RESUME)
+#define USBC_INTUSB_SUSPEND (1 << USBC_BP_INTUSB_SUSPEND)
+
+#define USB_CSRL0_NAKTO 0x00000080 // NAK Timeout
+#define USB_CSRL0_SETENDC 0x00000080 // Setup End Clear
+#define USB_CSRL0_STATUS 0x00000040 // STATUS Packet
+#define USB_CSRL0_RXRDYC 0x00000040 // RXRDY Clear
+#define USB_CSRL0_REQPKT 0x00000020 // Request Packet
+#define USB_CSRL0_STALL 0x00000020 // Send Stall
+#define USB_CSRL0_SETEND 0x00000010 // Setup End
+#define USB_CSRL0_ERROR 0x00000010 // Error
+#define USB_CSRL0_DATAEND 0x00000008 // Data End
+#define USB_CSRL0_SETUP 0x00000008 // Setup Packet
+#define USB_CSRL0_STALLED 0x00000004 // Endpoint Stalled
+#define USB_CSRL0_TXRDY 0x00000002 // Transmit Packet Ready
+#define USB_CSRL0_RXRDY 0x00000001 // Receive Packet Ready
+
+#define USB_RXFIFOSZ_DPB 0x00000010 // Double Packet Buffer Support
+#define USB_RXFIFOSZ_SIZE_M 0x0000000F // Max Packet Size
+
+#define USB_TXFIFOSZ_DPB 0x00000010 // Double Packet Buffer Support
+#define USB_TXFIFOSZ_SIZE_M 0x0000000F // Max Packet Size
+
+#endif