Merge branch 'master' of https://github.com/hathach/tinyusb into stm32_fsdev

This commit is contained in:
Mengsk
2022-12-29 12:14:52 +01:00
478 changed files with 38365 additions and 14680 deletions

View File

@@ -587,7 +587,7 @@ void dcd_remote_wakeup(uint8_t rhport)
SYS->MSC0CFG = SYS->MSC0CFG | MASK_SYS_MSC0CFG_DEV_RMWAKEUP;
// Atleast 2 ms of delay needed for RESUME Data K state.
// At least 2 ms of delay needed for RESUME Data K state.
delayms(2);
SYS->MSC0CFG &= ~MASK_SYS_MSC0CFG_DEV_RMWAKEUP;
@@ -720,7 +720,7 @@ bool dcd_edpt_open(uint8_t rhport, tusb_desc_endpoint_t const *ep_desc)
else
total_ram = USBD_RAMTOTAL_OUT;
// Work out how much has been allocated to existing endpoints.
// The total RAM allocated shoudl alsyes be a positive number as this
// The total RAM allocated should always be a positive number as this
// algorithm should not let it go below zero.
for (int i = 1; i < USBD_MAX_ENDPOINT_COUNT; i++)
{
@@ -976,7 +976,7 @@ void dcd_int_handler(uint8_t rhport)
USBD_EP_SR_REG(USBD_EP_0) = MASK_USBD_EP0SR_STALL;
}
// Host has sent a SETUP packet. Recieve this into the setup packet store.
// Host has sent a SETUP packet. Receive this into the setup packet store.
_ft90x_dusb_out(USBD_EP_0, (uint8_t *)_ft90x_setup_packet, sizeof(USB_device_request));
// Send the packet to tinyusb.

View File

@@ -243,7 +243,7 @@ static struct
// Converts xfer pointer to epnum (0,1,2,3) regardless of xfer direction
#define XFER_EPNUM(xfer) ((xfer - &_dcd.xfer_status[0][0]) >> 1)
// Converts xfer pinter to EPx_REGS pointer (returns same pointer for IN and OUT with same endpoint number)
// Converts xfer pointer to EPx_REGS pointer (returns same pointer for IN and OUT with same endpoint number)
#define XFER_REGS(xfer) ep_regs[XFER_EPNUM(xfer)]
// Converts epnum (0,1,2,3) to EPx_REGS pointer
#define EPNUM_REGS(epnum) ep_regs[epnum]

View File

@@ -199,7 +199,7 @@ static void list_remove_qhd_by_addr(ehci_link_t* list_head, uint8_t dev_addr)
#pragma GCC diagnostic pop
if ( qhd->dev_addr == dev_addr )
{
// TODO deactive all TD, wait for QHD to inactive before removal
// TODO deactivate all TD, wait for QHD to inactive before removal
prev->address = qhd->next.address;
// EHCI 4.8.2 link the removed qhd to async head (which always reachable by Host Controller)
@@ -839,7 +839,7 @@ static void qhd_init(ehci_qhd_t *p_qhd, uint8_t dev_addr, tusb_desc_endpoint_t c
if (TUSB_SPEED_HIGH == p_qhd->ep_speed)
{
TU_ASSERT( interval <= 16, );
if ( interval < 4) // sub milisecond interval
if ( interval < 4) // sub millisecond interval
{
p_qhd->interval_ms = 0;
p_qhd->int_smask = (interval == 1) ? TU_BIN8(11111111) :

View File

@@ -114,7 +114,7 @@ typedef struct
volatile uint32_t current_page : 3 ; ///< Index into the qTD buffer pointer list
uint32_t int_on_complete : 1 ; ///< Interrupt on complete
volatile uint32_t total_bytes : 15 ; ///< Transfer bytes, decreased during transaction
volatile uint32_t data_toggle : 1 ; ///< Data Toogle bit
volatile uint32_t data_toggle : 1 ; ///< Data Toggle bit
/// Buffer Page Pointer List, Each element in the list is a 4K page aligned, physical memory address. The lower 12 bits in each pointer are reserved (except for the first one) as each memory pointer must reference the start of a 4K page
@@ -160,7 +160,7 @@ typedef struct TU_ATTR_ALIGNED(32)
uint8_t used;
uint8_t removing; // removed from asyn list, waiting for async advance
uint8_t pid;
uint8_t interval_ms; // polling interval in frames (or milisecond)
uint8_t interval_ms; // polling interval in frames (or millisecond)
uint16_t total_xferred_bytes; // number of bytes xferred until a qtd with ioc bit set
uint8_t reserved2[2];
@@ -225,7 +225,7 @@ typedef struct TU_ATTR_ALIGNED(32)
uint16_t reserved ; ///< reserved
// Word 3: siTD Transfer Status and Control
// Status [7:0] TODO indentical to qTD Token'status --> refractor later
// Status [7:0] TODO identical to qTD Token'status --> refactor later
volatile uint32_t : 1 ; // reserved
volatile uint32_t split_state : 1 ;
volatile uint32_t missed_uframe : 1 ;
@@ -350,8 +350,8 @@ typedef volatile struct
uint32_t periodic_status : 1 ; ///< Periodic schedule status
uint32_t async_status : 1 ; ///< Async schedule status
uint32_t : 2 ;
uint32_t nxp_int_async : 1 ; ///< NXP customized: This bit is set by the Host Controller when the cause of an interrupt is a completion of a USB transaction where the Transfer Descriptor (TD) has an interrupt on complete (IOC) bit set andthe TD was from the asynchronous schedule. This bit is also set by the Host when a short packet is detected andthe packet is on the asynchronous schedule.
uint32_t nxp_int_period : 1 ; ///< NXP customized: This bit is set by the Host Controller when the cause of an interrupt is a completion of a USB transaction where the Transfer Descriptor (TD) has an interrupt on complete (IOC) bit set andthe TD was from the periodic schedule.
uint32_t nxp_int_async : 1 ; ///< NXP customized: This bit is set by the Host Controller when the cause of an interrupt is a completion of a USB transaction where the Transfer Descriptor (TD) has an interrupt on complete (IOC) bit set and the TD was from the asynchronous schedule. This bit is also set by the Host when a short packet is detected and the packet is on the asynchronous schedule.
uint32_t nxp_int_period : 1 ; ///< NXP customized: This bit is set by the Host Controller when the cause of an interrupt is a completion of a USB transaction where the Transfer Descriptor (TD) has an interrupt on complete (IOC) bit set and the TD was from the periodic schedule.
uint32_t : 12 ;
}status_bm;
};

View File

@@ -741,7 +741,7 @@ static void handle_epin_ints(void)
// XFER Timeout
if (USB0.in_ep_reg[n].diepint & USB_D_TIMEOUT0_M) {
// Clear interrupt or enpoint will hang.
// Clear interrupt or endpoint will hang.
USB0.in_ep_reg[n].diepint = USB_D_TIMEOUT0_M;
// Maybe retry?
}

View File

@@ -21,16 +21,16 @@
* THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
*******************************************************************************/
/*******************************************************************************
USBHS Peripheral Library Register Defintions
USBHS Peripheral Library Register Definitions
File Name:
usbhs_registers.h
Summary:
USBHS PLIB Register Defintions
USBHS PLIB Register Definitions
Description:
This file contains the constants and defintions which are required by the
This file contains the constants and definitions which are required by the
the USBHS library.
*******************************************************************************/

View File

@@ -42,7 +42,7 @@
# define USE_SOF 0
#endif
// Dual bank can imporve performance, but need 2 times bigger packet buffer
// Dual bank can improve performance, but need 2 times bigger packet buffer
// As SAM7x has only 4KB packet buffer, use with caution !
// Enable in FS mode as packets are smaller
#ifndef USE_DUAL_BANK
@@ -644,7 +644,7 @@ bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t
}
__set_PRIMASK(irq_state);
// Here a ZLP has been recieved
// Here a ZLP has been received
// and the DMA transfer must be not started.
// It is the end of transfer
return false;
@@ -734,7 +734,7 @@ bool dcd_edpt_xfer_fifo (uint8_t rhport, uint8_t ep_addr, tu_fifo_t * ff, uint16
}
__set_PRIMASK(irq_state);
// Here a ZLP has been recieved
// Here a ZLP has been received
// and the DMA transfer must be not started.
// It is the end of transfer
return false;

View File

@@ -170,7 +170,7 @@ static void xact_out_dma(uint8_t epnum)
uint32_t xact_len;
// DMA can't be active during read of SIZE.EPOUT or SIZE.ISOOUT, so try to lock,
// If already running deffer call regardless if it was called from ISR or task,
// If already running defer call regardless if it was called from ISR or task,
if ( atomic_flag_test_and_set(&_dcd.dma_running) )
{
usbd_defer_func((osal_task_func_t)xact_out_dma_wrapper, (void *)(uint32_t)epnum, is_in_isr());

View File

@@ -181,7 +181,7 @@ static void dcd_userEP_in_xfer(struct xfer_ctl_t *xfer, USBD_EP_T *ep)
ep->EPINTEN = USBD_EPINTEN_TXPKIEN_Msk;
}
/* provided buffers are thankfully 32-bit aligned, allowing most data to be transfered as 32-bit */
/* provided buffers are thankfully 32-bit aligned, allowing most data to be transferred as 32-bit */
#if 0 // TODO support dcd_edpt_xfer_fifo API
if (xfer->ff)
{

View File

@@ -165,7 +165,7 @@ bool hcd_init(uint8_t rhport)
//------------- Data Structure init -------------//
tu_memclr(&ohci_data, sizeof(ohci_data_t));
for(uint8_t i=0; i<32; i++)
{ // assign all interrupt pointes to period head ed
{ // assign all interrupt pointers to period head ed
ohci_data.hcca.interrupt_table[i] = (uint32_t) &ohci_data.period_head_ed;
}

View File

@@ -34,7 +34,7 @@
//--------------------------------------------------------------------+
// OHCI CONFIGURATION & CONSTANTS
//--------------------------------------------------------------------+
#define HOST_HCD_XFER_INTERRUPT // TODO interrupt is used widely, should always be enalbed
#define HOST_HCD_XFER_INTERRUPT // TODO interrupt is used widely, should always be enabled
#define OHCI_PERIODIC_LIST (defined HOST_HCD_XFER_INTERRUPT || defined HOST_HCD_XFER_ISOCHRONOUS)
// TODO merge OHCI with EHCI

View File

@@ -81,89 +81,90 @@ static struct hw_endpoint *get_dev_ep(uint8_t dev_addr, uint8_t ep_addr)
TU_ATTR_ALWAYS_INLINE static inline uint8_t dev_speed(void)
{
return (usb_hw->sie_status & USB_SIE_STATUS_SPEED_BITS) >> USB_SIE_STATUS_SPEED_LSB;
return (usb_hw->sie_status & USB_SIE_STATUS_SPEED_BITS) >> USB_SIE_STATUS_SPEED_LSB;
}
static bool need_pre(uint8_t dev_addr)
TU_ATTR_ALWAYS_INLINE static inline bool need_pre(uint8_t dev_addr)
{
// If this device is different to the speed of the root device
// (i.e. is a low speed device on a full speed hub) then need pre
return hcd_port_speed_get(0) != tuh_speed_get(dev_addr);
// If this device is different to the speed of the root device
// (i.e. is a low speed device on a full speed hub) then need pre
return hcd_port_speed_get(0) != tuh_speed_get(dev_addr);
}
static void __tusb_irq_path_func(hw_xfer_complete)(struct hw_endpoint *ep, xfer_result_t xfer_result)
{
// Mark transfer as done before we tell the tinyusb stack
uint8_t dev_addr = ep->dev_addr;
uint8_t ep_addr = ep->ep_addr;
uint xferred_len = ep->xferred_len;
hw_endpoint_reset_transfer(ep);
hcd_event_xfer_complete(dev_addr, ep_addr, xferred_len, xfer_result, true);
// Mark transfer as done before we tell the tinyusb stack
uint8_t dev_addr = ep->dev_addr;
uint8_t ep_addr = ep->ep_addr;
uint xferred_len = ep->xferred_len;
hw_endpoint_reset_transfer(ep);
hcd_event_xfer_complete(dev_addr, ep_addr, xferred_len, xfer_result, true);
}
static void __tusb_irq_path_func(_handle_buff_status_bit)(uint bit, struct hw_endpoint *ep)
{
usb_hw_clear->buf_status = bit;
// EP may have been stalled?
assert(ep->active);
bool done = hw_endpoint_xfer_continue(ep);
if (done)
{
hw_xfer_complete(ep, XFER_RESULT_SUCCESS);
}
usb_hw_clear->buf_status = bit;
// EP may have been stalled?
assert(ep->active);
bool done = hw_endpoint_xfer_continue(ep);
if ( done )
{
hw_xfer_complete(ep, XFER_RESULT_SUCCESS);
}
}
static void __tusb_irq_path_func(hw_handle_buff_status)(void)
{
uint32_t remaining_buffers = usb_hw->buf_status;
pico_trace("buf_status 0x%08x\n", remaining_buffers);
uint32_t remaining_buffers = usb_hw->buf_status;
pico_trace("buf_status 0x%08x\n", remaining_buffers);
// Check EPX first
uint bit = 0b1;
if (remaining_buffers & bit)
// Check EPX first
uint bit = 0b1;
if ( remaining_buffers & bit )
{
remaining_buffers &= ~bit;
struct hw_endpoint * ep = &epx;
uint32_t ep_ctrl = *ep->endpoint_control;
if ( ep_ctrl & EP_CTRL_DOUBLE_BUFFERED_BITS )
{
TU_LOG(3, "Double Buffered: ");
}
else
{
TU_LOG(3, "Single Buffered: ");
}
TU_LOG_HEX(3, ep_ctrl);
_handle_buff_status_bit(bit, ep);
}
// Check "interrupt" (asynchronous) endpoints for both IN and OUT
for ( uint i = 1; i <= USB_HOST_INTERRUPT_ENDPOINTS && remaining_buffers; i++ )
{
// EPX is bit 0 & 1
// IEP1 IN is bit 2
// IEP1 OUT is bit 3
// IEP2 IN is bit 4
// IEP2 OUT is bit 5
// IEP3 IN is bit 6
// IEP3 OUT is bit 7
// etc
for ( uint j = 0; j < 2; j++ )
{
bit = 1 << (i * 2 + j);
if ( remaining_buffers & bit )
{
remaining_buffers &= ~bit;
struct hw_endpoint *ep = &epx;
uint32_t ep_ctrl = *ep->endpoint_control;
if (ep_ctrl & EP_CTRL_DOUBLE_BUFFERED_BITS)
{
TU_LOG(3, "Double Buffered: ");
}else
{
TU_LOG(3, "Single Buffered: ");
}
TU_LOG_HEX(3, ep_ctrl);
_handle_buff_status_bit(bit, ep);
_handle_buff_status_bit(bit, &ep_pool[i]);
}
}
}
// Check "interrupt" (asynchronous) endpoints for both IN and OUT
for (uint i = 1; i <= USB_HOST_INTERRUPT_ENDPOINTS && remaining_buffers; i++)
{
// EPX is bit 0 & 1
// IEP1 IN is bit 2
// IEP1 OUT is bit 3
// IEP2 IN is bit 4
// IEP2 OUT is bit 5
// IEP3 IN is bit 6
// IEP3 OUT is bit 7
// etc
for(uint j = 0; j < 2; j++)
{
bit = 1 << (i*2+j);
if (remaining_buffers & bit)
{
remaining_buffers &= ~bit;
_handle_buff_status_bit(bit, &ep_pool[i]);
}
}
}
if (remaining_buffers)
{
panic("Unhandled buffer %d\n", remaining_buffers);
}
if ( remaining_buffers )
{
panic("Unhandled buffer %d\n", remaining_buffers);
}
}
static void __tusb_irq_path_func(hw_trans_complete)(void)
@@ -186,70 +187,72 @@ static void __tusb_irq_path_func(hw_trans_complete)(void)
static void __tusb_irq_path_func(hcd_rp2040_irq)(void)
{
uint32_t status = usb_hw->ints;
uint32_t handled = 0;
uint32_t status = usb_hw->ints;
uint32_t handled = 0;
if (status & USB_INTS_HOST_CONN_DIS_BITS)
if ( status & USB_INTS_HOST_CONN_DIS_BITS )
{
handled |= USB_INTS_HOST_CONN_DIS_BITS;
if ( dev_speed() )
{
handled |= USB_INTS_HOST_CONN_DIS_BITS;
if (dev_speed())
{
hcd_event_device_attach(RHPORT_NATIVE, true);
}
else
{
hcd_event_device_remove(RHPORT_NATIVE, true);
}
// Clear speed change interrupt
usb_hw_clear->sie_status = USB_SIE_STATUS_SPEED_BITS;
hcd_event_device_attach(RHPORT_NATIVE, true);
}
else
{
hcd_event_device_remove(RHPORT_NATIVE, true);
}
if (status & USB_INTS_STALL_BITS)
{
// We have rx'd a stall from the device
// NOTE THIS SHOULD HAVE PRIORITY OVER BUFF_STATUS
// AND TRANS_COMPLETE as the stall is an alternative response
// to one of those events
pico_trace("Stall REC\n");
handled |= USB_INTS_STALL_BITS;
usb_hw_clear->sie_status = USB_SIE_STATUS_STALL_REC_BITS;
hw_xfer_complete(&epx, XFER_RESULT_STALLED);
}
// Clear speed change interrupt
usb_hw_clear->sie_status = USB_SIE_STATUS_SPEED_BITS;
}
if (status & USB_INTS_BUFF_STATUS_BITS)
{
handled |= USB_INTS_BUFF_STATUS_BITS;
TU_LOG(2, "Buffer complete\n");
hw_handle_buff_status();
}
if ( status & USB_INTS_STALL_BITS )
{
// We have rx'd a stall from the device
// NOTE THIS SHOULD HAVE PRIORITY OVER BUFF_STATUS
// AND TRANS_COMPLETE as the stall is an alternative response
// to one of those events
pico_trace("Stall REC\n");
handled |= USB_INTS_STALL_BITS;
usb_hw_clear->sie_status = USB_SIE_STATUS_STALL_REC_BITS;
hw_xfer_complete(&epx, XFER_RESULT_STALLED);
}
if (status & USB_INTS_TRANS_COMPLETE_BITS)
{
handled |= USB_INTS_TRANS_COMPLETE_BITS;
usb_hw_clear->sie_status = USB_SIE_STATUS_TRANS_COMPLETE_BITS;
TU_LOG(2, "Transfer complete\n");
hw_trans_complete();
}
if ( status & USB_INTS_BUFF_STATUS_BITS )
{
handled |= USB_INTS_BUFF_STATUS_BITS;
TU_LOG(2, "Buffer complete\n");
hw_handle_buff_status();
}
if (status & USB_INTS_ERROR_RX_TIMEOUT_BITS)
{
handled |= USB_INTS_ERROR_RX_TIMEOUT_BITS;
usb_hw_clear->sie_status = USB_SIE_STATUS_RX_TIMEOUT_BITS;
}
if ( status & USB_INTS_TRANS_COMPLETE_BITS )
{
handled |= USB_INTS_TRANS_COMPLETE_BITS;
usb_hw_clear->sie_status = USB_SIE_STATUS_TRANS_COMPLETE_BITS;
TU_LOG(2, "Transfer complete\n");
hw_trans_complete();
}
if (status & USB_INTS_ERROR_DATA_SEQ_BITS)
{
usb_hw_clear->sie_status = USB_SIE_STATUS_DATA_SEQ_ERROR_BITS;
TU_LOG(3, " Seq Error: [0] = 0x%04u [1] = 0x%04x\r\n", tu_u32_low16(*epx.buffer_control), tu_u32_high16(*epx.buffer_control));
panic("Data Seq Error \n");
}
if ( status & USB_INTS_ERROR_RX_TIMEOUT_BITS )
{
handled |= USB_INTS_ERROR_RX_TIMEOUT_BITS;
usb_hw_clear->sie_status = USB_SIE_STATUS_RX_TIMEOUT_BITS;
}
if (status ^ handled)
{
panic("Unhandled IRQ 0x%x\n", (uint) (status ^ handled));
}
if ( status & USB_INTS_ERROR_DATA_SEQ_BITS )
{
usb_hw_clear->sie_status = USB_SIE_STATUS_DATA_SEQ_ERROR_BITS;
TU_LOG(3, " Seq Error: [0] = 0x%04u [1] = 0x%04x\r\n",
tu_u32_low16(*epx.buffer_control),
tu_u32_high16(*epx.buffer_control));
panic("Data Seq Error \n");
}
if ( status ^ handled )
{
panic("Unhandled IRQ 0x%x\n", (uint) (status ^ handled));
}
}
void __tusb_irq_path_func(hcd_int_handler)(uint8_t rhport)
@@ -260,116 +263,118 @@ void __tusb_irq_path_func(hcd_int_handler)(uint8_t rhport)
static struct hw_endpoint *_next_free_interrupt_ep(void)
{
struct hw_endpoint *ep = NULL;
for (uint i = 1; i < TU_ARRAY_SIZE(ep_pool); i++)
struct hw_endpoint * ep = NULL;
for ( uint i = 1; i < TU_ARRAY_SIZE(ep_pool); i++ )
{
ep = &ep_pool[i];
if ( !ep->configured )
{
ep = &ep_pool[i];
if (!ep->configured)
{
// Will be configured by _hw_endpoint_init / _hw_endpoint_allocate
ep->interrupt_num = (uint8_t) (i - 1);
return ep;
}
// Will be configured by _hw_endpoint_init / _hw_endpoint_allocate
ep->interrupt_num = (uint8_t) (i - 1);
return ep;
}
return ep;
}
return ep;
}
static struct hw_endpoint *_hw_endpoint_allocate(uint8_t transfer_type)
{
struct hw_endpoint *ep = NULL;
struct hw_endpoint * ep = NULL;
if (transfer_type != TUSB_XFER_CONTROL)
{
// Note: even though datasheet name these "Interrupt" endpoints. These are actually
// "Asynchronous" endpoints and can be used for other type such as: Bulk (ISO need confirmation)
ep = _next_free_interrupt_ep();
pico_info("Allocate %s ep %d\n", tu_edpt_type_str(transfer_type), ep->interrupt_num);
assert(ep);
ep->buffer_control = &usbh_dpram->int_ep_buffer_ctrl[ep->interrupt_num].ctrl;
ep->endpoint_control = &usbh_dpram->int_ep_ctrl[ep->interrupt_num].ctrl;
// 0 for epx (double buffered): TODO increase to 1024 for ISO
// 2x64 for intep0
// 3x64 for intep1
// etc
ep->hw_data_buf = &usbh_dpram->epx_data[64 * (ep->interrupt_num + 2)];
}
else
{
ep = &epx;
ep->buffer_control = &usbh_dpram->epx_buf_ctrl;
ep->endpoint_control = &usbh_dpram->epx_ctrl;
ep->hw_data_buf = &usbh_dpram->epx_data[0];
}
if ( transfer_type != TUSB_XFER_CONTROL )
{
// Note: even though datasheet name these "Interrupt" endpoints. These are actually
// "Asynchronous" endpoints and can be used for other type such as: Bulk (ISO need confirmation)
ep = _next_free_interrupt_ep();
pico_info("Allocate %s ep %d\n", tu_edpt_type_str(transfer_type), ep->interrupt_num);
assert(ep);
ep->buffer_control = &usbh_dpram->int_ep_buffer_ctrl[ep->interrupt_num].ctrl;
ep->endpoint_control = &usbh_dpram->int_ep_ctrl[ep->interrupt_num].ctrl;
// 0 for epx (double buffered): TODO increase to 1024 for ISO
// 2x64 for intep0
// 3x64 for intep1
// etc
ep->hw_data_buf = &usbh_dpram->epx_data[64 * (ep->interrupt_num + 2)];
}
else
{
ep = &epx;
ep->buffer_control = &usbh_dpram->epx_buf_ctrl;
ep->endpoint_control = &usbh_dpram->epx_ctrl;
ep->hw_data_buf = &usbh_dpram->epx_data[0];
}
return ep;
return ep;
}
static void _hw_endpoint_init(struct hw_endpoint *ep, uint8_t dev_addr, uint8_t ep_addr, uint16_t wMaxPacketSize, uint8_t transfer_type, uint8_t bmInterval)
{
// Already has data buffer, endpoint control, and buffer control allocated at this point
assert(ep->endpoint_control);
assert(ep->buffer_control);
assert(ep->hw_data_buf);
// Already has data buffer, endpoint control, and buffer control allocated at this point
assert(ep->endpoint_control);
assert(ep->buffer_control);
assert(ep->hw_data_buf);
uint8_t const num = tu_edpt_number(ep_addr);
tusb_dir_t const dir = tu_edpt_dir(ep_addr);
uint8_t const num = tu_edpt_number(ep_addr);
tusb_dir_t const dir = tu_edpt_dir(ep_addr);
ep->ep_addr = ep_addr;
ep->dev_addr = dev_addr;
ep->ep_addr = ep_addr;
ep->dev_addr = dev_addr;
// For host, IN to host == RX, anything else rx == false
ep->rx = (dir == TUSB_DIR_IN);
// For host, IN to host == RX, anything else rx == false
ep->rx = (dir == TUSB_DIR_IN);
// Response to a setup packet on EP0 starts with pid of 1
ep->next_pid = (num == 0 ? 1u : 0u);
ep->wMaxPacketSize = wMaxPacketSize;
ep->transfer_type = transfer_type;
// Response to a setup packet on EP0 starts with pid of 1
ep->next_pid = (num == 0 ? 1u : 0u);
ep->wMaxPacketSize = wMaxPacketSize;
ep->transfer_type = transfer_type;
pico_trace("hw_endpoint_init dev %d ep %d %s xfer %d\n", ep->dev_addr, tu_edpt_number(ep->ep_addr), ep_dir_string[tu_edpt_dir(ep->ep_addr)], ep->transfer_type);
pico_trace("dev %d ep %d %s setup buffer @ 0x%p\n", ep->dev_addr, tu_edpt_number(ep->ep_addr), ep_dir_string[tu_edpt_dir(ep->ep_addr)], ep->hw_data_buf);
uint dpram_offset = hw_data_offset(ep->hw_data_buf);
// Bits 0-5 should be 0
assert(!(dpram_offset & 0b111111));
pico_trace("hw_endpoint_init dev %d ep %d %s xfer %d\n", ep->dev_addr, tu_edpt_number(ep->ep_addr),
ep_dir_string[tu_edpt_dir(ep->ep_addr)], ep->transfer_type);
pico_trace("dev %d ep %d %s setup buffer @ 0x%p\n", ep->dev_addr, tu_edpt_number(ep->ep_addr),
ep_dir_string[tu_edpt_dir(ep->ep_addr)], ep->hw_data_buf);
uint dpram_offset = hw_data_offset(ep->hw_data_buf);
// Bits 0-5 should be 0
assert(!(dpram_offset & 0b111111));
// Fill in endpoint control register with buffer offset
uint32_t ep_reg = EP_CTRL_ENABLE_BITS
| EP_CTRL_INTERRUPT_PER_BUFFER
| (ep->transfer_type << EP_CTRL_BUFFER_TYPE_LSB)
| dpram_offset;
if (bmInterval)
// Fill in endpoint control register with buffer offset
uint32_t ep_reg = EP_CTRL_ENABLE_BITS
| EP_CTRL_INTERRUPT_PER_BUFFER
| (ep->transfer_type << EP_CTRL_BUFFER_TYPE_LSB)
| dpram_offset;
if ( bmInterval )
{
ep_reg |= (uint32_t) ((bmInterval - 1) << EP_CTRL_HOST_INTERRUPT_INTERVAL_LSB);
}
*ep->endpoint_control = ep_reg;
pico_trace("endpoint control (0x%p) <- 0x%x\n", ep->endpoint_control, ep_reg);
ep->configured = true;
if ( ep != &epx )
{
// Endpoint has its own addr_endp and interrupt bits to be setup!
// This is an interrupt/async endpoint. so need to set up ADDR_ENDP register with:
// - device address
// - endpoint number / direction
// - preamble
uint32_t reg = (uint32_t) (dev_addr | (num << USB_ADDR_ENDP1_ENDPOINT_LSB));
if ( dir == TUSB_DIR_OUT )
{
ep_reg |= (uint32_t) ((bmInterval - 1) << EP_CTRL_HOST_INTERRUPT_INTERVAL_LSB);
reg |= USB_ADDR_ENDP1_INTEP_DIR_BITS;
}
*ep->endpoint_control = ep_reg;
pico_trace("endpoint control (0x%p) <- 0x%x\n", ep->endpoint_control, ep_reg);
ep->configured = true;
if (ep != &epx)
if ( need_pre(dev_addr) )
{
// Endpoint has its own addr_endp and interrupt bits to be setup!
// This is an interrupt/async endpoint. so need to set up ADDR_ENDP register with:
// - device address
// - endpoint number / direction
// - preamble
uint32_t reg = (uint32_t) (dev_addr | (num << USB_ADDR_ENDP1_ENDPOINT_LSB));
if (dir == TUSB_DIR_OUT)
{
reg |= USB_ADDR_ENDP1_INTEP_DIR_BITS;
}
if (need_pre(dev_addr))
{
reg |= USB_ADDR_ENDP1_INTEP_PREAMBLE_BITS;
}
usb_hw->int_ep_addr_ctrl[ep->interrupt_num] = reg;
// Finally, enable interrupt that endpoint
usb_hw_set->int_ep_ctrl = 1 << (ep->interrupt_num + 1);
// If it's an interrupt endpoint we need to set up the buffer control
// register
reg |= USB_ADDR_ENDP1_INTEP_PREAMBLE_BITS;
}
usb_hw->int_ep_addr_ctrl[ep->interrupt_num] = reg;
// Finally, enable interrupt that endpoint
usb_hw_set->int_ep_ctrl = 1 << (ep->interrupt_num + 1);
// If it's an interrupt endpoint we need to set up the buffer control
// register
}
}
//--------------------------------------------------------------------+
@@ -434,16 +439,17 @@ tusb_speed_t hcd_port_speed_get(uint8_t rhport)
{
(void) rhport;
assert(rhport == 0);
// TODO: Should enumval this register
switch (dev_speed())
switch ( dev_speed() )
{
case 1:
return TUSB_SPEED_LOW;
case 2:
return TUSB_SPEED_FULL;
default:
panic("Invalid speed\n");
return TUSB_SPEED_INVALID;
case 1:
return TUSB_SPEED_LOW;
case 2:
return TUSB_SPEED_FULL;
default:
panic("Invalid speed\n");
return TUSB_SPEED_INVALID;
}
}
@@ -476,8 +482,8 @@ void hcd_device_close(uint8_t rhport, uint8_t dev_addr)
uint32_t hcd_frame_number(uint8_t rhport)
{
(void) rhport;
return usb_hw->sof_rd;
(void) rhport;
return usb_hw->sof_rd;
}
void hcd_int_enable(uint8_t rhport)
@@ -501,117 +507,116 @@ void hcd_int_disable(uint8_t rhport)
bool hcd_edpt_open(uint8_t rhport, uint8_t dev_addr, tusb_desc_endpoint_t const * ep_desc)
{
(void) rhport;
(void) rhport;
pico_trace("hcd_edpt_open dev_addr %d, ep_addr %d\n", dev_addr, ep_desc->bEndpointAddress);
pico_trace("hcd_edpt_open dev_addr %d, ep_addr %d\n", dev_addr, ep_desc->bEndpointAddress);
// Allocated differently based on if it's an interrupt endpoint or not
struct hw_endpoint *ep = _hw_endpoint_allocate(ep_desc->bmAttributes.xfer);
TU_ASSERT(ep);
// Allocated differently based on if it's an interrupt endpoint or not
struct hw_endpoint *ep = _hw_endpoint_allocate(ep_desc->bmAttributes.xfer);
TU_ASSERT(ep);
_hw_endpoint_init(ep,
dev_addr,
ep_desc->bEndpointAddress,
tu_edpt_packet_size(ep_desc),
ep_desc->bmAttributes.xfer,
ep_desc->bInterval);
_hw_endpoint_init(ep,
dev_addr,
ep_desc->bEndpointAddress,
tu_edpt_packet_size(ep_desc),
ep_desc->bmAttributes.xfer,
ep_desc->bInterval);
return true;
return true;
}
bool hcd_edpt_xfer(uint8_t rhport, uint8_t dev_addr, uint8_t ep_addr, uint8_t * buffer, uint16_t buflen)
{
(void) rhport;
(void) rhport;
pico_trace("hcd_edpt_xfer dev_addr %d, ep_addr 0x%x, len %d\n", dev_addr, ep_addr, buflen);
uint8_t const ep_num = tu_edpt_number(ep_addr);
tusb_dir_t const ep_dir = tu_edpt_dir(ep_addr);
pico_trace("hcd_edpt_xfer dev_addr %d, ep_addr 0x%x, len %d\n", dev_addr, ep_addr, buflen);
// Get appropriate ep. Either EPX or interrupt endpoint
struct hw_endpoint *ep = get_dev_ep(dev_addr, ep_addr);
uint8_t const ep_num = tu_edpt_number(ep_addr);
tusb_dir_t const ep_dir = tu_edpt_dir(ep_addr);
TU_ASSERT(ep);
// Get appropriate ep. Either EPX or interrupt endpoint
struct hw_endpoint *ep = get_dev_ep(dev_addr, ep_addr);
// EP should be inactive
assert(!ep->active);
TU_ASSERT(ep);
// Control endpoint can change direction 0x00 <-> 0x80
if ( ep_addr != ep->ep_addr )
{
assert(ep_num == 0);
// EP should be inactive
assert(!ep->active);
// Direction has flipped on endpoint control so re init it but with same properties
_hw_endpoint_init(ep, dev_addr, ep_addr, ep->wMaxPacketSize, ep->transfer_type, 0);
}
// Control endpoint can change direction 0x00 <-> 0x80
if ( ep_addr != ep->ep_addr )
{
assert(ep_num == 0);
// If a normal transfer (non-interrupt) then initiate using
// sie ctrl registers. Otherwise interrupt ep registers should
// already be configured
if (ep == &epx) {
hw_endpoint_xfer_start(ep, buffer, buflen);
// Direction has flipped on endpoint control so re init it but with same properties
_hw_endpoint_init(ep, dev_addr, ep_addr, ep->wMaxPacketSize, ep->transfer_type, 0);
}
// That has set up buffer control, endpoint control etc
// for host we have to initiate the transfer
usb_hw->dev_addr_ctrl = (uint32_t) (dev_addr | (ep_num << USB_ADDR_ENDP_ENDPOINT_LSB));
// If a normal transfer (non-interrupt) then initiate using
// sie ctrl registers. Otherwise interrupt ep registers should
// already be configured
if ( ep == &epx )
{
hw_endpoint_xfer_start(ep, buffer, buflen);
uint32_t flags = USB_SIE_CTRL_START_TRANS_BITS | SIE_CTRL_BASE |
(ep_dir ? USB_SIE_CTRL_RECEIVE_DATA_BITS : USB_SIE_CTRL_SEND_DATA_BITS);
// Set pre if we are a low speed device on full speed hub
flags |= need_pre(dev_addr) ? USB_SIE_CTRL_PREAMBLE_EN_BITS : 0;
// That has set up buffer control, endpoint control etc
// for host we have to initiate the transfer
usb_hw->dev_addr_ctrl = (uint32_t) (dev_addr | (ep_num << USB_ADDR_ENDP_ENDPOINT_LSB));
usb_hw->sie_ctrl = flags;
}else
{
hw_endpoint_xfer_start(ep, buffer, buflen);
}
uint32_t flags = USB_SIE_CTRL_START_TRANS_BITS | SIE_CTRL_BASE |
(ep_dir ? USB_SIE_CTRL_RECEIVE_DATA_BITS : USB_SIE_CTRL_SEND_DATA_BITS) |
(need_pre(dev_addr) ? USB_SIE_CTRL_PREAMBLE_EN_BITS : 0);
usb_hw->sie_ctrl = flags;
}else
{
hw_endpoint_xfer_start(ep, buffer, buflen);
}
return true;
return true;
}
bool hcd_setup_send(uint8_t rhport, uint8_t dev_addr, uint8_t const setup_packet[8])
{
(void) rhport;
(void) rhport;
// Copy data into setup packet buffer
for(uint8_t i=0; i<8; i++)
{
usbh_dpram->setup_packet[i] = setup_packet[i];
}
// Copy data into setup packet buffer
for ( uint8_t i = 0; i < 8; i++ )
{
usbh_dpram->setup_packet[i] = setup_packet[i];
}
// Configure EP0 struct with setup info for the trans complete
struct hw_endpoint *ep = _hw_endpoint_allocate(0);
TU_ASSERT(ep);
// Configure EP0 struct with setup info for the trans complete
struct hw_endpoint * ep = _hw_endpoint_allocate(0);
TU_ASSERT(ep);
// EPX should be inactive
assert(!ep->active);
// EPX should be inactive
assert(!ep->active);
// EP0 out
_hw_endpoint_init(ep, dev_addr, 0x00, ep->wMaxPacketSize, 0, 0);
assert(ep->configured);
// EP0 out
_hw_endpoint_init(ep, dev_addr, 0x00, ep->wMaxPacketSize, 0, 0);
assert(ep->configured);
ep->remaining_len = 8;
ep->active = true;
ep->remaining_len = 8;
ep->active = true;
// Set device address
usb_hw->dev_addr_ctrl = dev_addr;
// Set device address
usb_hw->dev_addr_ctrl = dev_addr;
// Set pre if we are a low speed device on full speed hub
uint32_t const flags = SIE_CTRL_BASE | USB_SIE_CTRL_SEND_SETUP_BITS | USB_SIE_CTRL_START_TRANS_BITS |
(need_pre(dev_addr) ? USB_SIE_CTRL_PREAMBLE_EN_BITS : 0);
// Set pre if we are a low speed device on full speed hub
uint32_t const flags = SIE_CTRL_BASE | USB_SIE_CTRL_SEND_SETUP_BITS | USB_SIE_CTRL_START_TRANS_BITS |
(need_pre(dev_addr) ? USB_SIE_CTRL_PREAMBLE_EN_BITS : 0);
usb_hw->sie_ctrl = flags;
usb_hw->sie_ctrl = flags;
return true;
return true;
}
bool hcd_edpt_clear_stall(uint8_t dev_addr, uint8_t ep_addr)
{
(void) dev_addr;
(void) ep_addr;
(void) dev_addr;
(void) ep_addr;
panic("hcd_clear_stall");
return true;
panic("hcd_clear_stall");
return true;
}
#endif

View File

@@ -47,6 +47,12 @@ TU_ATTR_ALWAYS_INLINE static inline void _hw_endpoint_lock_update(__unused struc
static void _hw_endpoint_xfer_sync(struct hw_endpoint *ep);
static void _hw_endpoint_start_next_buffer(struct hw_endpoint *ep);
// if usb hardware is in host mode
TU_ATTR_ALWAYS_INLINE static inline bool is_host_mode(void)
{
return (usb_hw->main_ctrl & USB_MAIN_CTRL_HOST_NDEVICE_BITS) ? true : false;
}
//--------------------------------------------------------------------+
//
//--------------------------------------------------------------------+
@@ -69,6 +75,8 @@ void rp2040_usb_init(void)
// Mux the controller to the onboard usb phy
usb_hw->muxing = USB_USB_MUXING_TO_PHY_BITS | USB_USB_MUXING_SOFTCON_BITS;
TU_LOG2_INT(sizeof(hw_endpoint_t));
}
void __tusb_irq_path_func(hw_endpoint_reset_transfer)(struct hw_endpoint *ep)
@@ -80,19 +88,23 @@ void __tusb_irq_path_func(hw_endpoint_reset_transfer)(struct hw_endpoint *ep)
}
void __tusb_irq_path_func(_hw_endpoint_buffer_control_update32)(struct hw_endpoint *ep, uint32_t and_mask, uint32_t or_mask) {
uint32_t value = 0;
if (and_mask) {
value = *ep->buffer_control & and_mask;
}
if (or_mask) {
value |= or_mask;
if (or_mask & USB_BUF_CTRL_AVAIL) {
if (*ep->buffer_control & USB_BUF_CTRL_AVAIL) {
panic("ep %d %s was already available", tu_edpt_number(ep->ep_addr), ep_dir_string[tu_edpt_dir(ep->ep_addr)]);
}
*ep->buffer_control = value & ~USB_BUF_CTRL_AVAIL;
// 12 cycle delay.. (should be good for 48*12Mhz = 576Mhz)
// Don't need delay in host mode as host is in charge
uint32_t value = 0;
if ( and_mask )
{
value = *ep->buffer_control & and_mask;
}
if ( or_mask )
{
value |= or_mask;
if ( or_mask & USB_BUF_CTRL_AVAIL )
{
if ( *ep->buffer_control & USB_BUF_CTRL_AVAIL )
{
panic("ep %d %s was already available", tu_edpt_number(ep->ep_addr), ep_dir_string[tu_edpt_dir(ep->ep_addr)]);
}
*ep->buffer_control = value & ~USB_BUF_CTRL_AVAIL;
// 12 cycle delay.. (should be good for 48*12Mhz = 576Mhz)
// Don't need delay in host mode as host is in charge
#if !CFG_TUH_ENABLED
__asm volatile (
"b 1f\n"
@@ -104,9 +116,9 @@ void __tusb_irq_path_func(_hw_endpoint_buffer_control_update32)(struct hw_endpoi
"1:\n"
: : : "memory");
#endif
}
}
*ep->buffer_control = value;
}
*ep->buffer_control = value;
}
// prepare buffer, return buffer control
@@ -152,10 +164,14 @@ static void __tusb_irq_path_func(_hw_endpoint_start_next_buffer)(struct hw_endpo
// always compute and start with buffer 0
uint32_t buf_ctrl = prepare_ep_buffer(ep, 0) | USB_BUF_CTRL_SEL;
// For now: skip double buffered for Device mode, OUT endpoint since
// For now: skip double buffered for OUT endpoint in Device mode, since
// host could send < 64 bytes and cause short packet on buffer0
// NOTE this could happen to Host mode IN endpoint
bool const force_single = !(usb_hw->main_ctrl & USB_MAIN_CTRL_HOST_NDEVICE_BITS) && !tu_edpt_dir(ep->ep_addr);
// NOTE: this could happen to Host mode IN endpoint
// Also, Host mode "interrupt" endpoint hardware is only single buffered,
// NOTE2: Currently Host bulk is implemented using "interrupt" endpoint
bool const is_host = is_host_mode();
bool const force_single = (!is_host && !tu_edpt_dir(ep->ep_addr)) ||
(is_host && tu_edpt_number(ep->ep_addr) != 0);
if(ep->remaining_len && !force_single)
{

View File

@@ -82,26 +82,30 @@ void hw_endpoint_reset_transfer(struct hw_endpoint *ep);
void _hw_endpoint_buffer_control_update32(struct hw_endpoint *ep, uint32_t and_mask, uint32_t or_mask);
TU_ATTR_ALWAYS_INLINE static inline uint32_t _hw_endpoint_buffer_control_get_value32(struct hw_endpoint *ep) {
return *ep->buffer_control;
}
TU_ATTR_ALWAYS_INLINE static inline void _hw_endpoint_buffer_control_set_value32(struct hw_endpoint *ep, uint32_t value) {
return _hw_endpoint_buffer_control_update32(ep, 0, value);
}
TU_ATTR_ALWAYS_INLINE static inline void _hw_endpoint_buffer_control_set_mask32(struct hw_endpoint *ep, uint32_t value) {
return _hw_endpoint_buffer_control_update32(ep, ~value, value);
}
TU_ATTR_ALWAYS_INLINE static inline void _hw_endpoint_buffer_control_clear_mask32(struct hw_endpoint *ep, uint32_t value) {
return _hw_endpoint_buffer_control_update32(ep, ~value, 0);
}
static inline uintptr_t hw_data_offset(uint8_t *buf)
TU_ATTR_ALWAYS_INLINE static inline uint32_t _hw_endpoint_buffer_control_get_value32 (struct hw_endpoint *ep)
{
// Remove usb base from buffer pointer
return (uintptr_t)buf ^ (uintptr_t)usb_dpram;
return *ep->buffer_control;
}
TU_ATTR_ALWAYS_INLINE static inline void _hw_endpoint_buffer_control_set_value32 (struct hw_endpoint *ep, uint32_t value)
{
return _hw_endpoint_buffer_control_update32(ep, 0, value);
}
TU_ATTR_ALWAYS_INLINE static inline void _hw_endpoint_buffer_control_set_mask32 (struct hw_endpoint *ep, uint32_t value)
{
return _hw_endpoint_buffer_control_update32(ep, ~value, value);
}
TU_ATTR_ALWAYS_INLINE static inline void _hw_endpoint_buffer_control_clear_mask32 (struct hw_endpoint *ep, uint32_t value)
{
return _hw_endpoint_buffer_control_update32(ep, ~value, 0);
}
static inline uintptr_t hw_data_offset (uint8_t *buf)
{
// Remove usb base from buffer pointer
return (uintptr_t) buf ^ (uintptr_t) usb_dpram;
}
extern const char *ep_dir_string[];

View File

@@ -600,7 +600,7 @@ uint32_t hcd_frame_number(uint8_t rhport)
bool hcd_port_connect_status(uint8_t rhport)
{
(void)rhport;
return USB0.INTSTS1.BIT.ATTCH ? true: false;
return USB0.INTSTS1.BIT.ATTCH ? true : false;
}
void hcd_port_reset(uint8_t rhport)

View File

@@ -108,12 +108,20 @@
#define STM32F1_FSDEV
#endif
#if defined(STM32L412xx) || defined(STM32L422xx) || \
defined(STM32L432xx) || defined(STM32L433xx) || \
defined(STM32L442xx) || defined(STM32L443xx) || \
defined(STM32L452xx) || defined(STM32L462xx)
#define STM32L4_FSDEV
#endif
#if CFG_TUD_ENABLED && \
( TU_CHECK_MCU(OPT_MCU_STM32F0, OPT_MCU_STM32F3, OPT_MCU_STM32L0, OPT_MCU_STM32L1, OPT_MCU_STM32G4, OPT_MCU_STM32WB) || \
(TU_CHECK_MCU(OPT_MCU_STM32F1) && defined(STM32F1_FSDEV)) \
(TU_CHECK_MCU(OPT_MCU_STM32F1) && defined(STM32F1_FSDEV)) || \
(TU_CHECK_MCU(OPT_MCU_STM32L4) && defined(STM32L4_FSDEV)) \
)
// In order to reduce the dependance on HAL, we undefine this.
// In order to reduce the dependence on HAL, we undefine this.
// Some definitions are copied to our private include file.
#undef USE_HAL_DRIVER
@@ -306,7 +314,8 @@ void dcd_int_enable (uint8_t rhport)
// Member here forces write to RAM before allowing ISR to execute
__DSB();
__ISB();
#if CFG_TUSB_MCU == OPT_MCU_STM32F0 || CFG_TUSB_MCU == OPT_MCU_STM32L0
#if CFG_TUSB_MCU == OPT_MCU_STM32F0 || CFG_TUSB_MCU == OPT_MCU_STM32L0 || \
CFG_TUSB_MCU == OPT_MCU_STM32L4
NVIC_EnableIRQ(USB_IRQn);
#elif CFG_TUSB_MCU == OPT_MCU_STM32L1
@@ -354,7 +363,8 @@ void dcd_int_disable(uint8_t rhport)
{
(void)rhport;
#if CFG_TUSB_MCU == OPT_MCU_STM32F0 || CFG_TUSB_MCU == OPT_MCU_STM32L0
#if CFG_TUSB_MCU == OPT_MCU_STM32F0 || CFG_TUSB_MCU == OPT_MCU_STM32L0 || \
CFG_TUSB_MCU == OPT_MCU_STM32L4
NVIC_DisableIRQ(USB_IRQn);
#elif CFG_TUSB_MCU == OPT_MCU_STM32L1
NVIC_DisableIRQ(USB_LP_IRQn);

View File

@@ -100,6 +100,10 @@
#undef USB_PMAADDR
#define USB_PMAADDR USB1_PMAADDR
#elif CFG_TUSB_MCU == OPT_MCU_STM32L4
#include "stm32l4xx.h"
#define PMA_LENGTH (1024u)
#else
#error You are using an untested or unimplemented STM32 variant. Please update the driver.
// This includes L1x0, L1x1, L1x2, L4x2 and L4x3, G1x1, G1x3, and G1x4

View File

@@ -243,7 +243,7 @@ static void USBC_Dev_SetAddress(u8 address)
static void __USBC_Dev_Tx_SendStall(void)
{
//send stall, and fifo is flushed automaticly
//send stall, and fifo is flushed automatically
USBC_REG_set_bit_w(USBC_BP_TXCSR_D_SEND_STALL, USBC_REG_TXCSR(USBC0_BASE));
}
static u32 __USBC_Dev_Tx_IsEpStall(void)

View File

@@ -93,7 +93,7 @@
#define USBC1_BASE 0x01c14000
#define USBC2_BASE 0x01c1E000
//Some reg whithin musb
//Some reg within musb
#define USBPHY_CLK_REG 0x01c200CC
#define USBPHY_CLK_RST_BIT 0
#define USBPHY_CLK_GAT_BIT 1

View File

@@ -1003,7 +1003,7 @@ static void handle_rxflvl_irq(uint8_t rhport)
switch ( pktsts )
{
// Global OUT NAK: do nothign
// Global OUT NAK: do nothing
case GRXSTS_PKTSTS_GLOBALOUTNAK: break;
case GRXSTS_PKTSTS_SETUPRX:

View File

@@ -116,7 +116,7 @@ static const dwc2_controller_t _dwc2_controller[] =
//
//--------------------------------------------------------------------+
// SystemCoreClock is alrady included by family header
// SystemCoreClock is already included by family header
// extern uint32_t SystemCoreClock;
TU_ATTR_ALWAYS_INLINE

View File

@@ -465,7 +465,7 @@ void dcd_edpt_clear_stall(uint8_t rhport, uint8_t ep_addr)
enable = 1;
usb_out_ctrl_write((0 << CSR_USB_OUT_CTRL_STALL_OFFSET) | (enable << CSR_USB_OUT_CTRL_ENABLE_OFFSET) | tu_edpt_number(ep_addr));
}
// IN endpoints will get unstalled when more data is written.
// IN endpoints will get un-stalled when more data is written.
}
bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, uint16_t total_bytes)