Merge branch 'master' into warning

This commit is contained in:
Ha Thach
2024-11-14 10:25:52 +07:00
committed by GitHub
190 changed files with 4948 additions and 1907 deletions

View File

@@ -2066,8 +2066,8 @@ static bool audiod_set_interface(uint8_t rhport, tusb_control_request_t const *
// Avoid 64bit division
uint32_t nominal = ((fb_param.sample_freq / 100) << 16) / (frame_div / 100);
audio->feedback.compute.fifo_count.nom_value = nominal;
audio->feedback.compute.fifo_count.rate_const[0] = (audio->feedback.max_value - nominal) / fifo_lvl_thr;
audio->feedback.compute.fifo_count.rate_const[1] = (nominal - audio->feedback.min_value) / fifo_lvl_thr;
audio->feedback.compute.fifo_count.rate_const[0] = (uint16_t) ((audio->feedback.max_value - nominal) / fifo_lvl_thr);
audio->feedback.compute.fifo_count.rate_const[1] = (uint16_t) ((nominal - audio->feedback.min_value) / fifo_lvl_thr);
// On HS feedback is more sensitive since packet size can vary every MSOF, could cause instability
if(tud_speed_get() == TUSB_SPEED_HIGH) {
audio->feedback.compute.fifo_count.rate_const[0] /= 8;
@@ -2376,11 +2376,11 @@ static bool audiod_set_fb_params_freq(audiod_function_t* audio, uint32_t sample_
if ((mclk_freq % sample_freq) == 0 && tu_is_power_of_two(mclk_freq / sample_freq))
{
audio->feedback.compute_method = AUDIO_FEEDBACK_METHOD_FREQUENCY_POWER_OF_2;
audio->feedback.compute.power_of_2 = 16 - (audio->feedback.frame_shift - 1) - tu_log2(mclk_freq / sample_freq);
audio->feedback.compute.power_of_2 = (uint8_t) (16 - (audio->feedback.frame_shift - 1) - tu_log2(mclk_freq / sample_freq));
}
else if ( audio->feedback.compute_method == AUDIO_FEEDBACK_METHOD_FREQUENCY_FLOAT)
{
audio->feedback.compute.float_const = (float)sample_freq / mclk_freq * (1UL << (16 - (audio->feedback.frame_shift - 1)));
audio->feedback.compute.float_const = (float)sample_freq / (float) mclk_freq * (1UL << (16 - (audio->feedback.frame_shift - 1)));
}
else
{

View File

@@ -204,6 +204,9 @@ TU_ATTR_WEAK void tud_cdc_line_state_cb(uint8_t itf, bool dtr, bool rts);
TU_ATTR_WEAK void tud_cdc_line_coding_cb(uint8_t itf, cdc_line_coding_t const* p_line_coding);
// Invoked when received send break
// \param[in] itf interface for which send break was received.
// \param[in] duration_ms the length of time, in milliseconds, of the break signal. If a value of FFFFh, then the
// device will send a break until another SendBreak request is received with value 0000h.
TU_ATTR_WEAK void tud_cdc_send_break_cb(uint8_t itf, uint16_t duration_ms);
//--------------------------------------------------------------------+

View File

@@ -110,8 +110,12 @@ typedef struct {
NOTIFICATION_SPEED,
NOTIFICATION_CONNECTED,
NOTIFICATION_DONE
} notification_xmit_state; // state of notification transmission
bool notification_xmit_is_running; // notification is currently transmitted
} notification_xmit_state; // state of notification transmission
bool notification_xmit_is_running; // notification is currently transmitted
// misc
bool tud_network_recv_renew_active; // tud_network_recv_renew() is active (avoid recursive invocations)
bool tud_network_recv_renew_process_again; // tud_network_recv_renew() should process again
} ncm_interface_t;
CFG_TUD_MEM_SECTION CFG_TUD_MEM_ALIGN tu_static ncm_interface_t ncm_interface;
@@ -689,11 +693,29 @@ void tud_network_xmit(void *ref, uint16_t arg) {
/**
* Keep the receive logic busy and transfer pending packets to the glue logic.
* Avoid recursive calls due to wrong expectations of the net glue logic,
* see https://github.com/hathach/tinyusb/issues/2711
*/
void tud_network_recv_renew(void) {
TU_LOG_DRV("tud_network_recv_renew()\n");
recv_transfer_datagram_to_glue_logic();
ncm_interface.tud_network_recv_renew_process_again = true;
if (ncm_interface.tud_network_recv_renew_active) {
TU_LOG_DRV("Re-entrant into tud_network_recv_renew, will process later\n");
return;
}
while (ncm_interface.tud_network_recv_renew_process_again) {
ncm_interface.tud_network_recv_renew_process_again = false;
// If the current function is called within recv_transfer_datagram_to_glue_logic,
// tud_network_recv_renew_process_again will become true, and the loop will run again
// Otherwise the loop will not run again
ncm_interface.tud_network_recv_renew_active = true;
recv_transfer_datagram_to_glue_logic();
ncm_interface.tud_network_recv_renew_active = false;
}
recv_try_to_start_new_reception(ncm_interface.rhport);
} // tud_network_recv_renew

View File

@@ -123,11 +123,15 @@ TU_ATTR_ALWAYS_INLINE static inline int tu_memcpy_s(void *dest, size_t destsz, c
//------------- Bytes -------------//
TU_ATTR_ALWAYS_INLINE static inline uint32_t tu_u32(uint8_t b3, uint8_t b2, uint8_t b1, uint8_t b0) {
return ( ((uint32_t) b3) << 24) | ( ((uint32_t) b2) << 16) | ( ((uint32_t) b1) << 8) | b0;
return (((uint32_t)b3) << 24) | (((uint32_t)b2) << 16) | (((uint32_t)b1) << 8) | b0;
}
TU_ATTR_ALWAYS_INLINE static inline uint32_t tu_u32_from_u16(uint16_t high, uint16_t low) {
return (((uint32_t)high) << 16) | low;
}
TU_ATTR_ALWAYS_INLINE static inline uint16_t tu_u16(uint8_t high, uint8_t low) {
return (uint16_t) ((((uint16_t) high) << 8) | low);
return (uint16_t)((((uint16_t)high) << 8) | low);
}
TU_ATTR_ALWAYS_INLINE static inline uint8_t tu_u32_byte3(uint32_t ui32) { return TU_U32_BYTE3(ui32); }

View File

@@ -169,6 +169,7 @@
defined (STM32F107xB) || defined (STM32F107xC)
#define TUP_USBIP_DWC2
#define TUP_USBIP_DWC2_STM32
#define CFG_TUH_DWC2_DMA_ENABLE_DEFAULT 0
#define TUP_DCD_ENDPOINT_MAX 4
#elif defined(STM32F102x6) || defined(STM32F102xB) || \
@@ -343,12 +344,14 @@
#define TUP_USBIP_DWC2
#define TUP_USBIP_DWC2_ESP32
#define TUP_DCD_ENDPOINT_MAX 7 // only 5 TX FIFO for endpoint IN
#define CFG_TUH_DWC2_DMA_ENABLE_DEFAULT 0 // TODO currently have issue with buffer DMA with espressif
#elif TU_CHECK_MCU(OPT_MCU_ESP32P4)
#define TUP_USBIP_DWC2
#define TUP_USBIP_DWC2_ESP32
#define TUP_RHPORT_HIGHSPEED 1 // port0 FS, port1 HS
#define TUP_DCD_ENDPOINT_MAX 16 // FS 7 ep, HS 16 ep
#define CFG_TUH_DWC2_DMA_ENABLE_DEFAULT 0 // TODO currently have issue with buffer DMA with espressif
#elif TU_CHECK_MCU(OPT_MCU_ESP32, OPT_MCU_ESP32C2, OPT_MCU_ESP32C3, OPT_MCU_ESP32C6, OPT_MCU_ESP32H2)
#if (CFG_TUD_ENABLED || !(defined(CFG_TUH_MAX3421) && CFG_TUH_MAX3421))

View File

@@ -24,9 +24,8 @@
* This file is part of the TinyUSB stack.
*/
#ifndef _TUSB_PRIVATE_H_
#define _TUSB_PRIVATE_H_
#ifndef TUSB_PRIVATE_H_
#define TUSB_PRIVATE_H_
// Internal Helper used by Host and Device Stack
@@ -34,6 +33,13 @@
extern "C" {
#endif
#define TUP_USBIP_CONTROLLER_NUM 2
extern tusb_role_t _tusb_rhport_role[TUP_USBIP_CONTROLLER_NUM];
//--------------------------------------------------------------------+
// Endpoint
//--------------------------------------------------------------------+
typedef struct TU_ATTR_PACKED {
volatile uint8_t busy : 1;
volatile uint8_t stalled : 1;
@@ -163,4 +169,4 @@ bool tu_edpt_stream_peek(tu_edpt_stream_t* s, uint8_t* ch) {
}
#endif
#endif /* _TUSB_PRIVATE_H_ */
#endif

View File

@@ -41,8 +41,8 @@
typedef enum {
TUSB_ROLE_INVALID = 0,
TUSB_ROLE_DEVICE,
TUSB_ROLE_HOST,
TUSB_ROLE_DEVICE = 0x1,
TUSB_ROLE_HOST = 0x2,
} tusb_role_t;
/// defined base on EHCI specs value for Endpoint Speed
@@ -56,10 +56,10 @@ typedef enum {
/// defined base on USB Specs Endpoint's bmAttributes
typedef enum {
TUSB_XFER_CONTROL = 0 ,
TUSB_XFER_ISOCHRONOUS ,
TUSB_XFER_BULK ,
TUSB_XFER_INTERRUPT
TUSB_XFER_CONTROL = 0,
TUSB_XFER_ISOCHRONOUS = 1,
TUSB_XFER_BULK = 2,
TUSB_XFER_INTERRUPT = 3
} tusb_xfer_type_t;
typedef enum {
@@ -224,10 +224,10 @@ enum {
// USB 2.0 Spec Table 9-7: Test Mode Selectors
typedef enum {
TUSB_FEATURE_TEST_J = 1,
TUSB_FEATURE_TEST_K,
TUSB_FEATURE_TEST_SE0_NAK,
TUSB_FEATURE_TEST_PACKET,
TUSB_FEATURE_TEST_FORCE_ENABLE,
TUSB_FEATURE_TEST_K = 2,
TUSB_FEATURE_TEST_SE0_NAK = 3,
TUSB_FEATURE_TEST_PACKET = 4,
TUSB_FEATURE_TEST_FORCE_ENABLE = 5,
} tusb_feature_test_mode_t;
//--------------------------------------------------------------------+
@@ -264,7 +264,7 @@ typedef enum {
} microsoft_os_20_type_t;
enum {
CONTROL_STAGE_IDLE,
CONTROL_STAGE_IDLE = 0,
CONTROL_STAGE_SETUP,
CONTROL_STAGE_DATA,
CONTROL_STAGE_ACK

View File

@@ -83,7 +83,7 @@
if ( (*ARM_CM_DHCSR) & 1UL ) __asm("BKPT #0\n"); /* Only halt mcu if debugger is attached */ \
} while(0)
#elif defined(__riscv) && !TUP_MCU_ESPRESSIF
#elif defined(__riscv) && !TUSB_MCU_VENDOR_ESPRESSIF
#define TU_BREAKPOINT() do { __asm("ebreak\n"); } while(0)
#elif defined(_mips)

View File

@@ -278,15 +278,6 @@ static void process_removing_device(uint8_t rhport, uint8_t hub_addr, uint8_t hu
static bool usbh_edpt_control_open(uint8_t dev_addr, uint8_t max_packet_size);
static bool usbh_control_xfer_cb (uint8_t daddr, uint8_t ep_addr, xfer_result_t result, uint32_t xferred_bytes);
#if CFG_TUSB_OS == OPT_OS_NONE
// TODO rework time-related function later
// weak and overridable
TU_ATTR_WEAK void osal_task_delay(uint32_t msec) {
const uint32_t start = hcd_frame_number(_usbh_controller);
while ( ( hcd_frame_number(_usbh_controller) - start ) < msec ) {}
}
#endif
TU_ATTR_ALWAYS_INLINE static inline bool queue_event(hcd_event_t const * event, bool in_isr) {
TU_ASSERT(osal_queue_send(_usbh_q, event, in_isr));
tuh_event_hook_cb(event->rhport, event->event_id, in_isr);
@@ -447,9 +438,9 @@ bool tuh_deinit(uint8_t rhport) {
}
bool tuh_task_event_ready(void) {
// Skip if stack is not initialized
if ( !tuh_inited() ) return false;
if (!tuh_inited()) {
return false; // Skip if stack is not initialized
}
return !osal_queue_empty(_usbh_q);
}
@@ -487,17 +478,27 @@ void tuh_task_ext(uint32_t timeout_ms, bool in_isr) {
// due to the shared _usbh_ctrl_buf, we must complete enumerating one device before enumerating another one.
// TODO better to have an separated queue for newly attached devices
if (_dev0.enumerating) {
TU_LOG_USBH("[%u:] USBH Defer Attach until current enumeration complete\r\n", event.rhport);
// Some device can cause multiple duplicated attach events
// drop current enumerating and start over for a proper port reset
if (event.rhport == _dev0.rhport && event.connection.hub_addr == _dev0.hub_addr &&
event.connection.hub_port == _dev0.hub_port) {
// abort/cancel current enumeration and start new one
TU_LOG1("[%u:] USBH Device Attach (duplicated)\r\n", event.rhport);
tuh_edpt_abort_xfer(0, 0);
enum_new_device(&event);
} else {
TU_LOG_USBH("[%u:] USBH Defer Attach until current enumeration complete\r\n", event.rhport);
bool is_empty = osal_queue_empty(_usbh_q);
queue_event(&event, in_isr);
bool is_empty = osal_queue_empty(_usbh_q);
queue_event(&event, in_isr);
if (is_empty) {
// Exit if this is the only event in the queue, otherwise we may loop forever
return;
if (is_empty) {
// Exit if this is the only event in the queue, otherwise we may loop forever
return;
}
}
} else {
TU_LOG_USBH("[%u:] USBH DEVICE ATTACH\r\n", event.rhport);
TU_LOG1("[%u:] USBH Device Attach\r\n", event.rhport);
_dev0.enumerating = 1;
enum_new_device(&event);
}
@@ -603,12 +604,12 @@ bool tuh_control_xfer (tuh_xfer_t* xfer) {
TU_VERIFY(xfer->ep_addr == 0 && xfer->setup);
// Check if device is still connected (enumerating for dev0)
uint8_t const daddr = xfer->daddr;
if ( daddr == 0 ) {
if (!_dev0.enumerating) return false;
const uint8_t daddr = xfer->daddr;
if (daddr == 0) {
TU_VERIFY(_dev0.enumerating);
} else {
usbh_device_t const* dev = get_device(daddr);
if (dev && dev->connected == 0) return false;
const usbh_device_t* dev = get_device(daddr);
TU_VERIFY(dev && dev->connected);
}
// pre-check to help reducing mutex lock
@@ -778,24 +779,26 @@ bool tuh_edpt_xfer(tuh_xfer_t* xfer) {
}
bool tuh_edpt_abort_xfer(uint8_t daddr, uint8_t ep_addr) {
usbh_device_t* dev = get_device(daddr);
TU_VERIFY(dev);
TU_LOG_USBH("[%u] Aborted transfer on EP %02X\r\n", daddr, ep_addr);
uint8_t const epnum = tu_edpt_number(ep_addr);
uint8_t const dir = tu_edpt_dir(ep_addr);
const uint8_t epnum = tu_edpt_number(ep_addr);
const uint8_t dir = tu_edpt_dir(ep_addr);
if (epnum == 0) {
// Also include dev0 for aborting enumerating
const uint8_t rhport = usbh_get_rhport(daddr);
if ( epnum == 0 ) {
// control transfer: only 1 control at a time, check if we are aborting the current one
TU_VERIFY(daddr == _ctrl_xfer.daddr && _ctrl_xfer.stage != CONTROL_STAGE_IDLE);
TU_VERIFY(hcd_edpt_abort_xfer(dev->rhport, daddr, ep_addr));
// reset control transfer state to idle
_set_control_xfer_stage(CONTROL_STAGE_IDLE);
hcd_edpt_abort_xfer(rhport, daddr, ep_addr);
_set_control_xfer_stage(CONTROL_STAGE_IDLE); // reset control transfer state to idle
} else {
// non-control skip if not busy
TU_VERIFY(dev->ep_status[epnum][dir].busy);
TU_VERIFY(hcd_edpt_abort_xfer(dev->rhport, daddr, ep_addr));
usbh_device_t* dev = get_device(daddr);
TU_VERIFY(dev);
TU_VERIFY(dev->ep_status[epnum][dir].busy); // non-control skip if not busy
hcd_edpt_abort_xfer(dev->rhport, daddr, ep_addr);
// mark as ready and release endpoint if transfer is aborted
dev->ep_status[epnum][dir].busy = false;
tu_edpt_release(&dev->ep_status[epnum][dir], _usbh_mutex);
@@ -1281,9 +1284,9 @@ static void process_removing_device(uint8_t rhport, uint8_t hub_addr, uint8_t hu
//--------------------------------------------------------------------+
enum {
ENUM_RESET_DELAY = 50, // USB specs: 10 to 50ms
ENUM_CONTACT_DEBOUNCING_DELAY = 450, // when plug/unplug a device, physical connection can be bouncing and may
// generate a series of attach/detach event. This delay wait for stable connection
ENUM_RESET_DELAY_MS = 50, // USB specs: 10 to 50ms
ENUM_DEBOUNCING_DELAY_MS = 450, // when plug/unplug a device, physical connection can be bouncing and may
// generate a series of attach/detach event. This delay wait for stable connection
};
enum {
@@ -1322,7 +1325,7 @@ static void process_enumeration(tuh_xfer_t* xfer) {
bool retry = _dev0.enumerating && (failed_count < ATTEMPT_COUNT_MAX);
if ( retry ) {
failed_count++;
osal_task_delay(ATTEMPT_DELAY_MS); // delay a bit
tusb_time_delay_ms_api(ATTEMPT_DELAY_MS); // delay a bit
TU_LOG1("Enumeration attempt %u\r\n", failed_count);
retry = tuh_control_xfer(xfer);
}
@@ -1364,7 +1367,7 @@ static void process_enumeration(tuh_xfer_t* xfer) {
}
case ENUM_HUB_GET_STATUS_2:
osal_task_delay(ENUM_RESET_DELAY);
tusb_time_delay_ms_api(ENUM_RESET_DELAY_MS);
TU_ASSERT(hub_port_get_status(_dev0.hub_addr, _dev0.hub_port, _usbh_ctrl_buf,
process_enumeration, ENUM_HUB_CLEAR_RESET_2),);
break;
@@ -1402,7 +1405,7 @@ static void process_enumeration(tuh_xfer_t* xfer) {
if (_dev0.hub_addr == 0) {
// connected directly to roothub
hcd_port_reset( _dev0.rhport );
osal_task_delay(RESET_DELAY); // TODO may not work for no-OS on MCU that require reset_end() since
tusb_time_delay_ms_api(RESET_DELAY); // TODO may not work for no-OS on MCU that require reset_end() since
// sof of controller may not running while resetting
hcd_port_reset_end(_dev0.rhport);
// TODO: fall through to SET ADDRESS, refactor later
@@ -1424,9 +1427,9 @@ static void process_enumeration(tuh_xfer_t* xfer) {
case ENUM_GET_DEVICE_DESC: {
// Allow 2ms for address recovery time, Ref USB Spec 9.2.6.3
osal_task_delay(2);
tusb_time_delay_ms_api(2);
uint8_t const new_addr = (uint8_t) tu_le16toh(xfer->setup->wValue);
const uint8_t new_addr = (uint8_t) tu_le16toh(xfer->setup->wValue);
usbh_device_t* new_dev = get_device(new_addr);
TU_ASSERT(new_dev,);
@@ -1514,20 +1517,25 @@ static void process_enumeration(tuh_xfer_t* xfer) {
}
}
static bool enum_new_device(hcd_event_t* event) {
_dev0.rhport = event->rhport;
_dev0.hub_addr = event->connection.hub_addr;
_dev0.hub_port = event->connection.hub_port;
if (_dev0.hub_addr == 0) {
// connected/disconnected directly with roothub
// connected directly to roothub
hcd_port_reset(_dev0.rhport);
osal_task_delay(ENUM_RESET_DELAY); // TODO may not work for no-OS on MCU that require reset_end() since
// sof of controller may not running while resetting
// Since we are in middle of rhport reset, frame number is not available yet.
// need to depend on tusb_time_millis_api()
tusb_time_delay_ms_api(ENUM_RESET_DELAY_MS);
hcd_port_reset_end(_dev0.rhport);
// wait until device connection is stable TODO non blocking
osal_task_delay(ENUM_CONTACT_DEBOUNCING_DELAY);
tusb_time_delay_ms_api(ENUM_DEBOUNCING_DELAY_MS);
// device unplugged while delaying
if (!hcd_port_connect_status(_dev0.rhport)) {
@@ -1548,12 +1556,11 @@ static bool enum_new_device(hcd_event_t* event) {
}
#if CFG_TUH_HUB
else {
// connected/disconnected via external hub
// connected via external hub
// wait until device connection is stable TODO non blocking
osal_task_delay(ENUM_CONTACT_DEBOUNCING_DELAY);
tusb_time_delay_ms_api(ENUM_DEBOUNCING_DELAY_MS);
// ENUM_HUB_GET_STATUS
//TU_ASSERT( hub_port_get_status(_dev0.hub_addr, _dev0.hub_port, _usbh_ctrl_buf, enum_hub_get_status0_complete, 0) );
TU_ASSERT(hub_port_get_status(_dev0.hub_addr, _dev0.hub_port, _usbh_ctrl_buf,
process_enumeration, ENUM_HUB_CLEAR_RESET_1));
}

View File

@@ -35,45 +35,7 @@
#define DWC2_DEBUG 2
#include "device/dcd.h"
#include "dwc2_type.h"
// Following symbols must be defined by port header
// - _dwc2_controller[]: array of controllers
// - DWC2_EP_MAX: largest EP counts of all controllers
// - dwc2_phy_init/dwc2_phy_update: phy init called before and after core reset
// - dwc2_dcd_int_enable/dwc2_dcd_int_disable
// - dwc2_remote_wakeup_delay
#if defined(TUP_USBIP_DWC2_STM32)
#include "dwc2_stm32.h"
#elif defined(TUP_USBIP_DWC2_ESP32)
#include "dwc2_esp32.h"
#elif TU_CHECK_MCU(OPT_MCU_GD32VF103)
#include "dwc2_gd32.h"
#elif TU_CHECK_MCU(OPT_MCU_BCM2711, OPT_MCU_BCM2835, OPT_MCU_BCM2837)
#include "dwc2_bcm.h"
#elif TU_CHECK_MCU(OPT_MCU_EFM32GG)
#include "dwc2_efm32.h"
#elif TU_CHECK_MCU(OPT_MCU_XMC4000)
#include "dwc2_xmc.h"
#else
#error "Unsupported MCUs"
#endif
enum {
DWC2_CONTROLLER_COUNT = TU_ARRAY_SIZE(_dwc2_controller)
};
// DWC2 registers
//#define DWC2_REG(_port) ((dwc2_regs_t*) _dwc2_controller[_port].reg_base)
TU_ATTR_ALWAYS_INLINE static inline dwc2_regs_t* DWC2_REG(uint8_t rhport) {
if (rhport >= DWC2_CONTROLLER_COUNT) {
// user mis-configured, ignore and use first controller
rhport = 0;
}
return (dwc2_regs_t*) _dwc2_controller[rhport].reg_base;
}
#include "dwc2_common.h"
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM
@@ -94,7 +56,7 @@ static xfer_ctl_t xfer_status[DWC2_EP_MAX][2];
// EP0 transfers are limited to 1 packet - larger sizes has to be split
static uint16_t ep0_pending[2]; // Index determines direction as tusb_dir_t type
static uint16_t _dfifo_top; // top free location in FIFO RAM
static uint16_t _dfifo_top; // top free location in DFIFO in words
// Number of IN endpoints active
static uint8_t _allocated_ep_in_count;
@@ -106,20 +68,10 @@ static bool _sof_en;
// DMA
//--------------------------------------------------------------------
TU_ATTR_ALWAYS_INLINE static inline bool dma_enabled(const dwc2_regs_t* dwc2) {
#if !CFG_TUD_DWC2_DMA
TU_ATTR_ALWAYS_INLINE static inline bool dma_device_enabled(const dwc2_regs_t* dwc2) {
(void) dwc2;
return false;
#else
// Internal DMA only
return (dwc2->ghwcfg2_bm.arch == GHWCFG2_ARCH_INTERNAL_DMA);
#endif
}
TU_ATTR_ALWAYS_INLINE static inline uint16_t dma_cal_epfifo_base(uint8_t rhport) {
// Scatter/Gather DMA mode is not yet supported. Buffer DMA only need 1 words per endpoint direction
const dwc2_controller_t* dwc2_controller = &_dwc2_controller[rhport];
return dwc2_controller->ep_fifo_size/4 - 2*dwc2_controller->ep_count;
return CFG_TUD_DWC2_DMA && dwc2->ghwcfg2_bm.arch == GHWCFG2_ARCH_INTERNAL_DMA;
}
static void dma_setup_prepare(uint8_t rhport) {
@@ -141,18 +93,8 @@ static void dma_setup_prepare(uint8_t rhport) {
// Data FIFO
//--------------------------------------------------------------------+
TU_ATTR_ALWAYS_INLINE static inline void dfifo_flush_tx(dwc2_regs_t* dwc2, uint8_t epnum) {
// flush TX fifo and wait for it cleared
dwc2->grstctl = GRSTCTL_TXFFLSH | (epnum << GRSTCTL_TXFNUM_Pos);
while (dwc2->grstctl & GRSTCTL_TXFFLSH_Msk) {}
}
TU_ATTR_ALWAYS_INLINE static inline void dfifo_flush_rx(dwc2_regs_t* dwc2) {
// flush RX fifo and wait for it cleared
dwc2->grstctl = GRSTCTL_RXFFLSH;
while (dwc2->grstctl & GRSTCTL_RXFFLSH_Msk) {}
}
/* USB Data FIFO Layout
/* Device Data FIFO scheme
The FIFO is split up into
- EPInfo: for storing DMA metadata, only required when use DMA. Maximum size is called
@@ -167,11 +109,9 @@ TU_ATTR_ALWAYS_INLINE static inline void dfifo_flush_rx(dwc2_regs_t* dwc2) {
possible since the free space is located between the RX and TX FIFOs.
---------------- ep_fifo_size
| EPInfo |
| for DMA |
| DxEPIDMAn |
|-------------|-- gdfifocfg.EPINFOBASE (max is ghwcfg3.dfifo_depth)
| IN FIFO 0 |
| control |
| IN FIFO 0 | control EP
|-------------|
| IN FIFO 1 |
|-------------|
@@ -190,13 +130,13 @@ TU_ATTR_ALWAYS_INLINE static inline void dfifo_flush_rx(dwc2_regs_t* dwc2) {
- All EP OUT shared a unique OUT FIFO which uses (for Slave or Buffer DMA, Scatt/Gather DMA use different formula):
- 13 for setup packets + control words (up to 3 setup packets).
- 1 for global NAK (not required/used here).
- Largest-EPsize / 4 + 1. ( FS: 64 bytes, HS: 512 bytes). Recommended is "2 x (Largest-EPsize/4) + 1"
- Largest-EPsize/4 + 1. ( FS: 64 bytes, HS: 512 bytes). Recommended is "2 x (Largest-EPsize/4 + 1)"
- 2 for each used OUT endpoint
Therefore GRXFSIZ = 13 + 1 + 2 x (Largest-EPsize/4 + 1) + 2 x EPOUTnum
*/
TU_ATTR_ALWAYS_INLINE static inline uint16_t calc_grxfsiz(uint16_t largest_ep_size, uint8_t ep_count) {
TU_ATTR_ALWAYS_INLINE static inline uint16_t calc_device_grxfsiz(uint16_t largest_ep_size, uint8_t ep_count) {
return 13 + 1 + 2 * ((largest_ep_size / 4) + 1) + 2 * ep_count;
}
@@ -212,7 +152,7 @@ static bool dfifo_alloc(uint8_t rhport, uint8_t ep_addr, uint16_t packet_size) {
uint16_t fifo_size = tu_div_ceil(packet_size, 4);
if (dir == TUSB_DIR_OUT) {
// Calculate required size of RX FIFO
uint16_t const new_sz = calc_grxfsiz(4 * fifo_size, ep_count);
uint16_t const new_sz = calc_device_grxfsiz(4 * fifo_size, ep_count);
// If size_rx needs to be extended check if there is enough free space
if (dwc2->grxfsiz < new_sz) {
@@ -227,7 +167,7 @@ static bool dfifo_alloc(uint8_t rhport, uint8_t ep_addr, uint16_t packet_size) {
}
// If The TXFELVL is configured as half empty, the fifo must be twice the max_size.
if ((dwc2->gahbcfg & GAHBCFG_TXFELVL) == 0) {
if ((dwc2->gahbcfg & GAHBCFG_TX_FIFO_EPMTY_LVL) == 0) {
fifo_size *= 2;
}
@@ -248,75 +188,27 @@ static bool dfifo_alloc(uint8_t rhport, uint8_t ep_addr, uint16_t packet_size) {
return true;
}
static void dfifo_init(uint8_t rhport) {
static void dfifo_device_init(uint8_t rhport) {
const dwc2_controller_t* dwc2_controller = &_dwc2_controller[rhport];
dwc2_regs_t* dwc2 = DWC2_REG(rhport);
dwc2->grxfsiz = calc_grxfsiz(CFG_TUD_ENDPOINT0_SIZE, dwc2_controller->ep_count);
dwc2->grxfsiz = calc_device_grxfsiz(CFG_TUD_ENDPOINT0_SIZE, dwc2_controller->ep_count);
if(dma_enabled(dwc2)) {
// DMA use last DFIFO to store metadata
_dfifo_top = dma_cal_epfifo_base(rhport);
}else {
_dfifo_top = dwc2_controller->ep_fifo_size / 4;
// Scatter/Gather DMA mode is not yet supported. Buffer DMA only need 1 words per endpoint direction
const bool is_dma = dma_device_enabled(dwc2);
_dfifo_top = dwc2_controller->ep_fifo_size/4;
if (is_dma) {
_dfifo_top -= 2 * dwc2_controller->ep_count;
}
dwc2->gdfifocfg = (_dfifo_top << GDFIFOCFG_EPINFOBASE_SHIFT) | _dfifo_top;
// Allocate FIFO for EP0 IN
dfifo_alloc(rhport, 0x80, CFG_TUD_ENDPOINT0_SIZE);
}
// Read a single data packet from receive FIFO
static void dfifo_read_packet(uint8_t rhport, uint8_t* dst, uint16_t len) {
(void) rhport;
dwc2_regs_t* dwc2 = DWC2_REG(rhport);
volatile const uint32_t* rx_fifo = dwc2->fifo[0];
// Reading full available 32 bit words from fifo
uint16_t full_words = len >> 2;
while (full_words--) {
tu_unaligned_write32(dst, *rx_fifo);
dst += 4;
}
// Read the remaining 1-3 bytes from fifo
uint8_t const bytes_rem = len & 0x03;
if (bytes_rem != 0) {
uint32_t const tmp = *rx_fifo;
dst[0] = tu_u32_byte0(tmp);
if (bytes_rem > 1) dst[1] = tu_u32_byte1(tmp);
if (bytes_rem > 2) dst[2] = tu_u32_byte2(tmp);
}
}
// Write a single data packet to EPIN FIFO
static void dfifo_write_packet(uint8_t rhport, uint8_t fifo_num, uint8_t const* src, uint16_t len) {
(void) rhport;
dwc2_regs_t* dwc2 = DWC2_REG(rhport);
volatile uint32_t* tx_fifo = dwc2->fifo[fifo_num];
// Pushing full available 32 bit words to fifo
uint16_t full_words = len >> 2;
while (full_words--) {
*tx_fifo = tu_unaligned_read32(src);
src += 4;
}
// Write the remaining 1-3 bytes into fifo
uint8_t const bytes_rem = len & 0x03;
if (bytes_rem) {
uint32_t tmp_word = src[0];
if (bytes_rem > 1) tmp_word |= (src[1] << 8);
if (bytes_rem > 2) tmp_word |= (src[2] << 16);
*tx_fifo = tmp_word;
}
}
//--------------------------------------------------------------------
// Endpoint
//--------------------------------------------------------------------
static void edpt_activate(uint8_t rhport, tusb_desc_endpoint_t const * p_endpoint_desc) {
dwc2_regs_t* dwc2 = DWC2_REG(rhport);
uint8_t const epnum = tu_edpt_number(p_endpoint_desc->bEndpointAddress);
@@ -421,7 +313,7 @@ static void bus_reset(uint8_t rhport) {
dwc2->diepmsk = DIEPMSK_TOM | DIEPMSK_XFRCM;
// 4. Set up DFIFO
dfifo_init(rhport);
dfifo_device_init(rhport);
// 5. Reset device address
dwc2->dcfg &= ~DCFG_DAD_Msk;
@@ -433,7 +325,7 @@ static void bus_reset(uint8_t rhport) {
xfer_status[0][TUSB_DIR_OUT].max_size = 64;
xfer_status[0][TUSB_DIR_IN].max_size = 64;
if(dma_enabled(dwc2)) {
if(dma_device_enabled(dwc2)) {
dma_setup_prepare(rhport);
} else {
dwc2->epout[0].doeptsiz |= (3 << DOEPTSIZ_STUPCNT_Pos);
@@ -463,9 +355,9 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c
if (dir == TUSB_DIR_IN) {
// A full IN transfer (multiple packets, possibly) triggers XFRC.
dep->dieptsiz = (num_packets << DIEPTSIZ_PKTCNT_Pos) |
((total_bytes << DIEPTSIZ_XFRSIZ_Pos) & DIEPTSIZ_XFRSIZ_Msk);
((total_bytes << DIEPTSIZ_XFRSIZ_Pos) & DIEPTSIZ_XFRSIZ_Msk);
if(dma_enabled(dwc2)) {
if(dma_device_enabled(dwc2)) {
dep->diepdma = (uintptr_t)xfer->buffer;
// For ISO endpoint set correct odd/even bit for next frame.
@@ -503,7 +395,7 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c
dep->doepctl |= (odd_frame_now ? DOEPCTL_SD0PID_SEVNFRM_Msk : DOEPCTL_SODDFRM_Msk);
}
if(dma_enabled(dwc2)) {
if(dma_device_enabled(dwc2)) {
dep->doepdma = (uintptr_t)xfer->buffer;
}
@@ -511,174 +403,41 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c
}
}
/*------------------------------------------------------------------*/
/* Controller API
*------------------------------------------------------------------*/
static void reset_core(dwc2_regs_t* dwc2) {
// reset core
dwc2->grstctl |= GRSTCTL_CSRST;
// wait for reset bit is cleared
// TODO version 4.20a should wait for RESET DONE mask
while (dwc2->grstctl & GRSTCTL_CSRST) {}
// wait for AHB master IDLE
while (!(dwc2->grstctl & GRSTCTL_AHBIDL)) {}
// wait for device mode ?
}
static bool phy_hs_supported(dwc2_regs_t* dwc2) {
(void) dwc2;
#if !TUD_OPT_HIGH_SPEED
return false;
#else
return dwc2->ghwcfg2_bm.hs_phy_type != GHWCFG2_HSPHY_NOT_SUPPORTED;
#endif
}
static void phy_fs_init(dwc2_regs_t* dwc2) {
TU_LOG(DWC2_DEBUG, "Fullspeed PHY init\r\n");
// Select FS PHY
dwc2->gusbcfg |= GUSBCFG_PHYSEL;
// MCU specific PHY init before reset
dwc2_phy_init(dwc2, GHWCFG2_HSPHY_NOT_SUPPORTED);
// Reset core after selecting PHY
reset_core(dwc2);
// USB turnaround time is critical for certification where long cables and 5-Hubs are used.
// So if you need the AHB to run at less than 30 MHz, and if USB turnaround time is not critical,
// these bits can be programmed to a larger value. Default is 5
dwc2->gusbcfg = (dwc2->gusbcfg & ~GUSBCFG_TRDT_Msk) | (5u << GUSBCFG_TRDT_Pos);
// MCU specific PHY update post reset
dwc2_phy_update(dwc2, GHWCFG2_HSPHY_NOT_SUPPORTED);
// set max speed
dwc2->dcfg = (dwc2->dcfg & ~DCFG_DSPD_Msk) | (DCFG_DSPD_FS << DCFG_DSPD_Pos);
}
static void phy_hs_init(dwc2_regs_t* dwc2) {
uint32_t gusbcfg = dwc2->gusbcfg;
// De-select FS PHY
gusbcfg &= ~GUSBCFG_PHYSEL;
if (dwc2->ghwcfg2_bm.hs_phy_type == GHWCFG2_HSPHY_ULPI) {
TU_LOG(DWC2_DEBUG, "Highspeed ULPI PHY init\r\n");
// Select ULPI
gusbcfg |= GUSBCFG_ULPI_UTMI_SEL;
// ULPI 8-bit interface, single data rate
gusbcfg &= ~(GUSBCFG_PHYIF16 | GUSBCFG_DDRSEL);
// default internal VBUS Indicator and Drive
gusbcfg &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI);
// Disable FS/LS ULPI
gusbcfg &= ~(GUSBCFG_ULPIFSLS | GUSBCFG_ULPICSM);
} else {
TU_LOG(DWC2_DEBUG, "Highspeed UTMI+ PHY init\r\n");
// Select UTMI+ with 8-bit interface
gusbcfg &= ~(GUSBCFG_ULPI_UTMI_SEL | GUSBCFG_PHYIF16);
// Set 16-bit interface if supported
if (dwc2->ghwcfg4_bm.phy_data_width) {
gusbcfg |= GUSBCFG_PHYIF16;
}
}
// Apply config
dwc2->gusbcfg = gusbcfg;
// mcu specific phy init
dwc2_phy_init(dwc2, dwc2->ghwcfg2_bm.hs_phy_type);
// Reset core after selecting PHY
reset_core(dwc2);
// Set turn-around, must after core reset otherwise it will be clear
// - 9 if using 8-bit PHY interface
// - 5 if using 16-bit PHY interface
gusbcfg &= ~GUSBCFG_TRDT_Msk;
gusbcfg |= (dwc2->ghwcfg4_bm.phy_data_width ? 5u : 9u) << GUSBCFG_TRDT_Pos;
dwc2->gusbcfg = gusbcfg;
// MCU specific PHY update post reset
dwc2_phy_update(dwc2, dwc2->ghwcfg2_bm.hs_phy_type);
// Set max speed
uint32_t dcfg = dwc2->dcfg;
dcfg &= ~DCFG_DSPD_Msk;
dcfg |= DCFG_DSPD_HS << DCFG_DSPD_Pos;
// XCVRDLY: transceiver delay between xcvr_sel and txvalid during device chirp is required
// when using with some PHYs such as USB334x (USB3341, USB3343, USB3346, USB3347)
if (dwc2->ghwcfg2_bm.hs_phy_type == GHWCFG2_HSPHY_ULPI) {
dcfg |= DCFG_XCVRDLY;
}
dwc2->dcfg = dcfg;
}
static bool check_dwc2(dwc2_regs_t* dwc2) {
#if CFG_TUSB_DEBUG >= DWC2_DEBUG
// print guid, gsnpsid, ghwcfg1, ghwcfg2, ghwcfg3, ghwcfg4
// Run 'python dwc2_info.py' and check dwc2_info.md for bit-field value and comparison with other ports
volatile uint32_t const* p = (volatile uint32_t const*) &dwc2->guid;
TU_LOG1("guid, gsnpsid, ghwcfg1, ghwcfg2, ghwcfg3, ghwcfg4\r\n");
for (size_t i = 0; i < 5; i++) {
TU_LOG1("0x%08" PRIX32 ", ", p[i]);
}
TU_LOG1("0x%08" PRIX32 "\r\n", p[5]);
#endif
// For some reason: GD32VF103 snpsid and all hwcfg register are always zero (skip it)
(void) dwc2;
#if !TU_CHECK_MCU(OPT_MCU_GD32VF103)
uint32_t const gsnpsid = dwc2->gsnpsid & GSNPSID_ID_MASK;
TU_ASSERT(gsnpsid == DWC2_OTG_ID || gsnpsid == DWC2_FS_IOT_ID || gsnpsid == DWC2_HS_IOT_ID);
#endif
return true;
}
//--------------------------------------------------------------------
// Controller API
//--------------------------------------------------------------------
bool dcd_init(uint8_t rhport, const tusb_rhport_init_t* rh_init) {
(void) rhport;
(void) rh_init;
// Programming model begins in the last section of the chapter on the USB
// peripheral in each Reference Manual.
dwc2_regs_t* dwc2 = DWC2_REG(rhport);
// Check Synopsys ID register, failed if controller clock/power is not enabled
TU_ASSERT(check_dwc2(dwc2));
dcd_disconnect(rhport);
// Core Initialization
const bool is_highspeed = dwc2_core_is_highspeed(dwc2, TUSB_ROLE_DEVICE);
TU_ASSERT(dwc2_core_init(rhport, is_highspeed));
if (phy_hs_supported(dwc2)) {
phy_hs_init(dwc2); // Highspeed
if (dma_device_enabled(dwc2)) {
// DMA seems to be only settable after a core reset, and not possible to switch on-the-fly
dwc2->gahbcfg |= GAHBCFG_DMAEN | GAHBCFG_HBSTLEN_2;
} else {
phy_fs_init(dwc2); // core does not support highspeed or hs phy is not present
dwc2->gintmsk |= GINTSTS_RXFLVL;
}
// Restart PHY clock
dwc2->pcgctl &= ~(PCGCTL_STOPPCLK | PCGCTL_GATEHCLK | PCGCTL_PWRCLMP | PCGCTL_RSTPDWNMODULE);
// Device Initialization
dcd_disconnect(rhport);
/* Set HS/FS Timeout Calibration to 7 (max available value).
* The number of PHY clocks that the application programs in
* this field is added to the high/full speed interpacket timeout
* duration in the core to account for any additional delays
* introduced by the PHY. This can be required, because the delay
* introduced by the PHY in generating the linestate condition
* can vary from one PHY to another.
*/
dwc2->gusbcfg |= (7ul << GUSBCFG_TOCAL_Pos);
// Set device max speed
uint32_t dcfg = dwc2->dcfg & ~DCFG_DSPD_Msk;
if (is_highspeed) {
dcfg |= DCFG_DSPD_HS << DCFG_DSPD_Pos;
// XCVRDLY: transceiver delay between xcvr_sel and txvalid during device chirp is required
// when using with some PHYs such as USB334x (USB3341, USB3343, USB3346, USB3347)
if (dwc2->ghwcfg2_bm.hs_phy_type == GHWCFG2_HSPHY_ULPI) {
dcfg |= DCFG_XCVRDLY;
}
}else {
dcfg |= DCFG_DSPD_FS << DCFG_DSPD_Pos;
}
dwc2->dcfg = dcfg;
// Force device mode
dwc2->gusbcfg = (dwc2->gusbcfg & ~GUSBCFG_FHMOD) | GUSBCFG_FDMOD;
@@ -686,48 +445,19 @@ bool dcd_init(uint8_t rhport, const tusb_rhport_init_t* rh_init) {
// Clear A override, force B Valid
dwc2->gotgctl = (dwc2->gotgctl & ~GOTGCTL_AVALOEN) | GOTGCTL_BVALOEN | GOTGCTL_BVALOVAL;
// If USB host misbehaves during status portion of control xfer
// (non zero-length packet), send STALL back and discard.
// If USB host misbehaves during status portion of control xfer (non zero-length packet), send STALL back and discard
dwc2->dcfg |= DCFG_NZLSOHSK;
dfifo_flush_tx(dwc2, 0x10); // all tx fifo
dfifo_flush_rx(dwc2);
// Enable required interrupts
dwc2->gintmsk |= GINTMSK_OTGINT | GINTMSK_USBSUSPM | GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_WUIM;
// Clear all interrupts
uint32_t int_mask = dwc2->gintsts;
dwc2->gintsts |= int_mask;
int_mask = dwc2->gotgint;
dwc2->gotgint |= int_mask;
// Required as part of core initialization.
dwc2->gintmsk = GINTMSK_OTGINT | GINTMSK_USBSUSPM | GINTMSK_USBRST | GINTMSK_ENUMDNEM | GINTMSK_WUIM;
// Configure TX FIFO empty level for interrupt. Default is complete empty
dwc2->gahbcfg |= GAHBCFG_TXFELVL;
if (dma_enabled(dwc2)) {
const uint16_t epinfo_base = dma_cal_epfifo_base(rhport);
dwc2->gdfifocfg = (epinfo_base << GDFIFOCFG_EPINFOBASE_SHIFT) | epinfo_base;
// DMA seems to be only settable after a core reset
dwc2->gahbcfg |= GAHBCFG_DMAEN | GAHBCFG_HBSTLEN_2;
}else {
dwc2->gintmsk |= GINTMSK_RXFLVLM;
}
// Enable global interrupt
dwc2->gahbcfg |= GAHBCFG_GINT;
// make sure we are in device mode
// TU_ASSERT(!(dwc2->gintsts & GINTSTS_CMOD), );
// TU_LOG_HEX(DWC2_DEBUG, dwc2->gotgctl);
// TU_LOG_HEX(DWC2_DEBUG, dwc2->gusbcfg);
// TU_LOG_HEX(DWC2_DEBUG, dwc2->dcfg);
// TU_LOG_HEX(DWC2_DEBUG, dwc2->gahbcfg);
// TX FIFO empty level for interrupt is complete empty
uint32_t gahbcfg = dwc2->gahbcfg;
gahbcfg |= GAHBCFG_TX_FIFO_EPMTY_LVL;
gahbcfg |= GAHBCFG_GINT; // Enable global interrupt
dwc2->gahbcfg = gahbcfg;
dcd_connect(rhport);
return true;
}
@@ -847,7 +577,7 @@ void dcd_edpt_close_all(uint8_t rhport) {
dfifo_flush_tx(dwc2, 0x10); // all tx fifo
dfifo_flush_rx(dwc2);
dfifo_init(rhport); // re-init dfifo
dfifo_device_init(rhport); // re-init dfifo
}
bool dcd_edpt_iso_alloc(uint8_t rhport, uint8_t ep_addr, uint16_t largest_packet_size) {
@@ -878,11 +608,10 @@ bool dcd_edpt_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, uint16_t to
// Schedule the first transaction for EP0 transfer
edpt_schedule_packets(rhport, epnum, dir, 1, ep0_pending[dir]);
} else {
uint16_t num_packets = (total_bytes / xfer->max_size);
uint16_t const short_packet_size = total_bytes % xfer->max_size;
// Zero-size packet is special case.
if ((short_packet_size > 0) || (total_bytes == 0)) num_packets++;
uint16_t num_packets = tu_div_ceil(total_bytes, xfer->max_size);
if (num_packets == 0) {
num_packets = 1; // zero length packet still count as 1
}
// Schedule packets to be sent within interrupt
edpt_schedule_packets(rhport, epnum, dir, num_packets, total_bytes);
@@ -926,8 +655,9 @@ void dcd_edpt_close(uint8_t rhport, uint8_t ep_addr) {
}
void dcd_edpt_stall(uint8_t rhport, uint8_t ep_addr) {
dwc2_regs_t* dwc2 = DWC2_REG(rhport);
edpt_disable(rhport, ep_addr, true);
if((tu_edpt_number(ep_addr) == 0) && dma_enabled(DWC2_REG(rhport))) {
if((tu_edpt_number(ep_addr) == 0) && dma_device_enabled(dwc2)) {
dma_setup_prepare(rhport);
}
}
@@ -950,16 +680,15 @@ void dcd_edpt_clear_stall(uint8_t rhport, uint8_t ep_addr) {
// Process shared receive FIFO, this interrupt is only used in Slave mode
static void handle_rxflvl_irq(uint8_t rhport) {
dwc2_regs_t* dwc2 = DWC2_REG(rhport);
volatile uint32_t const* rx_fifo = dwc2->fifo[0];
const volatile uint32_t* rx_fifo = dwc2->fifo[0];
// Pop control word off FIFO
uint32_t const grxstsp = dwc2->grxstsp;
uint8_t const pktsts = (grxstsp & GRXSTSP_PKTSTS_Msk) >> GRXSTSP_PKTSTS_Pos;
uint8_t const epnum = (grxstsp & GRXSTSP_EPNUM_Msk) >> GRXSTSP_EPNUM_Pos;
uint16_t const bcnt = (grxstsp & GRXSTSP_BCNT_Msk) >> GRXSTSP_BCNT_Pos;
const dwc2_grxstsp_t grxstsp_bm = dwc2->grxstsp_bm;
const uint8_t epnum = grxstsp_bm.ep_ch_num;
const uint16_t byte_count = grxstsp_bm.byte_count;
dwc2_epout_t* epout = &dwc2->epout[epnum];
switch (pktsts) {
switch (grxstsp_bm.packet_status) {
// Global OUT NAK: do nothing
case GRXSTS_PKTSTS_GLOBALOUTNAK:
break;
@@ -984,18 +713,18 @@ static void handle_rxflvl_irq(uint8_t rhport) {
// Read packet off RxFIFO
if (xfer->ff) {
// Ring buffer
tu_fifo_write_n_const_addr_full_words(xfer->ff, (const void*) (uintptr_t) rx_fifo, bcnt);
tu_fifo_write_n_const_addr_full_words(xfer->ff, (const void*) (uintptr_t) rx_fifo, byte_count);
} else {
// Linear buffer
dfifo_read_packet(rhport, xfer->buffer, bcnt);
dfifo_read_packet(dwc2, xfer->buffer, byte_count);
// Increment pointer to xfer data
xfer->buffer += bcnt;
xfer->buffer += byte_count;
}
// Truncate transfer length in case of short packet
if (bcnt < xfer->max_size) {
xfer->total_len -= (epout->doeptsiz & DOEPTSIZ_XFRSIZ_Msk) >> DOEPTSIZ_XFRSIZ_Pos;
// short packet, minus remaining bytes (xfer_size)
if (byte_count < xfer->max_size) {
xfer->total_len -= epout->doeptsiz_bm.xfer_size;
if (epnum == 0) {
xfer->total_len -= ep0_pending[TUSB_DIR_OUT];
ep0_pending[TUSB_DIR_OUT] = 0;
@@ -1044,7 +773,7 @@ static void handle_epout_irq(uint8_t rhport) {
if (doepint & DOEPINT_SETUP) {
epout->doepint = DOEPINT_SETUP;
if(dma_enabled(dwc2)) {
if(dma_device_enabled(dwc2)) {
dma_setup_prepare(rhport);
}
@@ -1060,7 +789,7 @@ static void handle_epout_irq(uint8_t rhport) {
if (!(doepint & (DOEPINT_SETUP | DOEPINT_STPKTRX | DOEPINT_STSPHSRX))) {
xfer_ctl_t* xfer = XFER_CTL_BASE(epnum, TUSB_DIR_OUT);
if(dma_enabled(dwc2)) {
if(dma_device_enabled(dwc2)) {
if ((epnum == 0) && ep0_pending[TUSB_DIR_OUT]) {
// EP0 can only handle one packet Schedule another packet to be received.
edpt_schedule_packets(rhport, epnum, TUSB_DIR_OUT, 1, ep0_pending[TUSB_DIR_OUT]);
@@ -1092,8 +821,7 @@ static void handle_epout_irq(uint8_t rhport) {
static void handle_epin_irq(uint8_t rhport) {
dwc2_regs_t* dwc2 = DWC2_REG(rhport);
uint8_t const ep_count = _dwc2_controller[rhport].ep_count;
dwc2_epin_t* epin = dwc2->epin;
const uint8_t ep_count = _dwc2_controller[rhport].ep_count;
// DAINT for a given EP clears when DIEPINTx is cleared.
// IEPINT will be cleared when DAINT's out bits are cleared.
@@ -1101,16 +829,17 @@ static void handle_epin_irq(uint8_t rhport) {
if (dwc2->daint & TU_BIT(DAINT_IEPINT_Pos + n)) {
// IN XFER complete (entire xfer).
xfer_ctl_t* xfer = XFER_CTL_BASE(n, TUSB_DIR_IN);
dwc2_epin_t* epin = &dwc2->epin[n];
if (epin[n].diepint & DIEPINT_XFRC) {
epin[n].diepint = DIEPINT_XFRC;
if (epin->diepint & DIEPINT_XFRC) {
epin->diepint = DIEPINT_XFRC;
// EP0 can only handle one packet
if ((n == 0) && ep0_pending[TUSB_DIR_IN]) {
// Schedule another packet to be transmitted.
edpt_schedule_packets(rhport, n, TUSB_DIR_IN, 1, ep0_pending[TUSB_DIR_IN]);
} else {
if((n == 0) && dma_enabled(dwc2)) {
if((n == 0) && dma_device_enabled(dwc2)) {
dma_setup_prepare(rhport);
}
dcd_event_xfer_complete(rhport, n | TUSB_DIR_IN_MASK, xfer->total_len, XFER_RESULT_SUCCESS, true);
@@ -1118,39 +847,38 @@ static void handle_epin_irq(uint8_t rhport) {
}
// XFER FIFO empty
if ((epin[n].diepint & DIEPINT_TXFE) && (dwc2->diepempmsk & (1 << n))) {
if ((epin->diepint & DIEPINT_TXFE) && (dwc2->diepempmsk & (1 << n))) {
// diepint's TXFE bit is read-only, software cannot clear it.
// It will only be cleared by hardware when written bytes is more than
// - 64 bytes or
// - Half of TX FIFO size (configured by DIEPTXF)
uint16_t remaining_packets = (epin[n].dieptsiz & DIEPTSIZ_PKTCNT_Msk) >> DIEPTSIZ_PKTCNT_Pos;
// - Half/Empty of TX FIFO size (configured by GAHBCFG.TXFELVL)
const uint16_t remain_packets = epin->dieptsiz_bm.packet_count;
// Process every single packet (only whole packets can be written to fifo)
for (uint16_t i = 0; i < remaining_packets; i++) {
uint16_t const remaining_bytes = (epin[n].dieptsiz & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos;
for (uint16_t i = 0; i < remain_packets; i++) {
const uint16_t remain_bytes = (uint16_t) epin->dieptsiz_bm.xfer_size;
// Packet can not be larger than ep max size
uint16_t const packet_size = tu_min16(remaining_bytes, xfer->max_size);
const uint16_t xact_bytes = tu_min16(remain_bytes, xfer->max_size);
// It's only possible to write full packets into FIFO. Therefore DTXFSTS register of current
// EP has to be checked if the buffer can take another WHOLE packet
if (packet_size > ((epin[n].dtxfsts & DTXFSTS_INEPTFSAV_Msk) << 2)) break;
if (xact_bytes > ((epin->dtxfsts & DTXFSTS_INEPTFSAV_Msk) << 2)) {
break;
}
// Push packet to Tx-FIFO
if (xfer->ff) {
volatile uint32_t* tx_fifo = dwc2->fifo[n];
tu_fifo_read_n_const_addr_full_words(xfer->ff, (void*) (uintptr_t) tx_fifo, packet_size);
tu_fifo_read_n_const_addr_full_words(xfer->ff, (void*) (uintptr_t) tx_fifo, xact_bytes);
} else {
dfifo_write_packet(rhport, n, xfer->buffer, packet_size);
// Increment pointer to xfer data
xfer->buffer += packet_size;
dfifo_write_packet(dwc2, n, xfer->buffer, xact_bytes);
xfer->buffer += xact_bytes;
}
}
// Turn off TXFE if all bytes are written.
if (((epin[n].dieptsiz & DIEPTSIZ_XFRSIZ_Msk) >> DIEPTSIZ_XFRSIZ_Pos) == 0) {
if (epin->dieptsiz_bm.xfer_size == 0) {
dwc2->diepempmsk &= ~(1 << n);
}
}
@@ -1160,21 +888,11 @@ static void handle_epin_irq(uint8_t rhport) {
/* Interrupt Hierarchy
DxEPMSK.XferComplMsk DxEPINTn.XferCompl
| |
+---------- AND --------+
|
DAINT.xEPnInt DAINTMSK.xEPnMsk
| |
+---------- AND --------+
|
GINTSTS.xEPInt GINTMSK.xEPIntMsk
| |
+---------- AND --------+
|
GAHBCFG.GblIntrMsk
|
IRQn
DxEPINTn
|
DAINT.xEPn
|
GINTSTS: xEPInt
Note: when OTG_MULTI_PROC_INTRPT = 1, Device Each endpoint interrupt deachint/deachmsk/diepeachmsk/doepeachmsk
are combined to generate dedicated interrupt line for each endpoint.

View File

@@ -0,0 +1,302 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2024 Ha Thach (tinyusb.org)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* This file is part of the TinyUSB stack.
*/
#include "tusb_option.h"
#define DWC2_COMMON_DEBUG 2
#if defined(TUP_USBIP_DWC2) && (CFG_TUH_ENABLED || CFG_TUD_ENABLED)
#if CFG_TUD_ENABLED
#include "device/dcd.h"
#endif
#if CFG_TUH_ENABLED
#include "host/hcd.h"
#endif
#include "dwc2_common.h"
//--------------------------------------------------------------------
//
//--------------------------------------------------------------------
static void reset_core(dwc2_regs_t* dwc2) {
// reset core
dwc2->grstctl |= GRSTCTL_CSRST;
if ((dwc2->gsnpsid & DWC2_CORE_REV_MASK) < (DWC2_CORE_REV_4_20a & DWC2_CORE_REV_MASK)) {
// prior v42.0 CSRST is self-clearing
while (dwc2->grstctl & GRSTCTL_CSRST) {}
} else {
// From v4.20a CSRST bit is write only, CSRT_DONE (w1c) is introduced for checking.
// CSRST must also be explicitly cleared
while (!(dwc2->grstctl & GRSTCTL_CSRST_DONE)) {}
dwc2->grstctl = (dwc2->grstctl & ~GRSTCTL_CSRST) | GRSTCTL_CSRST_DONE;
}
while (!(dwc2->grstctl & GRSTCTL_AHBIDL)) {} // wait for AHB master IDLE
}
static void phy_fs_init(dwc2_regs_t* dwc2) {
TU_LOG(DWC2_COMMON_DEBUG, "Fullspeed PHY init\r\n");
uint32_t gusbcfg = dwc2->gusbcfg;
// Select FS PHY
gusbcfg |= GUSBCFG_PHYSEL;
dwc2->gusbcfg = gusbcfg;
// MCU specific PHY init before reset
dwc2_phy_init(dwc2, GHWCFG2_HSPHY_NOT_SUPPORTED);
// Reset core after selecting PHY
reset_core(dwc2);
// USB turnaround time is critical for certification where long cables and 5-Hubs are used.
// So if you need the AHB to run at less than 30 MHz, and if USB turnaround time is not critical,
// these bits can be programmed to a larger value. Default is 5
gusbcfg &= ~GUSBCFG_TRDT_Msk;
gusbcfg |= 5u << GUSBCFG_TRDT_Pos;
dwc2->gusbcfg = gusbcfg;
// MCU specific PHY update post reset
dwc2_phy_update(dwc2, GHWCFG2_HSPHY_NOT_SUPPORTED);
}
static void phy_hs_init(dwc2_regs_t* dwc2) {
uint32_t gusbcfg = dwc2->gusbcfg;
// De-select FS PHY
gusbcfg &= ~GUSBCFG_PHYSEL;
if (dwc2->ghwcfg2_bm.hs_phy_type == GHWCFG2_HSPHY_ULPI) {
TU_LOG(DWC2_COMMON_DEBUG, "Highspeed ULPI PHY init\r\n");
// Select ULPI PHY (external)
gusbcfg |= GUSBCFG_ULPI_UTMI_SEL;
// ULPI is always 8-bit interface
gusbcfg &= ~GUSBCFG_PHYIF16;
// ULPI select single data rate
gusbcfg &= ~GUSBCFG_DDRSEL;
// default internal VBUS Indicator and Drive
gusbcfg &= ~(GUSBCFG_ULPIEVBUSD | GUSBCFG_ULPIEVBUSI);
// Disable FS/LS ULPI
gusbcfg &= ~(GUSBCFG_ULPIFSLS | GUSBCFG_ULPICSM);
} else {
TU_LOG(DWC2_COMMON_DEBUG, "Highspeed UTMI+ PHY init\r\n");
// Select UTMI+ PHY (internal)
gusbcfg &= ~GUSBCFG_ULPI_UTMI_SEL;
// Set 16-bit interface if supported
if (dwc2->ghwcfg4_bm.phy_data_width) {
gusbcfg |= GUSBCFG_PHYIF16; // 16 bit
} else {
gusbcfg &= ~GUSBCFG_PHYIF16; // 8 bit
}
}
// Apply config
dwc2->gusbcfg = gusbcfg;
// mcu specific phy init
dwc2_phy_init(dwc2, dwc2->ghwcfg2_bm.hs_phy_type);
// Reset core after selecting PHY
reset_core(dwc2);
// Set turn-around, must after core reset otherwise it will be clear
// - 9 if using 8-bit PHY interface
// - 5 if using 16-bit PHY interface
gusbcfg &= ~GUSBCFG_TRDT_Msk;
gusbcfg |= (dwc2->ghwcfg4_bm.phy_data_width ? 5u : 9u) << GUSBCFG_TRDT_Pos;
dwc2->gusbcfg = gusbcfg;
// MCU specific PHY update post reset
dwc2_phy_update(dwc2, dwc2->ghwcfg2_bm.hs_phy_type);
}
static bool check_dwc2(dwc2_regs_t* dwc2) {
#if CFG_TUSB_DEBUG >= DWC2_COMMON_DEBUG
// print guid, gsnpsid, ghwcfg1, ghwcfg2, ghwcfg3, ghwcfg4
// Run 'python dwc2_info.py' and check dwc2_info.md for bit-field value and comparison with other ports
volatile uint32_t const* p = (volatile uint32_t const*) &dwc2->guid;
TU_LOG1("guid, gsnpsid, ghwcfg1, ghwcfg2, ghwcfg3, ghwcfg4\r\n");
for (size_t i = 0; i < 5; i++) {
TU_LOG1("0x%08" PRIX32 ", ", p[i]);
}
TU_LOG1("0x%08" PRIX32 "\r\n", p[5]);
#endif
// For some reason: GD32VF103 gsnpsid and all hwcfg register are always zero (skip it)
(void)dwc2;
#if !TU_CHECK_MCU(OPT_MCU_GD32VF103)
enum { GSNPSID_ID_MASK = TU_GENMASK(31, 16) };
const uint32_t gsnpsid = dwc2->gsnpsid & GSNPSID_ID_MASK;
TU_ASSERT(gsnpsid == DWC2_OTG_ID || gsnpsid == DWC2_FS_IOT_ID || gsnpsid == DWC2_HS_IOT_ID);
#endif
return true;
}
//--------------------------------------------------------------------
//
//--------------------------------------------------------------------
bool dwc2_core_is_highspeed(dwc2_regs_t* dwc2, tusb_role_t role) {
(void)dwc2;
#if CFG_TUD_ENABLED
if (role == TUSB_ROLE_DEVICE && !TUD_OPT_HIGH_SPEED) {
return false;
}
#endif
#if CFG_TUH_ENABLED
if (role == TUSB_ROLE_HOST && !TUH_OPT_HIGH_SPEED) {
return false;
}
#endif
return dwc2->ghwcfg2_bm.hs_phy_type != GHWCFG2_HSPHY_NOT_SUPPORTED;
}
/* dwc2 has several PHYs option
* - UTMI+ is internal highspeed PHY, clock can be 30 Mhz (8-bit) or 60 Mhz (16-bit)
* - ULPI is external highspeed PHY, clock is 60Mhz with only 8-bit interface
* - Dedicated FS PHY is internal with clock 48Mhz.
*
* In addition, UTMI+/ULPI can be shared to run at fullspeed mode with 48Mhz
*
*/
bool dwc2_core_init(uint8_t rhport, bool is_highspeed) {
dwc2_regs_t* dwc2 = DWC2_REG(rhport);
// Check Synopsys ID register, failed if controller clock/power is not enabled
TU_ASSERT(check_dwc2(dwc2));
// disable global interrupt
dwc2->gahbcfg &= ~GAHBCFG_GINT;
if (is_highspeed) {
phy_hs_init(dwc2);
} else {
phy_fs_init(dwc2);
}
/* Set HS/FS Timeout Calibration to 7 (max available value).
* The number of PHY clocks that the application programs in
* this field is added to the high/full speed interpacket timeout
* duration in the core to account for any additional delays
* introduced by the PHY. This can be required, because the delay
* introduced by the PHY in generating the linestate condition
* can vary from one PHY to another. */
dwc2->gusbcfg |= (7ul << GUSBCFG_TOCAL_Pos);
// Enable PHY clock TODO stop/gate clock when suspended mode
dwc2->pcgcctl &= ~(PCGCCTL_STOPPCLK | PCGCCTL_GATEHCLK | PCGCCTL_PWRCLMP | PCGCCTL_RSTPDWNMODULE);
dfifo_flush_tx(dwc2, 0x10); // all tx fifo
dfifo_flush_rx(dwc2);
// Clear pending and disable all interrupts
dwc2->gintsts = 0xFFFFFFFFU;
dwc2->gotgint = 0xFFFFFFFFU;
dwc2->gintmsk = 0;
return true;
}
// void dwc2_core_handle_common_irq(uint8_t rhport, bool in_isr) {
// (void) in_isr;
// dwc2_regs_t * const dwc2 = DWC2_REG(rhport);
// const uint32_t int_mask = dwc2->gintmsk;
// const uint32_t int_status = dwc2->gintsts & int_mask;
//
// // Device disconnect
// if (int_status & GINTSTS_DISCINT) {
// dwc2->gintsts = GINTSTS_DISCINT;
// }
//
// }
//--------------------------------------------------------------------
// DFIFO
//--------------------------------------------------------------------
// Read a single data packet from receive DFIFO
void dfifo_read_packet(dwc2_regs_t* dwc2, uint8_t* dst, uint16_t len) {
const volatile uint32_t* rx_fifo = dwc2->fifo[0];
// Reading full available 32 bit words from fifo
uint16_t word_count = len >> 2;
while (word_count--) {
tu_unaligned_write32(dst, *rx_fifo);
dst += 4;
}
// Read the remaining 1-3 bytes from fifo
const uint8_t bytes_rem = len & 0x03;
if (bytes_rem != 0) {
const uint32_t tmp = *rx_fifo;
dst[0] = tu_u32_byte0(tmp);
if (bytes_rem > 1) {
dst[1] = tu_u32_byte1(tmp);
}
if (bytes_rem > 2) {
dst[2] = tu_u32_byte2(tmp);
}
}
}
// Write a single data packet to DFIFO
void dfifo_write_packet(dwc2_regs_t* dwc2, uint8_t fifo_num, const uint8_t* src, uint16_t len) {
volatile uint32_t* tx_fifo = dwc2->fifo[fifo_num];
// Pushing full available 32 bit words to fifo
uint16_t word_count = len >> 2;
while (word_count--) {
*tx_fifo = tu_unaligned_read32(src);
src += 4;
}
// Write the remaining 1-3 bytes into fifo
const uint8_t bytes_rem = len & 0x03;
if (bytes_rem) {
uint32_t tmp_word = src[0];
if (bytes_rem > 1) {
tmp_word |= (src[1] << 8);
}
if (bytes_rem > 2) {
tmp_word |= (src[2] << 16);
}
*tx_fifo = tmp_word;
}
}
#endif

View File

@@ -0,0 +1,101 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2024 Ha Thach (tinyusb.org)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* This file is part of the TinyUSB stack.
*/
#ifndef TUSB_DWC2_COMMON_H
#define TUSB_DWC2_COMMON_H
#include "common/tusb_common.h"
#include "dwc2_type.h"
// Following symbols must be defined by port header
// - _dwc2_controller[]: array of controllers
// - DWC2_EP_MAX: largest EP counts of all controllers
// - dwc2_phy_init/dwc2_phy_update: phy init called before and after core reset
// - dwc2_dcd_int_enable/dwc2_dcd_int_disable
// - dwc2_remote_wakeup_delay
#if defined(TUP_USBIP_DWC2_STM32)
#include "dwc2_stm32.h"
#elif defined(TUP_USBIP_DWC2_ESP32)
#include "dwc2_esp32.h"
#elif TU_CHECK_MCU(OPT_MCU_GD32VF103)
#include "dwc2_gd32.h"
#elif TU_CHECK_MCU(OPT_MCU_BCM2711, OPT_MCU_BCM2835, OPT_MCU_BCM2837)
#include "dwc2_bcm.h"
#elif TU_CHECK_MCU(OPT_MCU_EFM32GG)
#include "dwc2_efm32.h"
#elif TU_CHECK_MCU(OPT_MCU_XMC4000)
#include "dwc2_xmc.h"
#else
#error "Unsupported MCUs"
#endif
enum {
DWC2_CONTROLLER_COUNT = TU_ARRAY_SIZE(_dwc2_controller)
};
enum {
OTG_INT_COMMON = 0 // GINTSTS_DISCINT | GINTSTS_CONIDSTSCHNG
};
//--------------------------------------------------------------------+
// Core/Controller
//--------------------------------------------------------------------+
TU_ATTR_ALWAYS_INLINE static inline dwc2_regs_t* DWC2_REG(uint8_t rhport) {
if (rhport >= DWC2_CONTROLLER_COUNT) {
// user mis-configured, ignore and use first controller
rhport = 0;
}
return (dwc2_regs_t*)_dwc2_controller[rhport].reg_base;
}
bool dwc2_core_is_highspeed(dwc2_regs_t* dwc2, tusb_role_t role);
bool dwc2_core_init(uint8_t rhport, bool is_highspeed);
void dwc2_core_handle_common_irq(uint8_t rhport, bool in_isr);
//--------------------------------------------------------------------+
// DFIFO
//--------------------------------------------------------------------+
TU_ATTR_ALWAYS_INLINE static inline void dfifo_flush_tx(dwc2_regs_t* dwc2, uint8_t fnum) {
// flush TX fifo and wait for it cleared
dwc2->grstctl = GRSTCTL_TXFFLSH | (fnum << GRSTCTL_TXFNUM_Pos);
while (dwc2->grstctl & GRSTCTL_TXFFLSH_Msk) {}
}
TU_ATTR_ALWAYS_INLINE static inline void dfifo_flush_rx(dwc2_regs_t* dwc2) {
// flush RX fifo and wait for it cleared
dwc2->grstctl = GRSTCTL_RXFFLSH;
while (dwc2->grstctl & GRSTCTL_RXFFLSH_Msk) {}
}
void dfifo_read_packet(dwc2_regs_t* dwc2, uint8_t* dst, uint16_t len);
void dfifo_write_packet(dwc2_regs_t* dwc2, uint8_t fifo_num, uint8_t const* src, uint16_t len);
//--------------------------------------------------------------------+
// DMA
//--------------------------------------------------------------------+
#endif

View File

@@ -25,13 +25,14 @@
*/
#ifndef _DWC2_ESP32_H_
#define _DWC2_ESP32_H_
#ifndef TUSB_DWC2_ESP32_H_
#define TUSB_DWC2_ESP32_H_
#ifdef __cplusplus
extern "C" {
#endif
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "esp_intr_alloc.h"
@@ -59,21 +60,37 @@ static const dwc2_controller_t _dwc2_controller[] = {
};
#endif
//--------------------------------------------------------------------+
//
//--------------------------------------------------------------------+
static intr_handle_t usb_ih[TU_ARRAY_SIZE(_dwc2_controller)];
static void dcd_int_handler_wrap(void* arg) {
const uint8_t rhport = (uint8_t)(uintptr_t) arg;
dcd_int_handler(rhport);
static void dwc2_int_handler_wrap(void* arg) {
const uint8_t rhport = tu_u16_low((uint16_t)(uintptr_t)arg);
const tusb_role_t role = (tusb_role_t) tu_u16_high((uint16_t)(uintptr_t)arg);
#if CFG_TUD_ENABLED
if (role == TUSB_ROLE_DEVICE) {
dcd_int_handler(rhport);
}
#endif
#if CFG_TUH_ENABLED
if (role == TUSB_ROLE_HOST) {
hcd_int_handler(rhport, true);
}
#endif
}
TU_ATTR_ALWAYS_INLINE static inline void dwc2_dcd_int_enable(uint8_t rhport) {
esp_intr_alloc(_dwc2_controller[rhport].irqnum, ESP_INTR_FLAG_LOWMED,
dcd_int_handler_wrap, (void*)(uintptr_t) rhport, &usb_ih[rhport]);
TU_ATTR_ALWAYS_INLINE static inline void dwc2_int_set(uint8_t rhport, tusb_role_t role, bool enabled) {
if (enabled) {
esp_intr_alloc(_dwc2_controller[rhport].irqnum, ESP_INTR_FLAG_LOWMED,
dwc2_int_handler_wrap, (void*)(uintptr_t)tu_u16(role, rhport), &usb_ih[rhport]);
} else {
esp_intr_free(usb_ih[rhport]);
}
}
TU_ATTR_ALWAYS_INLINE static inline void dwc2_dcd_int_disable(uint8_t rhport) {
esp_intr_free(usb_ih[rhport]);
}
#define dwc2_dcd_int_enable(_rhport) dwc2_int_set(_rhport, TUSB_ROLE_DEVICE, true)
#define dwc2_dcd_int_disable(_rhport) dwc2_int_set(_rhport, TUSB_ROLE_DEVICE, false)
TU_ATTR_ALWAYS_INLINE static inline void dwc2_remote_wakeup_delay(void) {
vTaskDelay(pdMS_TO_TICKS(1));
@@ -83,14 +100,15 @@ TU_ATTR_ALWAYS_INLINE static inline void dwc2_remote_wakeup_delay(void) {
TU_ATTR_ALWAYS_INLINE static inline void dwc2_phy_init(dwc2_regs_t* dwc2, uint8_t hs_phy_type) {
(void)dwc2;
(void)hs_phy_type;
// nothing to do
// maybe usb_utmi_hal_init()
}
// MCU specific PHY update, it is called AFTER init() and core reset
TU_ATTR_ALWAYS_INLINE static inline void dwc2_phy_update(dwc2_regs_t* dwc2, uint8_t hs_phy_type) {
(void)dwc2;
(void)hs_phy_type;
// nothing to do
// maybe usb_utmi_hal_disable()
}
#ifdef __cplusplus

View File

@@ -1,58 +1,58 @@
| | BCM2711 (Pi4) | EFM32GG | ESP32-S2/S3 | ESP32-P4 | ST F207/F407/411/429 FS | ST F407/429 HS | ST F412/767 FS | ST F723/L4P5 FS | ST F723 HS | ST F769 | ST H743/H750 | ST L476 FS | ST U5A5 HS | GD32VF103 | XMC4500 |
|:---------------------------|:----------------|:-------------|:--------------|:-------------|:--------------------------|:-----------------|:-----------------|:------------------|:-------------|:-------------|:---------------|:-------------|:-------------|:------------|:-------------|
| GUID | 0x2708A000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00001200 | 0x00001100 | 0x00002000 | 0x00003000 | 0x00003100 | 0x00002100 | 0x00002300 | 0x00002000 | 0x00005000 | 0x00001000 | 0x00AEC000 |
| GSNPSID | 0x4F54280A | 0x4F54330A | 0x4F54400A | 0x4F54400A | 0x4F54281A | 0x4F54281A | 0x4F54320A | 0x4F54330A | 0x4F54330A | 0x4F54320A | 0x4F54330A | 0x4F54310A | 0x4F54411A | 0x00000000 | 0x4F54292A |
| - specs version | 2.80a | 3.30a | 4.00a | 4.00a | 2.81a | 2.81a | 3.20a | 3.30a | 3.30a | 3.20a | 3.30a | 3.10a | 4.11a | 0.00W | 2.92a |
| GHWCFG1 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 |
| GHWCFG2 | 0x228DDD50 | 0x228F5910 | 0x224DD930 | 0x215FFFD0 | 0x229DCD20 | 0x229ED590 | 0x229ED520 | 0x229ED520 | 0x229FE1D0 | 0x229FE190 | 0x229FE190 | 0x229ED520 | 0x228FE052 | 0x00000000 | 0x228F5930 |
| - op_mode | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | noHNP noSRP | HNP SRP | HNP SRP |
| - arch | DMA internal | DMA internal | DMA internal | DMA internal | Slave only | DMA internal | Slave only | Slave only | DMA internal | DMA internal | DMA internal | Slave only | DMA internal | Slave only | DMA internal |
| - p2p (hub support) | 0 | 0 | 1 | 0 | 1 | 0 | 1 | 1 | 0 | 0 | 0 | 1 | 0 | 0 | 1 |
| - hs_phy_type | UTMI+ | n/a | n/a | UTMI+/ULPI | n/a | ULPI | n/a | n/a | UTMI+/ULPI | ULPI | ULPI | n/a | UTMI+ | n/a | n/a |
| - fs_phy_type | Dedicated | Dedicated | Dedicated | Shared ULPI | Dedicated | Dedicated | Dedicated | Dedicated | Dedicated | Dedicated | Dedicated | Dedicated | n/a | n/a | Dedicated |
| - num_dev_ep | 7 | 6 | 6 | 15 | 3 | 5 | 5 | 5 | 8 | 8 | 8 | 5 | 8 | 0 | 6 |
| - num_host_ch | 7 | 13 | 7 | 15 | 7 | 11 | 11 | 11 | 15 | 15 | 15 | 11 | 15 | 0 | 13 |
| - period_channel_support | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 1 |
| - enable_dynamic_fifo | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 1 |
| - mul_proc_intrpt | 0 | 0 | 0 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 0 | 0 |
| - reserved21 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - nptx_q_depth | 2 | 2 | 1 | 1 | 2 | 2 | 2 | 2 | 2 | 2 | 2 | 2 | 2 | 0 | 2 |
| - ptx_q_depth | 2 | 2 | 2 | 1 | 2 | 2 | 2 | 2 | 2 | 2 | 2 | 2 | 2 | 0 | 2 |
| - token_q_depth | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 0 | 8 |
| - otg_enable_ic_usb | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| GHWCFG3 | 0x0FF000E8 | 0x01F204E8 | 0x00C804B5 | 0x03805EB5 | 0x020001E8 | 0x03F403E8 | 0x0200D1E8 | 0x0200D1E8 | 0x03EED2E8 | 0x03EED2E8 | 0x03B8D2E8 | 0x0200D1E8 | 0x03B882E8 | 0x00000000 | 0x027A01E5 |
| - xfer_size_width | 8 | 8 | 5 | 5 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 0 | 5 |
| - packet_size_width | 6 | 6 | 3 | 3 | 6 | 6 | 6 | 6 | 6 | 6 | 6 | 6 | 6 | 0 | 6 |
| - otg_enable | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 1 |
| - i2c_enable | 0 | 0 | 0 | 0 | 1 | 1 | 1 | 1 | 0 | 0 | 0 | 1 | 0 | 0 | 1 |
| - vendor_ctrl_itf | 0 | 0 | 0 | 1 | 0 | 1 | 0 | 0 | 1 | 1 | 1 | 0 | 1 | 0 | 0 |
| - optional_feature_removed | 0 | 1 | 1 | 1 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - synch_reset | 0 | 0 | 0 | 1 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - otg_adp_support | 0 | 0 | 0 | 1 | 0 | 0 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 0 | 0 |
| - otg_enable_hsic | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - battery_charger_support | 0 | 0 | 0 | 1 | 0 | 0 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 0 | 0 |
| - lpm_mode | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 0 |
| - dfifo_depth | 4080 | 498 | 200 | 896 | 512 | 1012 | 512 | 512 | 1006 | 1006 | 952 | 512 | 952 | 0 | 634 |
| GHWCFG4 | 0x1FF00020 | 0x1BF08030 | 0xD3F0A030 | 0xDFF1A030 | 0x0FF08030 | 0x17F00030 | 0x17F08030 | 0x17F08030 | 0x23F00030 | 0x23F00030 | 0xE3F00030 | 0x17F08030 | 0xE2103E30 | 0x00000000 | 0xDBF08030 |
| - num_dev_period_in_ep | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - partial_powerdown | 0 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 1 |
| - ahb_freq_min | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 1 |
| - hibernation | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - extended_hibernation | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - reserved8 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - enhanced_lpm_support1 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 0 |
| - service_interval_flow | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 0 |
| - ipg_isoc_support | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 0 |
| - acg_support | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 0 |
| - enhanced_lpm_support | 0 | 0 | 1 | 1 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 0 |
| - phy_data_width | 8 bit | 8/16 bit | 8/16 bit | 8/16 bit | 8/16 bit | 8 bit | 8/16 bit | 8/16 bit | 8 bit | 8 bit | 8 bit | 8/16 bit | 8 bit | 8 bit | 8/16 bit |
| - ctrl_ep_num | 0 | 0 | 0 | 1 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - iddg_filter | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 1 |
| - vbus_valid_filter | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 0 | 1 |
| - a_valid_filter | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 0 | 1 |
| - b_valid_filter | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 0 | 1 |
| - session_end_filter | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 0 | 1 |
| - dedicated_fifos | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 1 |
| - num_dev_in_eps | 7 | 6 | 4 | 7 | 3 | 5 | 5 | 5 | 8 | 8 | 8 | 5 | 8 | 0 | 6 |
| - dma_desc_enable | 0 | 0 | 1 | 1 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 1 | 0 | 1 |
| - dma_desc_dynamic | 0 | 0 | 1 | 1 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 1 | 0 | 1 |
| | BCM2711 (Pi4) | EFM32GG | ESP32-S2/S3 | ESP32-P4 | ST F207/F407/411/429 FS | ST F407/429 HS | ST F412/76x FS | ST F723/L4P5 FS | ST F723 HS | ST F76x HS | ST H743/H750 | ST L476 FS | ST U5A5 HS | XMC4500 | GD32VF103 |
|:---------------------------|:----------------|:-------------|:--------------|:-------------|:--------------------------|:-----------------|:-----------------|:------------------|:-------------|:-------------|:---------------|:-------------|:-------------|:-------------|:------------|
| GUID | 0x2708A000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00001200 | 0x00001100 | 0x00002000 | 0x00003000 | 0x00003100 | 0x00002100 | 0x00002300 | 0x00002000 | 0x00005000 | 0x00AEC000 | 0x00001000 |
| GSNPSID | 0x4F54280A | 0x4F54330A | 0x4F54400A | 0x4F54400A | 0x4F54281A | 0x4F54281A | 0x4F54320A | 0x4F54330A | 0x4F54330A | 0x4F54320A | 0x4F54330A | 0x4F54310A | 0x4F54411A | 0x4F54292A | 0x00000000 |
| - specs version | 2.80a | 3.30a | 4.00a | 4.00a | 2.81a | 2.81a | 3.20a | 3.30a | 3.30a | 3.20a | 3.30a | 3.10a | 4.11a | 2.92a | 0.00W |
| GHWCFG1 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 | 0x00000000 |
| GHWCFG2 | 0x228DDD50 | 0x228F5910 | 0x224DD930 | 0x215FFFD0 | 0x229DCD20 | 0x229ED590 | 0x229ED520 | 0x229ED520 | 0x229FE1D0 | 0x229FE190 | 0x229FE190 | 0x229ED520 | 0x228FE052 | 0x228F5930 | 0x00000000 |
| - op_mode | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | HNP SRP | noHNP noSRP | HNP SRP | HNP SRP |
| - arch | DMA internal | DMA internal | DMA internal | DMA internal | Slave only | DMA internal | Slave only | Slave only | DMA internal | DMA internal | DMA internal | Slave only | DMA internal | DMA internal | Slave only |
| - single_point | hub | hub | n/a | hub | n/a | hub | n/a | n/a | hub | hub | hub | n/a | hub | n/a | hub |
| - hs_phy_type | UTMI+ | n/a | n/a | UTMI+/ULPI | n/a | ULPI | n/a | n/a | UTMI+/ULPI | ULPI | ULPI | n/a | UTMI+ | n/a | n/a |
| - fs_phy_type | Dedicated | Dedicated | Dedicated | Shared ULPI | Dedicated | Dedicated | Dedicated | Dedicated | Dedicated | Dedicated | Dedicated | Dedicated | n/a | Dedicated | n/a |
| - num_dev_ep | 7 | 6 | 6 | 15 | 3 | 5 | 5 | 5 | 8 | 8 | 8 | 5 | 8 | 6 | 0 |
| - num_host_ch | 7 | 13 | 7 | 15 | 7 | 11 | 11 | 11 | 15 | 15 | 15 | 11 | 15 | 13 | 0 |
| - period_channel_support | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 |
| - enable_dynamic_fifo | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 |
| - mul_proc_intrpt | 0 | 0 | 0 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 0 | 0 |
| - reserved21 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - nptx_q_depth | 8 | 8 | 4 | 4 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 2 |
| - ptx_q_depth | 8 | 8 | 8 | 4 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 2 |
| - token_q_depth | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 0 |
| - otg_enable_ic_usb | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| GHWCFG3 | 0x0FF000E8 | 0x01F204E8 | 0x00C804B5 | 0x03805EB5 | 0x020001E8 | 0x03F403E8 | 0x0200D1E8 | 0x0200D1E8 | 0x03EED2E8 | 0x03EED2E8 | 0x03B8D2E8 | 0x0200D1E8 | 0x03B882E8 | 0x027A01E5 | 0x00000000 |
| - xfer_size_width | 8 | 8 | 5 | 5 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 8 | 5 | 0 |
| - packet_size_width | 6 | 6 | 3 | 3 | 6 | 6 | 6 | 6 | 6 | 6 | 6 | 6 | 6 | 6 | 0 |
| - otg_enable | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 |
| - i2c_enable | 0 | 0 | 0 | 0 | 1 | 1 | 1 | 1 | 0 | 0 | 0 | 1 | 0 | 1 | 0 |
| - vendor_ctrl_itf | 0 | 0 | 0 | 1 | 0 | 1 | 0 | 0 | 1 | 1 | 1 | 0 | 1 | 0 | 0 |
| - optional_feature_removed | 0 | 1 | 1 | 1 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - synch_reset | 0 | 0 | 0 | 1 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - otg_adp_support | 0 | 0 | 0 | 1 | 0 | 0 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 0 | 0 |
| - otg_enable_hsic | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - battery_charger_support | 0 | 0 | 0 | 1 | 0 | 0 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 0 | 0 |
| - lpm_mode | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 0 |
| - dfifo_depth | 4080 | 498 | 200 | 896 | 512 | 1012 | 512 | 512 | 1006 | 1006 | 952 | 512 | 952 | 634 | 0 |
| GHWCFG4 | 0x1FF00020 | 0x1BF08030 | 0xD3F0A030 | 0xDFF1A030 | 0x0FF08030 | 0x17F00030 | 0x17F08030 | 0x17F08030 | 0x23F00030 | 0x23F00030 | 0xE3F00030 | 0x17F08030 | 0xE2103E30 | 0xDBF08030 | 0x00000000 |
| - num_dev_period_in_ep | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - partial_powerdown | 0 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 |
| - ahb_freq_min | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 |
| - hibernation | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - extended_hibernation | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - reserved8 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - enhanced_lpm_support1 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 0 |
| - service_interval_flow | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 0 |
| - ipg_isoc_support | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 0 |
| - acg_support | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 0 |
| - enhanced_lpm_support | 0 | 0 | 1 | 1 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 0 |
| - phy_data_width | 8 bit | 8/16 bit | 8/16 bit | 8/16 bit | 8/16 bit | 8 bit | 8/16 bit | 8/16 bit | 8 bit | 8 bit | 8 bit | 8/16 bit | 8 bit | 8/16 bit | 8 bit |
| - ctrl_ep_num | 0 | 0 | 0 | 1 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 |
| - iddg_filter | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 |
| - vbus_valid_filter | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 1 | 0 |
| - a_valid_filter | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 1 | 0 |
| - b_valid_filter | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 1 | 0 |
| - session_end_filter | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 | 1 | 0 |
| - dedicated_fifos | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 0 |
| - num_dev_in_eps | 7 | 6 | 4 | 7 | 3 | 5 | 5 | 5 | 8 | 8 | 8 | 5 | 8 | 6 | 0 |
| - dma_desc_enable | 0 | 0 | 1 | 1 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 1 | 1 | 0 |
| - dma_desc_dynamic | 0 | 0 | 1 | 1 | 0 | 0 | 0 | 0 | 0 | 0 | 1 | 0 | 1 | 1 | 0 |

View File

@@ -15,16 +15,15 @@ dwc2_reg_value = {
'ESP32-P4': [0, 0x4F54400A, 0, 0x215FFFD0, 0x03805EB5, 0xDFF1A030],
'ST F207/F407/411/429 FS': [0x1200, 0x4F54281A, 0, 0x229DCD20, 0x020001E8, 0x0FF08030],
'ST F407/429 HS': [0x1100, 0x4F54281A, 0, 0x229ED590, 0x03F403E8, 0x17F00030],
'ST F412/767 FS': [0x2000, 0x4F54320A, 0, 0x229ED520, 0x0200D1E8, 0x17F08030],
'ST F412/76x FS': [0x2000, 0x4F54320A, 0, 0x229ED520, 0x0200D1E8, 0x17F08030],
'ST F723/L4P5 FS': [0x3000, 0x4F54330A, 0, 0x229ED520, 0x0200D1E8, 0x17F08030],
'ST F723 HS': [0x3100, 0x4F54330A, 0, 0x229FE1D0, 0x03EED2E8, 0x23F00030],
'ST F769': [0x2100, 0x4F54320A, 0, 0x229FE190, 0x03EED2E8, 0x23F00030],
'ST F76x HS': [0x2100, 0x4F54320A, 0, 0x229FE190, 0x03EED2E8, 0x23F00030],
'ST H743/H750': [0x2300, 0x4F54330A, 0, 0x229FE190, 0x03B8D2E8, 0xE3F00030],
'ST L476 FS': [0x2000, 0x4F54310A, 0, 0x229ED520, 0x0200D1E8, 0x17F08030],
'ST U5A5 HS': [0x5000, 0x4F54411A, 0, 0x228FE052, 0x03B882E8, 0xE2103E30],
'XMC4500': [0xAEC000, 0x4F54292A, 0, 0x228F5930, 0x027A01E5, 0xDBF08030],
'GD32VF103': [0x1000, 0, 0, 0, 0, 0],
'XMC4500': [0xAEC000, 0x4F54292A, 0, 0x228F5930, 0x027A01E5, 0xDBF08030]
}
# Combine dwc2_info with dwc2_reg_list
@@ -44,7 +43,7 @@ class GHWCFG2(ctypes.LittleEndianStructure):
_fields_ = [
("op_mode", ctypes.c_uint32, 3),
("arch", ctypes.c_uint32, 2),
("p2p (hub support)", ctypes.c_uint32, 1),
("single_point", ctypes.c_uint32, 1),
("hs_phy_type", ctypes.c_uint32, 2),
("fs_phy_type", ctypes.c_uint32, 2),
("num_dev_ep", ctypes.c_uint32, 4),
@@ -119,6 +118,10 @@ GHWCFG2_field = {
1: "DMA external",
2: "DMA internal"
},
'single_point': {
0: "hub",
1: "n/a"
},
'hs_phy_type': {
0: "n/a",
1: "UTMI+",
@@ -130,7 +133,18 @@ GHWCFG2_field = {
1: "Dedicated",
2: "Shared UTMI+",
3: "Shared ULPI"
}
},
'nptx_q_depth': {
0: "2",
1: "4",
2: "8",
},
'ptx_q_depth': {
0: "2",
1: "4",
2: "8",
3: "16"
},
}
# mapping for specific fields in GHWCFG4

View File

@@ -124,13 +124,19 @@ static const dwc2_controller_t _dwc2_controller[] = {
// SystemCoreClock is already included by family header
// extern uint32_t SystemCoreClock;
TU_ATTR_ALWAYS_INLINE static inline void dwc2_dcd_int_enable(uint8_t rhport) {
NVIC_EnableIRQ((IRQn_Type) _dwc2_controller[rhport].irqnum);
TU_ATTR_ALWAYS_INLINE static inline void dwc2_int_set(uint8_t rhport, tusb_role_t role, bool enabled) {
(void) role;
const IRQn_Type irqn = (IRQn_Type) _dwc2_controller[rhport].irqnum;
if (enabled) {
NVIC_EnableIRQ(irqn);
} else {
NVIC_DisableIRQ(irqn);
}
}
TU_ATTR_ALWAYS_INLINE static inline void dwc2_dcd_int_disable(uint8_t rhport) {
NVIC_DisableIRQ((IRQn_Type) _dwc2_controller[rhport].irqnum);
}
#define dwc2_dcd_int_enable(_rhport) dwc2_int_set(_rhport, TUSB_ROLE_DEVICE, true)
#define dwc2_dcd_int_disable(_rhport) dwc2_int_set(_rhport, TUSB_ROLE_DEVICE, false)
TU_ATTR_ALWAYS_INLINE static inline void dwc2_remote_wakeup_delay(void) {
// try to delay for 1 ms

View File

@@ -31,8 +31,8 @@
* opensource.org/licenses/BSD-3-Clause
*/
#ifndef _TUSB_DWC2_TYPES_H_
#define _TUSB_DWC2_TYPES_H_
#ifndef TUSB_DWC2_TYPES_H_
#define TUSB_DWC2_TYPES_H_
#include "stdint.h"
@@ -86,6 +86,11 @@ typedef struct
} HS_PHYC_GlobalTypeDef;
#endif
enum {
GOTGCTL_OTG_VERSION_1_3 = 0,
GOTGCTL_OTG_VERSION_2_0 = 1,
};
enum {
GHWCFG2_OPMODE_HNP_SRP = 0,
GHWCFG2_OPMODE_SRP = 1,
@@ -122,8 +127,52 @@ enum {
GHWCFFG4_PHY_DATA_WIDTH_8_16 = 2, // software selectable
};
enum {
HPRT_SPEED_HIGH = 0,
HPRT_SPEED_FULL = 1,
HPRT_SPEED_LOW = 2
};
enum {
GINTSTS_CMODE_DEVICE = 0,
GINTSTS_CMODE_HOST = 1,
};
enum {
HCTSIZ_PID_DATA0 = 0, // 00b
HCTSIZ_PID_DATA2 = 1, // 01b
HCTSIZ_PID_DATA1 = 2, // 10b
HCTSIZ_PID_SETUP = 3, // 11b
};
enum {
HCTSIZ_PID_MDATA = 3,
};
enum {
GRXSTS_PKTSTS_GLOBALOUTNAK = 1,
GRXSTS_PKTSTS_OUTRX = 2,
GRXSTS_PKTSTS_OUTDONE = 3,
GRXSTS_PKTSTS_SETUPDONE = 4,
GRXSTS_PKTSTS_SETUPRX = 6
};
enum {
GRXSTS_PKTSTS_RX_DATA = 2,
GRXSTS_PKTSTS_RX_COMPLETE = 3,
GRXSTS_PKTSTS_HOST_DATATOGGLE_ERR = 5,
GRXSTS_PKTSTS_HOST_CHANNEL_HALTED = 7
};
// Same as TUSB_XFER_*
enum {
HCCHAR_EPTYPE_CONTROL = 0,
HCCHAR_EPTYPE_ISOCHRONOUS = 1,
HCCHAR_EPTYPE_BULK = 2,
HCCHAR_EPTYPE_INTERRUPT = 3
};
//--------------------------------------------------------------------
// Register bitfield definitions
// Common Register Bitfield
//--------------------------------------------------------------------
typedef struct TU_ATTR_PACKED {
uint32_t ses_req_scs : 1; // 0 Session request success
@@ -146,7 +195,7 @@ typedef struct TU_ATTR_PACKED {
uint32_t ases_valid : 1; // 18 A-session valid
uint32_t bses_valid : 1; // 19 B-session valid
uint32_t otg_ver : 1; // 20 OTG version 0: v1.3, 1: v2.0
uint32_t current_mode : 1; // 21 Current mode of operation 0: device, 1: host
uint32_t current_mode : 1; // 21 Current mode of operation. Only from v3.00a
uint32_t mult_val_id_bc : 5; // 22..26 Multi-valued input pin ID battery charger
uint32_t chirp_en : 1; // 27 Chirp detection enable
uint32_t rsv28_30 : 3; // 28.30: Reserved
@@ -192,7 +241,7 @@ typedef struct TU_ATTR_PACKED {
based on the speed of enumeration. The number of bit times added per PHY clock are as follows:
- High-speed: PHY clock One 30-MHz = 16 bit times, One 60-MHz = 8 bit times
- Full-speed: PHY clock One 30-MHz = 0.4 bit times, One 60-MHz = 0.2 bit times, One 48-MHz = 0.25 bit times */
uint32_t phy_if : 1; // 3 PHY interface. 0: 8 bits, 1: 16 bits
uint32_t phy_if16 : 1; // 3 PHY interface. 0: 8 bits, 1: 16 bits
uint32_t ulpi_utmi_sel : 1; // 4 ULPI/UTMI select. 0: UTMI+, 1: ULPI
uint32_t fs_intf_sel : 1; // 5 Fullspeed serial interface select. 0: 6-pin, 1: 3-pin
uint32_t phy_sel : 1; // 6 HS/FS PHY selection. 0: HS UTMI+ or ULPI, 1: FS serial transceiver
@@ -240,10 +289,21 @@ typedef struct TU_ATTR_PACKED {
} dwc2_grstctl_t;
TU_VERIFY_STATIC(sizeof(dwc2_grstctl_t) == 4, "incorrect size");
typedef struct TU_ATTR_PACKED {
uint32_t ep_ch_num : 4; // 0..3 Endpoint/Channel Number
uint32_t byte_count :11; // 4..14 Byte Count
uint32_t dpid : 2; // 15..16 Data PID
uint32_t packet_status : 4; // 17..20 Packet Status
uint32_t frame_number : 4; // 21..24 Frame Number
uint32_t rsv25_31 : 7; // 25..31 Reserved
} dwc2_grxstsp_t;
TU_VERIFY_STATIC(sizeof(dwc2_grxstsp_t) == 4, "incorrect size");
// Hardware Configuration
typedef struct TU_ATTR_PACKED {
uint32_t op_mode : 3; // 0..2 HNP/SRP Host/Device/OTG mode
uint32_t arch : 2; // 3..4 Slave/External/Internal DMA
uint32_t point2point : 1; // 5 0: support hub and split | 1: no hub, no split
uint32_t single_point : 1; // 5 0: support hub and split | 1: no hub, no split
uint32_t hs_phy_type : 2; // 6..7 0: not supported | 1: UTMI+ | 2: ULPI | 3: UTMI+ and ULPI
uint32_t fs_phy_type : 2; // 8..9 0: not supported | 1: dedicated | 2: UTMI+ | 3: ULPI
uint32_t num_dev_ep : 4; // 10..13 Number of device endpoints (excluding EP0)
@@ -301,41 +361,150 @@ typedef struct TU_ATTR_PACKED {
}dwc2_ghwcfg4_t;
TU_VERIFY_STATIC(sizeof(dwc2_ghwcfg4_t) == 4, "incorrect size");
//--------------------------------------------------------------------
// Host Register Bitfield
//--------------------------------------------------------------------
typedef struct TU_ATTR_PACKED {
uint32_t fifo_available : 16; // 0..15 Number of words available in the Tx FIFO
uint32_t req_queue_available : 8; // 16..23 Number of spaces available in the NPT transmit request queue for both IN and OU
// 24..31 is top entry in the request queue that is currently being processed by the MAC
uint32_t qtop_terminate : 1; // 24 Last entry for selected channel
uint32_t qtop_type : 2; // 25..26 Token (0) In/Out (1) ZLP, (2) Ping/cspit, (3) Channel halt command
uint32_t qtop_ch_num : 4; // 27..30 Channel number
} dwc2_hnptxsts_t;
TU_VERIFY_STATIC(sizeof(dwc2_hnptxsts_t) == 4, "incorrect size");
typedef struct TU_ATTR_PACKED {
uint32_t fifo_available : 16; // 0..15 Number of words available in the Tx FIFO
uint32_t req_queue_available : 7; // 16..22 Number of spaces available in the PTX transmit request queue
uint32_t qtop_terminate : 1; // 23 Last entry for selected channel
uint32_t qtop_last_period : 1; // 24 Last entry for selected channel is a periodic entry
uint32_t qtop_type : 2; // 25..26 Token (0) In/Out (1) ZLP, (2) Ping/cspit, (3) Channel halt command
uint32_t qtop_ch_num : 4; // 27..30 Channel number
uint32_t qtop_odd_frame : 1; // 31 Send in odd frame
} dwc2_hptxsts_t;
TU_VERIFY_STATIC(sizeof(dwc2_hptxsts_t) == 4, "incorrect size");
typedef struct TU_ATTR_PACKED {
uint32_t conn_status : 1; // 0 Port connect status
uint32_t conn_detected : 1; // 1 Port connect detected
uint32_t enable : 1; // 2 Port enable status
uint32_t enable_change : 1; // 3 Port enable change
uint32_t over_current_active : 1; // 4 Port Over-current active
uint32_t over_current_change : 1; // 5 Port Over-current change
uint32_t resume : 1; // 6 Port resume
uint32_t suspend : 1; // 7 Port suspend
uint32_t reset : 1; // 8 Port reset
uint32_t rsv9 : 1; // 9 Reserved
uint32_t line_status : 2; // 10..11 Line status
uint32_t power : 1; // 12 Port power
uint32_t test_control : 4; // 13..16 Port Test control
uint32_t speed : 2; // 17..18 Port speed
uint32_t rsv19_31 :13; // 19..31 Reserved
}dwc2_hprt_t;
TU_VERIFY_STATIC(sizeof(dwc2_hprt_t) == 4, "incorrect size");
typedef struct TU_ATTR_PACKED {
uint32_t ep_size : 11; // 0..10 Maximum packet size
uint32_t ep_num : 4; // 11..14 Endpoint number
uint32_t ep_dir : 1; // 15 Endpoint direction
uint32_t rsv16 : 1; // 16 Reserved
uint32_t low_speed_dev : 1; // 17 Low-speed device
uint32_t ep_type : 2; // 18..19 Endpoint type
uint32_t err_multi_count : 2; // 20..21 Error (splitEn = 1) / Multi (SplitEn = 0) count
uint32_t dev_addr : 7; // 22..28 Device address
uint32_t odd_frame : 1; // 29 Odd frame
uint32_t disable : 1; // 30 Channel disable
uint32_t enable : 1; // 31 Channel enable
} dwc2_channel_char_t;
TU_VERIFY_STATIC(sizeof(dwc2_channel_char_t) == 4, "incorrect size");
typedef struct TU_ATTR_PACKED {
uint32_t hub_port : 7; // 0..6 Hub port number
uint32_t hub_addr : 7; // 7..13 Hub address
uint32_t xact_pos : 2; // 14..15 Transaction position
uint32_t split_compl : 1; // 16 Split completion
uint32_t rsv17_30 : 14; // 17..30 Reserved
uint32_t split_en : 1; // 31 Split enable
} dwc2_channel_split_t;
TU_VERIFY_STATIC(sizeof(dwc2_channel_split_t) == 4, "incorrect size");
typedef struct TU_ATTR_PACKED {
uint32_t xfer_size : 19; // 0..18 Transfer size in bytes
uint32_t packet_count : 10; // 19..28 Number of packets
uint32_t pid : 2; // 29..30 Packet ID
uint32_t do_ping : 1; // 31 Do PING
} dwc2_channel_tsize_t;
TU_VERIFY_STATIC(sizeof(dwc2_channel_tsize_t) == 4, "incorrect size");
typedef struct TU_ATTR_PACKED {
uint32_t num : 16; // 0..15 Frame number
uint32_t remainning : 16; // 16..31 Frame remaining
} dwc2_hfnum_t;
TU_VERIFY_STATIC(sizeof(dwc2_hfnum_t) == 4, "incorrect size");
// Host Channel
typedef struct {
volatile uint32_t hcchar; // 500 + 20*ch Host Channel Characteristics
volatile uint32_t hcsplt; // 504 + 20*ch Host Channel Split Control
volatile uint32_t hcint; // 508 + 20*ch Host Channel Interrupt
volatile uint32_t hcintmsk; // 50C + 20*ch Host Channel Interrupt Mask
volatile uint32_t hctsiz; // 510 + 20*ch Host Channel Transfer Size
volatile uint32_t hcdma; // 514 + 20*ch Host Channel DMA Address
uint32_t reserved518; // 518 + 20*ch
volatile uint32_t hcdmab; // 51C + 20*ch Host Channel DMA Address
union {
volatile uint32_t hcchar; // 500 + 20*ch Host Channel Characteristics
volatile dwc2_channel_char_t hcchar_bm;
};
union {
volatile uint32_t hcsplt; // 504 + 20*ch Host Channel Split Control
volatile dwc2_channel_split_t hcsplt_bm;
};
volatile uint32_t hcint; // 508 + 20*ch Host Channel Interrupt
volatile uint32_t hcintmsk; // 50C + 20*ch Host Channel Interrupt Mask
union {
volatile uint32_t hctsiz; // 510 + 20*ch Host Channel Transfer Size
volatile dwc2_channel_tsize_t hctsiz_bm;
};
volatile uint32_t hcdma; // 514 + 20*ch Host Channel DMA Address
uint32_t reserved518; // 518 + 20*ch
volatile uint32_t hcdmab; // 51C + 20*ch Host Channel DMA Address
} dwc2_channel_t;
//--------------------------------------------------------------------
// Device Register Bitfield
//--------------------------------------------------------------------
typedef struct TU_ATTR_PACKED {
uint32_t xfer_size : 19; // 0..18 Transfer size in bytes
uint32_t packet_count : 10; // 19..28 Number of packets
uint32_t mc_pid : 2; // 29..30 IN: Multi Count, OUT: PID
} dwc2_ep_tsize_t;
TU_VERIFY_STATIC(sizeof(dwc2_ep_tsize_t) == 4, "incorrect size");
// Endpoint IN
typedef struct {
volatile uint32_t diepctl; // 900 + 20*ep Device IN Endpoint Control
uint32_t reserved04; // 904
volatile uint32_t diepint; // 908 + 20*ep Device IN Endpoint Interrupt
uint32_t reserved0c; // 90C
volatile uint32_t dieptsiz; // 910 + 20*ep Device IN Endpoint Transfer Size
volatile uint32_t diepdma; // 914 + 20*ep Device IN Endpoint DMA Address
volatile uint32_t dtxfsts; // 918 + 20*ep Device IN Endpoint Tx FIFO Status
uint32_t reserved1c; // 91C
volatile uint32_t diepctl; // 900 + 20*ep Device IN Endpoint Control
uint32_t reserved04; // 904
volatile uint32_t diepint; // 908 + 20*ep Device IN Endpoint Interrupt
uint32_t reserved0c; // 90C
union {
volatile uint32_t dieptsiz; // 910 + 20*ep Device IN Endpoint Transfer Size
volatile dwc2_ep_tsize_t dieptsiz_bm;
};
volatile uint32_t diepdma; // 914 + 20*ep Device IN Endpoint DMA Address
volatile uint32_t dtxfsts; // 918 + 20*ep Device IN Endpoint Tx FIFO Status
uint32_t reserved1c; // 91C
} dwc2_epin_t;
// Endpoint OUT
typedef struct {
volatile uint32_t doepctl; // B00 + 20*ep Device OUT Endpoint Control
uint32_t reserved04; // B04
volatile uint32_t doepint; // B08 + 20*ep Device OUT Endpoint Interrupt
uint32_t reserved0c; // B0C
volatile uint32_t doeptsiz; // B10 + 20*ep Device OUT Endpoint Transfer Size
volatile uint32_t doepdma; // B14 + 20*ep Device OUT Endpoint DMA Address
uint32_t reserved18[2]; // B18..B1C
volatile uint32_t doepctl; // B00 + 20*ep Device OUT Endpoint Control
uint32_t reserved04; // B04
volatile uint32_t doepint; // B08 + 20*ep Device OUT Endpoint Interrupt
uint32_t reserved0c; // B0C
union {
volatile uint32_t doeptsiz; // B10 + 20*ep Device OUT Endpoint Transfer Size
volatile dwc2_ep_tsize_t doeptsiz_bm;
};
volatile uint32_t doepdma; // B14 + 20*ep Device OUT Endpoint DMA Address
uint32_t reserved18[2]; // B18..B1C
} dwc2_epout_t;
// Universal Endpoint
typedef struct {
union {
volatile uint32_t diepctl;
@@ -351,6 +520,7 @@ typedef struct {
union {
volatile uint32_t dieptsiz;
volatile uint32_t doeptsiz;
volatile dwc2_ep_tsize_t deptsiz_bm;
};
union {
volatile uint32_t diepdma;
@@ -367,21 +537,43 @@ TU_VERIFY_STATIC(sizeof(dwc2_dep_t) == 0x20, "incorrect size");
//--------------------------------------------------------------------
typedef struct {
//------------- Core Global -------------//
union {
volatile uint32_t gotgctl; // 000 OTG Control and Status
volatile dwc2_gotgctl_t gotgctl_bm;
};
union {
volatile uint32_t gotgint; // 004 OTG Interrupt
volatile dwc2_gotgint_t gotgint_bm;
};
union {
volatile uint32_t gahbcfg; // 008 AHB Configuration
volatile dwc2_gahbcfg_t gahbcfg_bm;
};
union {
volatile uint32_t gusbcfg; // 00c USB Configuration
volatile dwc2_gusbcfg_t gusbcfg_bm;
};
union {
volatile uint32_t grstctl; // 010 Reset
volatile dwc2_grstctl_t grstctl_bm;
};
volatile uint32_t gintsts; // 014 Interrupt
volatile uint32_t gintmsk; // 018 Interrupt Mask
volatile uint32_t grxstsr; // 01c Receive Status Debug Read
union {
volatile uint32_t grxstsp; // 020 Receive Status Read/Pop
volatile dwc2_grxstsp_t grxstsp_bm;
};
volatile uint32_t grxfsiz; // 024 Receive FIFO Size
union {
volatile uint32_t dieptxf0; // 028 EP0 Tx FIFO Size
volatile uint32_t gnptxfsiz; // 028 Non-periodic Transmit FIFO Size
};
volatile uint32_t gnptxsts; // 02c Non-periodic Transmit FIFO/Queue Status
union {
volatile uint32_t hnptxsts; // 02c Non-periodic Transmit FIFO/Queue Status
volatile dwc2_hnptxsts_t hnptxsts_bm;
volatile uint32_t gnptxsts;
};
volatile uint32_t gi2cctl; // 030 I2C Address
volatile uint32_t gpvndctl; // 034 PHY Vendor Control
union {
@@ -415,14 +607,23 @@ typedef struct {
//------------ Host -------------//
volatile uint32_t hcfg; // 400 Host Configuration
volatile uint32_t hfir; // 404 Host Frame Interval
union {
volatile uint32_t hfnum; // 408 Host Frame Number / Frame Remaining
volatile dwc2_hfnum_t hfnum_bm;
};
uint32_t reserved40c; // 40C
union {
volatile uint32_t hptxsts; // 410 Host Periodic TX FIFO / Queue Status
volatile dwc2_hptxsts_t hptxsts_bm;
};
volatile uint32_t haint; // 414 Host All Channels Interrupt
volatile uint32_t haintmsk; // 418 Host All Channels Interrupt Mask
volatile uint32_t hflbaddr; // 41C Host Frame List Base Address
uint32_t reserved420[8]; // 420..43F
union {
volatile uint32_t hprt; // 440 Host Port Control and Status
volatile dwc2_hprt_t hprt_bm;
};
uint32_t reserved444[47]; // 444..4FF
//------------- Host Channel -------------//
@@ -464,8 +665,8 @@ typedef struct {
uint32_t reservedd00[64]; // D00..DFF
//------------- Power Clock -------------//
volatile uint32_t pcgctl; // E00 Power and Clock Gating Control
volatile uint32_t pcgctl1; // E04
volatile uint32_t pcgcctl; // E00 Power and Clock Gating Characteristic Control
volatile uint32_t pcgcctl1; // E04 Power and Clock Gating Characteristic Control 1
uint32_t reservede08[126]; // E08..FFF
//------------- FIFOs -------------//
@@ -478,7 +679,7 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, channel) == 0x0500, "incorrect size");
TU_VERIFY_STATIC(offsetof(dwc2_regs_t, dcfg ) == 0x0800, "incorrect size");
TU_VERIFY_STATIC(offsetof(dwc2_regs_t, epin ) == 0x0900, "incorrect size");
TU_VERIFY_STATIC(offsetof(dwc2_regs_t, epout ) == 0x0B00, "incorrect size");
TU_VERIFY_STATIC(offsetof(dwc2_regs_t, pcgctl ) == 0x0E00, "incorrect size");
TU_VERIFY_STATIC(offsetof(dwc2_regs_t, pcgcctl) == 0x0E00, "incorrect size");
TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
//--------------------------------------------------------------------+
@@ -542,14 +743,16 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define GOTGCTL_OTGVER GOTGCTL_OTGVER_Msk // OTG version
/******************** Bit definition for HCFG register ********************/
#define HCFG_FSLSPCS_Pos (0U)
#define HCFG_FSLSPCS_Msk (0x3UL << HCFG_FSLSPCS_Pos) // 0x00000003
#define HCFG_FSLSPCS HCFG_FSLSPCS_Msk // FS/LS PHY clock select
#define HCFG_FSLSPCS_0 (0x1UL << HCFG_FSLSPCS_Pos) // 0x00000001
#define HCFG_FSLSPCS_1 (0x2UL << HCFG_FSLSPCS_Pos) // 0x00000002
#define HCFG_FSLSS_Pos (2U)
#define HCFG_FSLSS_Msk (0x1UL << HCFG_FSLSS_Pos) // 0x00000004
#define HCFG_FSLSS HCFG_FSLSS_Msk // FS- and LS-only support
#define HCFG_FSLS_PHYCLK_SEL_Pos (0U)
#define HCFG_FSLS_PHYCLK_SEL_Msk (0x3UL << HCFG_FSLS_PHYCLK_SEL_Pos) // 0x00000003
#define HCFG_FSLS_PHYCLK_SEL HCFG_FSLS_PHYCLK_SEL_Msk // FS/LS PHY clock select
#define HCFG_FSLS_PHYCLK_SEL_30_60MHZ (0x0UL << HCFG_FSLS_PHYCLK_SEL_Pos) // 0x00000000
#define HCFG_FSLS_PHYCLK_SEL_48MHZ (0x1UL << HCFG_FSLS_PHYCLK_SEL_Pos) // 0x00000001
#define HCFG_FSLS_PHYCLK_SEL_6MHZ (0x2UL << HCFG_FSLS_PHYCLK_SEL_Pos) // 0x00000002
#define HCFG_FSLS_ONLY_Pos (2U)
#define HCFG_FSLS_ONLY_Msk (0x1UL << HCFG_FSLS_ONLY_Pos) // 0x00000004
#define HCFG_FSLS_ONLY HCFG_FSLS_ONLY_Msk // FS- and LS-only support
/******************** Bit definition for PCGCR register ********************/
#define PCGCR_STPPCLK_Pos (0U)
@@ -664,6 +867,9 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define HFIR_FRIVL_Pos (0U)
#define HFIR_FRIVL_Msk (0xFFFFUL << HFIR_FRIVL_Pos) // 0x0000FFFF
#define HFIR_FRIVL HFIR_FRIVL_Msk // Frame interval
#define HFIR_RELOAD_CTRL_Pos (16U) // available since v2.92a
#define HFIR_RELOAD_CTRL_Msk (0x1UL << HFIR_RELOAD_CTRL_Pos)
#define HFIR_RELOAD_CTRL HFIR_RELOAD_CTRL_Msk
/******************** Bit definition for HFNUM register ********************/
#define HFNUM_FRNUM_Pos (0U)
@@ -708,19 +914,17 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define GAHBCFG_DMAEN_Pos (5U)
#define GAHBCFG_DMAEN_Msk (0x1UL << GAHBCFG_DMAEN_Pos) // 0x00000020
#define GAHBCFG_DMAEN GAHBCFG_DMAEN_Msk // DMA enable
#define GAHBCFG_TXFELVL_Pos (7U)
#define GAHBCFG_TXFELVL_Msk (0x1UL << GAHBCFG_TXFELVL_Pos) // 0x00000080
#define GAHBCFG_TXFELVL GAHBCFG_TXFELVL_Msk // TxFIFO empty level
#define GAHBCFG_PTXFELVL_Pos (8U)
#define GAHBCFG_PTXFELVL_Msk (0x1UL << GAHBCFG_PTXFELVL_Pos) // 0x00000100
#define GAHBCFG_PTXFELVL GAHBCFG_PTXFELVL_Msk // Periodic TxFIFO empty level
#define GSNPSID_ID_MASK TU_GENMASK(31, 16)
#define GAHBCFG_TX_FIFO_EPMTY_LVL_Pos (7U)
#define GAHBCFG_TX_FIFO_EPMTY_LVL_Msk (0x1UL << GAHBCFG_TX_FIFO_EPMTY_LVL_Pos) // 0x00000080
#define GAHBCFG_TX_FIFO_EPMTY_LVL GAHBCFG_TX_FIFO_EPMTY_LVL_Msk // TxFIFO empty level
#define GAHBCFG_PTX_FIFO_EPMTY_LVL_Pos (8U)
#define GAHBCFG_PTX_FIFO_EPMTY_LVL_Msk (0x1UL << GAHBCFG_PTX_FIFO_EPMTY_LVL_Pos) // 0x00000100
#define GAHBCFG_PTX_FIFO_EPMTY_LVL GAHBCFG_PTX_FIFO_EPMTY_LVL_Msk // Periodic TxFIFO empty level
/******************** Bit definition for GUSBCFG register ********************/
#define GUSBCFG_TOCAL_Pos (0U)
#define GUSBCFG_TOCAL_Msk (0x7UL << GUSBCFG_TOCAL_Pos) // 0x00000007
#define GUSBCFG_TOCAL GUSBCFG_TOCAL_Msk // FS timeout calibration
#define GUSBCFG_TOCAL GUSBCFG_TOCAL_Msk // HS/FS timeout calibration
#define GUSBCFG_PHYIF16_Pos (3U)
#define GUSBCFG_PHYIF16_Msk (0x1UL << GUSBCFG_PHYIF16_Pos) // 0x00000008
#define GUSBCFG_PHYIF16 GUSBCFG_PHYIF16_Msk // PHY Interface (PHYIf)
@@ -804,8 +1008,8 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define GRSTCTL_TXFNUM_2 (0x04UL << GRSTCTL_TXFNUM_Pos) // 0x00000100
#define GRSTCTL_TXFNUM_3 (0x08UL << GRSTCTL_TXFNUM_Pos) // 0x00000200
#define GRSTCTL_TXFNUM_4 (0x10UL << GRSTCTL_TXFNUM_Pos) // 0x00000400
#define GRSTCTL_CSFTRST_DONE_Pos (29)
#define GRSTCTL_CSFTRST_DONE (1u << GRSTCTL_CSFTRST_DONE_Pos) // Reset Done, only available from v4.20a
#define GRSTCTL_CSRST_DONE_Pos (29)
#define GRSTCTL_CSRST_DONE (1u << GRSTCTL_CSRST_DONE_Pos) // Reset Done, only available from v4.20a
#define GRSTCTL_DMAREQ_Pos (30U)
#define GRSTCTL_DMAREQ_Msk (0x1UL << GRSTCTL_DMAREQ_Pos) // 0x40000000
#define GRSTCTL_DMAREQ GRSTCTL_DMAREQ_Msk // DMA request signal
@@ -926,9 +1130,9 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define GINTSTS_RXFLVL_Pos (4U)
#define GINTSTS_RXFLVL_Msk (0x1UL << GINTSTS_RXFLVL_Pos) // 0x00000010
#define GINTSTS_RXFLVL GINTSTS_RXFLVL_Msk // RxFIFO nonempty
#define GINTSTS_NPTXFE_Pos (5U)
#define GINTSTS_NPTXFE_Msk (0x1UL << GINTSTS_NPTXFE_Pos) // 0x00000020
#define GINTSTS_NPTXFE GINTSTS_NPTXFE_Msk // Nonperiodic TxFIFO empty
#define GINTSTS_NPTX_FIFO_EMPTY_Pos (5U)
#define GINTSTS_NPTX_FIFO_EMPTY_Msk (0x1UL << GINTSTS_NPTX_FIFO_EMPTY_Pos) // 0x00000020
#define GINTSTS_NPTX_FIFO_EMPTY GINTSTS_NPTX_FIFO_EMPTY_Msk // Nonperiodic TxFIFO empty
#define GINTSTS_GINAKEFF_Pos (6U)
#define GINTSTS_GINAKEFF_Msk (0x1UL << GINTSTS_GINAKEFF_Pos) // 0x00000040
#define GINTSTS_GINAKEFF GINTSTS_GINAKEFF_Msk // Global IN nonperiodic NAK effective
@@ -977,15 +1181,15 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define GINTSTS_HCINT_Pos (25U)
#define GINTSTS_HCINT_Msk (0x1UL << GINTSTS_HCINT_Pos) // 0x02000000
#define GINTSTS_HCINT GINTSTS_HCINT_Msk // Host channels interrupt
#define GINTSTS_PTXFE_Pos (26U)
#define GINTSTS_PTXFE_Msk (0x1UL << GINTSTS_PTXFE_Pos) // 0x04000000
#define GINTSTS_PTXFE GINTSTS_PTXFE_Msk // Periodic TxFIFO empty
#define GINTSTS_PTX_FIFO_EMPTY_Pos (26U)
#define GINTSTS_PTX_FIFO_EMPTY_Msk (0x1UL << GINTSTS_PTX_FIFO_EMPTY_Pos) // 0x04000000
#define GINTSTS_PTX_FIFO_EMPTY GINTSTS_PTX_FIFO_EMPTY_Msk // Periodic TxFIFO empty
#define GINTSTS_LPMINT_Pos (27U)
#define GINTSTS_LPMINT_Msk (0x1UL << GINTSTS_LPMINT_Pos) // 0x08000000
#define GINTSTS_LPMINT GINTSTS_LPMINT_Msk // LPM interrupt
#define GINTSTS_CIDSCHG_Pos (28U)
#define GINTSTS_CIDSCHG_Msk (0x1UL << GINTSTS_CIDSCHG_Pos) // 0x10000000
#define GINTSTS_CIDSCHG GINTSTS_CIDSCHG_Msk // Connector ID status change
#define GINTSTS_CONIDSTSCHNG_Pos (28U)
#define GINTSTS_CONIDSTSCHNG_Msk (0x1UL << GINTSTS_CONIDSTSCHNG_Pos) // 0x10000000
#define GINTSTS_CONIDSTSCHNG GINTSTS_CONIDSTSCHNG_Msk // Connector ID status change
#define GINTSTS_DISCINT_Pos (29U)
#define GINTSTS_DISCINT_Msk (0x1UL << GINTSTS_DISCINT_Pos) // 0x20000000
#define GINTSTS_DISCINT GINTSTS_DISCINT_Msk // Disconnect detected interrupt
@@ -1069,9 +1273,9 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define GINTMSK_LPMINTM_Pos (27U)
#define GINTMSK_LPMINTM_Msk (0x1UL << GINTMSK_LPMINTM_Pos) // 0x08000000
#define GINTMSK_LPMINTM GINTMSK_LPMINTM_Msk // LPM interrupt Mask
#define GINTMSK_CIDSCHGM_Pos (28U)
#define GINTMSK_CIDSCHGM_Msk (0x1UL << GINTMSK_CIDSCHGM_Pos) // 0x10000000
#define GINTMSK_CIDSCHGM GINTMSK_CIDSCHGM_Msk // Connector ID status change mask
#define GINTMSK_CONIDSTSCHNGM_Pos (28U)
#define GINTMSK_CONIDSTSCHNGM_Msk (0x1UL << GINTMSK_CONIDSTSCHNGM_Pos) // 0x10000000
#define GINTMSK_CONIDSTSCHNGM GINTMSK_CONIDSTSCHNGM_Msk // Connector ID status change mask
#define GINTMSK_DISCINT_Pos (29U)
#define GINTMSK_DISCINT_Msk (0x1UL << GINTMSK_DISCINT_Pos) // 0x20000000
#define GINTMSK_DISCINT GINTMSK_DISCINT_Msk // Disconnect detected interrupt mask
@@ -1109,17 +1313,6 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define GRXSTSP_PKTSTS_Msk (0xFUL << GRXSTSP_PKTSTS_Pos) // 0x001E0000
#define GRXSTSP_PKTSTS GRXSTSP_PKTSTS_Msk // OUT EP interrupt mask bits
#define GRXSTS_PKTSTS_GLOBALOUTNAK 1
#define GRXSTS_PKTSTS_OUTRX 2
#define GRXSTS_PKTSTS_HCHIN 2
#define GRXSTS_PKTSTS_OUTDONE 3
#define GRXSTS_PKTSTS_HCHIN_XFER_COMP 3
#define GRXSTS_PKTSTS_SETUPDONE 4
#define GRXSTS_PKTSTS_DATATOGGLEERR 5
#define GRXSTS_PKTSTS_SETUPRX 6
#define GRXSTS_PKTSTS_HCHHALTED 7
/******************** Bit definition for DAINTMSK register ********************/
#define DAINTMSK_IEPM_Pos (0U)
#define DAINTMSK_IEPM_Msk (0xFFFFUL << DAINTMSK_IEPM_Pos) // 0x0000FFFF
@@ -1448,56 +1641,53 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define DIEPEACHMSK1_NAKM DIEPEACHMSK1_NAKM_Msk // NAK interrupt mask
/******************** Bit definition for HPRT register ********************/
#define HPRT_PCSTS_Pos (0U)
#define HPRT_PCSTS_Msk (0x1UL << HPRT_PCSTS_Pos) // 0x00000001
#define HPRT_PCSTS HPRT_PCSTS_Msk // Port connect status
#define HPRT_PCDET_Pos (1U)
#define HPRT_PCDET_Msk (0x1UL << HPRT_PCDET_Pos) // 0x00000002
#define HPRT_PCDET HPRT_PCDET_Msk // Port connect detected
#define HPRT_PENA_Pos (2U)
#define HPRT_PENA_Msk (0x1UL << HPRT_PENA_Pos) // 0x00000004
#define HPRT_PENA HPRT_PENA_Msk // Port enable
#define HPRT_PENCHNG_Pos (3U)
#define HPRT_PENCHNG_Msk (0x1UL << HPRT_PENCHNG_Pos) // 0x00000008
#define HPRT_PENCHNG HPRT_PENCHNG_Msk // Port enable/disable change
#define HPRT_POCA_Pos (4U)
#define HPRT_POCA_Msk (0x1UL << HPRT_POCA_Pos) // 0x00000010
#define HPRT_POCA HPRT_POCA_Msk // Port overcurrent active
#define HPRT_POCCHNG_Pos (5U)
#define HPRT_POCCHNG_Msk (0x1UL << HPRT_POCCHNG_Pos) // 0x00000020
#define HPRT_POCCHNG HPRT_POCCHNG_Msk // Port overcurrent change
#define HPRT_PRES_Pos (6U)
#define HPRT_PRES_Msk (0x1UL << HPRT_PRES_Pos) // 0x00000040
#define HPRT_PRES HPRT_PRES_Msk // Port resume
#define HPRT_PSUSP_Pos (7U)
#define HPRT_PSUSP_Msk (0x1UL << HPRT_PSUSP_Pos) // 0x00000080
#define HPRT_PSUSP HPRT_PSUSP_Msk // Port suspend
#define HPRT_PRST_Pos (8U)
#define HPRT_PRST_Msk (0x1UL << HPRT_PRST_Pos) // 0x00000100
#define HPRT_PRST HPRT_PRST_Msk // Port reset
#define HPRT_PLSTS_Pos (10U)
#define HPRT_PLSTS_Msk (0x3UL << HPRT_PLSTS_Pos) // 0x00000C00
#define HPRT_PLSTS HPRT_PLSTS_Msk // Port line status
#define HPRT_PLSTS_0 (0x1UL << HPRT_PLSTS_Pos) // 0x00000400
#define HPRT_PLSTS_1 (0x2UL << HPRT_PLSTS_Pos) // 0x00000800
#define HPRT_PPWR_Pos (12U)
#define HPRT_PPWR_Msk (0x1UL << HPRT_PPWR_Pos) // 0x00001000
#define HPRT_PPWR HPRT_PPWR_Msk // Port power
#define HPRT_PTCTL_Pos (13U)
#define HPRT_PTCTL_Msk (0xFUL << HPRT_PTCTL_Pos) // 0x0001E000
#define HPRT_PTCTL HPRT_PTCTL_Msk // Port test control
#define HPRT_PTCTL_0 (0x1UL << HPRT_PTCTL_Pos) // 0x00002000
#define HPRT_PTCTL_1 (0x2UL << HPRT_PTCTL_Pos) // 0x00004000
#define HPRT_PTCTL_2 (0x4UL << HPRT_PTCTL_Pos) // 0x00008000
#define HPRT_PTCTL_3 (0x8UL << HPRT_PTCTL_Pos) // 0x00010000
#define HPRT_PSPD_Pos (17U)
#define HPRT_PSPD_Msk (0x3UL << HPRT_PSPD_Pos) // 0x00060000
#define HPRT_PSPD HPRT_PSPD_Msk // Port speed
#define HPRT_PSPD_0 (0x1UL << HPRT_PSPD_Pos) // 0x00020000
#define HPRT_PSPD_1 (0x2UL << HPRT_PSPD_Pos) // 0x00040000
#define HPRT_CONN_STATUS_Pos (0U)
#define HPRT_CONN_STATUS_Msk (0x1UL << HPRT_CONN_STATUS_Pos) // 0x00000001
#define HPRT_CONN_STATUS HPRT_CONN_STATUS_Msk // Port connect status
#define HPRT_CONN_DETECT_Pos (1U)
#define HPRT_CONN_DETECT_Msk (0x1UL << HPRT_CONN_DETECT_Pos) // 0x00000002
#define HPRT_CONN_DETECT HPRT_CONN_DETECT_Msk // Port connect detected
#define HPRT_ENABLE_Pos (2U)
#define HPRT_ENABLE_Msk (0x1UL << HPRT_ENABLE_Pos) // 0x00000004
#define HPRT_ENABLE HPRT_ENABLE_Msk // Port enable
#define HPRT_ENABLE_CHANGE_Pos (3U)
#define HPRT_ENABLE_CHANGE_Msk (0x1UL << HPRT_ENABLE_CHANGE_Pos) // 0x00000008
#define HPRT_ENABLE_CHANGE HPRT_ENABLE_CHANGE_Msk // Port enable/disable change
#define HPRT_OVER_CURRENT_ACTIVE_Pos (4U)
#define HPRT_OVER_CURRENT_ACTIVE_Msk (0x1UL << HPRT_OVER_CURRENT_ACTIVE_Pos) // 0x00000010
#define HPRT_OVER_CURRENT_ACTIVE HPRT_OVER_CURRENT_ACTIVE_Msk // Port overcurrent active
#define HPRT_OVER_CURRENT_CHANGE_Pos (5U)
#define HPRT_OVER_CURRENT_CHANGE_Msk (0x1UL << HPRT_OVER_CURRENT_CHANGE_Pos) // 0x00000020
#define HPRT_OVER_CURRENT_CHANGE HPRT_OVER_CURRENT_CHANGE_Msk // Port overcurrent change
#define HPRT_RESUME_Pos (6U)
#define HPRT_RESUME_Msk (0x1UL << HPRT_RESUME_Pos) // 0x00000040
#define HPRT_RESUME HPRT_RESUME_Msk // Port resume
#define HPRT_SUSPEND_Pos (7U)
#define HPRT_SUSPEND_Msk (0x1UL << HPRT_SUSPEND_Pos) // 0x00000080
#define HPRT_SUSPEND HPRT_SUSPEND_Msk // Port suspend
#define HPRT_RESET_Pos (8U)
#define HPRT_RESET_Msk (0x1UL << HPRT_RESET_Pos) // 0x00000100
#define HPRT_RESET HPRT_RESET_Msk // Port reset
#define HPRT_LINE_STATUS_Pos (10U)
#define HPRT_LINE_STATUS_Msk (0x3UL << HPRT_LINE_STATUS_Pos) // 0x00000C00
#define HPRT_LINE_STATUS HPRT_LINE_STATUS_Msk // Port line status
#define HPRT_LINE_STATUS_0 (0x1UL << HPRT_LINE_STATUS_Pos) // 0x00000400
#define HPRT_LINE_STATUS_1 (0x2UL << HPRT_LINE_STATUS_Pos) // 0x00000800
#define HPRT_POWER_Pos (12U)
#define HPRT_POWER_Msk (0x1UL << HPRT_POWER_Pos) // 0x00001000
#define HPRT_POWER HPRT_POWER_Msk // Port power
#define HPRT_TEST_CONTROL_Pos (13U)
#define HPRT_TEST_CONTROL_Msk (0xFUL << HPRT_TEST_CONTROL_Pos) // 0x0001E000
#define HPRT_TEST_CONTROL HPRT_TEST_CONTROL_Msk // Port test control
#define HPRT_TEST_CONTROL_0 (0x1UL << HPRT_TEST_CONTROL_Pos) // 0x00002000
#define HPRT_TEST_CONTROL_1 (0x2UL << HPRT_TEST_CONTROL_Pos) // 0x00004000
#define HPRT_TEST_CONTROL_2 (0x4UL << HPRT_TEST_CONTROL_Pos) // 0x00008000
#define HPRT_TEST_CONTROL_3 (0x8UL << HPRT_TEST_CONTROL_Pos) // 0x00010000
#define HPRT_SPEED_Pos (17U)
#define HPRT_SPEED_Msk (0x3UL << HPRT_SPEED_Pos) // 0x00060000
#define HPRT_SPEED HPRT_SPEED_Msk // Port speed
#define HPRT_SPEED_0 (0x1UL << HPRT_SPEED_Pos) // 0x00020000
#define HPRT_SPEED_1 (0x2UL << HPRT_SPEED_Pos) // 0x00040000
/******************** Bit definition for DOEPEACHMSK1 register ********************/
#define DOEPEACHMSK1_XFRCM_Pos (0U)
@@ -1679,15 +1869,15 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define HCSPLT_SPLITEN HCSPLT_SPLITEN_Msk // Split enable
/******************** Bit definition for HCINT register ********************/
#define HCINT_XFRC_Pos (0U)
#define HCINT_XFRC_Msk (0x1UL << HCINT_XFRC_Pos) // 0x00000001
#define HCINT_XFRC HCINT_XFRC_Msk // Transfer completed
#define HCINT_CHH_Pos (1U)
#define HCINT_CHH_Msk (0x1UL << HCINT_CHH_Pos) // 0x00000002
#define HCINT_CHH HCINT_CHH_Msk // Channel halted
#define HCINT_AHBERR_Pos (2U)
#define HCINT_AHBERR_Msk (0x1UL << HCINT_AHBERR_Pos) // 0x00000004
#define HCINT_AHBERR HCINT_AHBERR_Msk // AHB error
#define HCINT_XFER_COMPLETE_Pos (0U)
#define HCINT_XFER_COMPLETE_Msk (0x1UL << HCINT_XFER_COMPLETE_Pos) // 0x00000001
#define HCINT_XFER_COMPLETE HCINT_XFER_COMPLETE_Msk // Transfer completed
#define HCINT_HALTED_Pos (1U)
#define HCINT_HALTED_Msk (0x1UL << HCINT_HALTED_Pos) // 0x00000002
#define HCINT_HALTED HCINT_HALTED_Msk // Channel halted
#define HCINT_AHB_ERR_Pos (2U)
#define HCINT_AHB_ERR_Msk (0x1UL << HCINT_AHB_ERR_Pos) // 0x00000004
#define HCINT_AHB_ERR HCINT_AHB_ERR_Msk // AHB error
#define HCINT_STALL_Pos (3U)
#define HCINT_STALL_Msk (0x1UL << HCINT_STALL_Pos) // 0x00000008
#define HCINT_STALL HCINT_STALL_Msk // STALL response received interrupt
@@ -1700,18 +1890,27 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define HCINT_NYET_Pos (6U)
#define HCINT_NYET_Msk (0x1UL << HCINT_NYET_Pos) // 0x00000040
#define HCINT_NYET HCINT_NYET_Msk // Response received interrupt
#define HCINT_TXERR_Pos (7U)
#define HCINT_TXERR_Msk (0x1UL << HCINT_TXERR_Pos) // 0x00000080
#define HCINT_TXERR HCINT_TXERR_Msk // Transaction error
#define HCINT_BBERR_Pos (8U)
#define HCINT_BBERR_Msk (0x1UL << HCINT_BBERR_Pos) // 0x00000100
#define HCINT_BBERR HCINT_BBERR_Msk // Babble error
#define HCINT_FRMOR_Pos (9U)
#define HCINT_FRMOR_Msk (0x1UL << HCINT_FRMOR_Pos) // 0x00000200
#define HCINT_FRMOR HCINT_FRMOR_Msk // Frame overrun
#define HCINT_DTERR_Pos (10U)
#define HCINT_DTERR_Msk (0x1UL << HCINT_DTERR_Pos) // 0x00000400
#define HCINT_DTERR HCINT_DTERR_Msk // Data toggle error
#define HCINT_XACT_ERR_Pos (7U)
#define HCINT_XACT_ERR_Msk (0x1UL << HCINT_XACT_ERR_Pos) // 0x00000080
#define HCINT_XACT_ERR HCINT_XACT_ERR_Msk // Transaction error
#define HCINT_BABBLE_ERR_Pos (8U)
#define HCINT_BABBLE_ERR_Msk (0x1UL << HCINT_BABBLE_ERR_Pos) // 0x00000100
#define HCINT_BABBLE_ERR HCINT_BABBLE_ERR_Msk // Babble error
#define HCINT_FARME_OVERRUN_Pos (9U)
#define HCINT_FARME_OVERRUN_Msk (0x1UL << HCINT_FARME_OVERRUN_Pos) // 0x00000200
#define HCINT_FARME_OVERRUN HCINT_FARME_OVERRUN_Msk // Frame overrun
#define HCINT_DATATOGGLE_ERR_Pos (10U)
#define HCINT_DATATOGGLE_ERR_Msk (0x1UL << HCINT_DATATOGGLE_ERR_Pos) // 0x00000400
#define HCINT_DATATOGGLE_ERR HCINT_DATATOGGLE_ERR_Msk // Data toggle error
#define HCINT_BUFFER_NA_Pos (11U)
#define HCINT_BUFFER_NA_Msk (0x1UL << HCINT_BUFFER_NA_Pos) // 0x00000800
#define HCINT_BUFFER_NA HCINT_BUFFER_NA_Msk // Buffer not available interrupt
#define HCINT_XCS_XACT_ERR_Pos (12U)
#define HCINT_XCS_XACT_ERR_Msk (0x1UL << HCINT_XCS_XACT_ERR_Pos) // 0x00001000
#define HCINT_XCS_XACT_ERR HCINT_XCS_XACT_ERR_Msk // Excessive transaction error
#define HCINT_DESC_ROLLOVER_Pos (13U)
#define HCINT_DESC_ROLLOVER_Msk (0x1UL << HCINT_DESC_ROLLOVER_Pos) // 0x00002000
#define HCINT_DESC_ROLLOVER HCINT_DESC_ROLLOVER_Msk // Descriptor rollover
/******************** Bit definition for DIEPINT register ********************/
#define DIEPINT_XFRC_Pos (0U)
@@ -1754,41 +1953,6 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define DIEPINT_NAK_Msk (0x1UL << DIEPINT_NAK_Pos) // 0x00002000
#define DIEPINT_NAK DIEPINT_NAK_Msk // NAK interrupt
/******************** Bit definition for HCINTMSK register ********************/
#define HCINTMSK_XFRCM_Pos (0U)
#define HCINTMSK_XFRCM_Msk (0x1UL << HCINTMSK_XFRCM_Pos) // 0x00000001
#define HCINTMSK_XFRCM HCINTMSK_XFRCM_Msk // Transfer completed mask
#define HCINTMSK_CHHM_Pos (1U)
#define HCINTMSK_CHHM_Msk (0x1UL << HCINTMSK_CHHM_Pos) // 0x00000002
#define HCINTMSK_CHHM HCINTMSK_CHHM_Msk // Channel halted mask
#define HCINTMSK_AHBERR_Pos (2U)
#define HCINTMSK_AHBERR_Msk (0x1UL << HCINTMSK_AHBERR_Pos) // 0x00000004
#define HCINTMSK_AHBERR HCINTMSK_AHBERR_Msk // AHB error
#define HCINTMSK_STALLM_Pos (3U)
#define HCINTMSK_STALLM_Msk (0x1UL << HCINTMSK_STALLM_Pos) // 0x00000008
#define HCINTMSK_STALLM HCINTMSK_STALLM_Msk // STALL response received interrupt mask
#define HCINTMSK_NAKM_Pos (4U)
#define HCINTMSK_NAKM_Msk (0x1UL << HCINTMSK_NAKM_Pos) // 0x00000010
#define HCINTMSK_NAKM HCINTMSK_NAKM_Msk // NAK response received interrupt mask
#define HCINTMSK_ACKM_Pos (5U)
#define HCINTMSK_ACKM_Msk (0x1UL << HCINTMSK_ACKM_Pos) // 0x00000020
#define HCINTMSK_ACKM HCINTMSK_ACKM_Msk // ACK response received/transmitted interrupt mask
#define HCINTMSK_NYET_Pos (6U)
#define HCINTMSK_NYET_Msk (0x1UL << HCINTMSK_NYET_Pos) // 0x00000040
#define HCINTMSK_NYET HCINTMSK_NYET_Msk // response received interrupt mask
#define HCINTMSK_TXERRM_Pos (7U)
#define HCINTMSK_TXERRM_Msk (0x1UL << HCINTMSK_TXERRM_Pos) // 0x00000080
#define HCINTMSK_TXERRM HCINTMSK_TXERRM_Msk // Transaction error mask
#define HCINTMSK_BBERRM_Pos (8U)
#define HCINTMSK_BBERRM_Msk (0x1UL << HCINTMSK_BBERRM_Pos) // 0x00000100
#define HCINTMSK_BBERRM HCINTMSK_BBERRM_Msk // Babble error mask
#define HCINTMSK_FRMORM_Pos (9U)
#define HCINTMSK_FRMORM_Msk (0x1UL << HCINTMSK_FRMORM_Pos) // 0x00000200
#define HCINTMSK_FRMORM HCINTMSK_FRMORM_Msk // Frame overrun mask
#define HCINTMSK_DTERRM_Pos (10U)
#define HCINTMSK_DTERRM_Msk (0x1UL << HCINTMSK_DTERRM_Pos) // 0x00000400
#define HCINTMSK_DTERRM HCINTMSK_DTERRM_Msk // Data toggle error mask
/******************** Bit definition for DIEPTSIZ register ********************/
#define DIEPTSIZ_XFRSIZ_Pos (0U)
@@ -1810,11 +1974,9 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define HCTSIZ_DOPING_Pos (31U)
#define HCTSIZ_DOPING_Msk (0x1UL << HCTSIZ_DOPING_Pos) // 0x80000000
#define HCTSIZ_DOPING HCTSIZ_DOPING_Msk // Do PING
#define HCTSIZ_DPID_Pos (29U)
#define HCTSIZ_DPID_Msk (0x3UL << HCTSIZ_DPID_Pos) // 0x60000000
#define HCTSIZ_DPID HCTSIZ_DPID_Msk // Data PID
#define HCTSIZ_DPID_0 (0x1UL << HCTSIZ_DPID_Pos) // 0x20000000
#define HCTSIZ_DPID_1 (0x2UL << HCTSIZ_DPID_Pos) // 0x40000000
#define HCTSIZ_PID_Pos (29U)
#define HCTSIZ_PID_Msk (0x3UL << HCTSIZ_PID_Pos) // 0x60000000
#define HCTSIZ_PID HCTSIZ_PID_Msk // Data PID
/******************** Bit definition for DIEPDMA register ********************/
#define DIEPDMA_DMAADDR_Pos (0U)
@@ -1973,32 +2135,32 @@ TU_VERIFY_STATIC(offsetof(dwc2_regs_t, fifo ) == 0x1000, "incorrect size");
#define DOEPTSIZ_STUPCNT_1 (0x2UL << DOEPTSIZ_STUPCNT_Pos) // 0x40000000
/******************** Bit definition for PCGCTL register ********************/
#define PCGCTL_IF_DEV_MODE TU_BIT(31)
#define PCGCTL_P2HD_PRT_SPD_MASK (0x3ul << 29)
#define PCGCTL_P2HD_PRT_SPD_SHIFT 29
#define PCGCTL_P2HD_DEV_ENUM_SPD_MASK (0x3ul << 27)
#define PCGCTL_P2HD_DEV_ENUM_SPD_SHIFT 27
#define PCGCTL_MAC_DEV_ADDR_MASK (0x7ful << 20)
#define PCGCTL_MAC_DEV_ADDR_SHIFT 20
#define PCGCTL_MAX_TERMSEL TU_BIT(19)
#define PCGCTL_MAX_XCVRSELECT_MASK (0x3ul << 17)
#define PCGCTL_MAX_XCVRSELECT_SHIFT 17
#define PCGCTL_PORT_POWER TU_BIT(16)
#define PCGCTL_PRT_CLK_SEL_MASK (0x3ul << 14)
#define PCGCTL_PRT_CLK_SEL_SHIFT 14
#define PCGCTL_ESS_REG_RESTORED TU_BIT(13)
#define PCGCTL_EXTND_HIBER_SWITCH TU_BIT(12)
#define PCGCTL_EXTND_HIBER_PWRCLMP TU_BIT(11)
#define PCGCTL_ENBL_EXTND_HIBER TU_BIT(10)
#define PCGCTL_RESTOREMODE TU_BIT(9)
#define PCGCTL_RESETAFTSUSP TU_BIT(8)
#define PCGCTL_DEEP_SLEEP TU_BIT(7)
#define PCGCTL_PHY_IN_SLEEP TU_BIT(6)
#define PCGCTL_ENBL_SLEEP_GATING TU_BIT(5)
#define PCGCTL_RSTPDWNMODULE TU_BIT(3)
#define PCGCTL_PWRCLMP TU_BIT(2)
#define PCGCTL_GATEHCLK TU_BIT(1)
#define PCGCTL_STOPPCLK TU_BIT(0)
#define PCGCCTL_IF_DEV_MODE TU_BIT(31)
#define PCGCCTL_P2HD_PRT_SPD_MASK (0x3ul << 29)
#define PCGCCTL_P2HD_PRT_SPD_SHIFT 29
#define PCGCCTL_P2HD_DEV_ENUM_SPD_MASK (0x3ul << 27)
#define PCGCCTL_P2HD_DEV_ENUM_SPD_SHIFT 27
#define PCGCCTL_MAC_DEV_ADDR_MASK (0x7ful << 20)
#define PCGCCTL_MAC_DEV_ADDR_SHIFT 20
#define PCGCCTL_MAX_TERMSEL TU_BIT(19)
#define PCGCCTL_MAX_XCVRSELECT_MASK (0x3ul << 17)
#define PCGCCTL_MAX_XCVRSELECT_SHIFT 17
#define PCGCCTL_PORT_POWER TU_BIT(16)
#define PCGCCTL_PRT_CLK_SEL_MASK (0x3ul << 14)
#define PCGCCTL_PRT_CLK_SEL_SHIFT 14
#define PCGCCTL_ESS_REG_RESTORED TU_BIT(13)
#define PCGCCTL_EXTND_HIBER_SWITCH TU_BIT(12)
#define PCGCCTL_EXTND_HIBER_PWRCLMP TU_BIT(11)
#define PCGCCTL_ENBL_EXTND_HIBER TU_BIT(10)
#define PCGCCTL_RESTOREMODE TU_BIT(9)
#define PCGCCTL_RESETAFTSUSP TU_BIT(8)
#define PCGCCTL_DEEP_SLEEP TU_BIT(7)
#define PCGCCTL_PHY_IN_SLEEP TU_BIT(6)
#define PCGCCTL_ENBL_SLEEP_GATING TU_BIT(5)
#define PCGCCTL_RSTPDWNMODULE TU_BIT(3)
#define PCGCCTL_PWRCLMP TU_BIT(2)
#define PCGCCTL_GATEHCLK TU_BIT(1)
#define PCGCCTL_STOPPCLK TU_BIT(0)
#define PCGCTL1_TIMER (0x3ul << 1)
#define PCGCTL1_GATEEN TU_BIT(0)

File diff suppressed because it is too large Load Diff

View File

@@ -39,14 +39,25 @@
#include "host/usbh_pvt.h"
#endif
#define TUP_USBIP_CONTROLLER_NUM 2
tusb_role_t _tusb_rhport_role[TUP_USBIP_CONTROLLER_NUM] = { TUSB_ROLE_INVALID };
static tusb_role_t _rhport_role[TUP_USBIP_CONTROLLER_NUM] = { TUSB_ROLE_INVALID };
//--------------------------------------------------------------------
// Weak/Default API, can be overwritten by Application
//--------------------------------------------------------------------
TU_ATTR_WEAK void tusb_time_delay_ms_api(uint32_t ms) {
#if CFG_TUSB_OS != OPT_OS_NONE
osal_task_delay(ms);
#else
// delay using millis() (if implemented) and/or frame number if possible
const uint32_t time_ms = tusb_time_millis_api();
while ((tusb_time_millis_api() - time_ms) < ms) {}
#endif
}
//--------------------------------------------------------------------+
// Public API
//--------------------------------------------------------------------+
bool tusb_rhport_init(uint8_t rhport, const tusb_rhport_init_t* rh_init) {
// backward compatible called with tusb_init(void)
#if defined(TUD_OPT_RHPORT) || defined(TUH_OPT_RHPORT)
@@ -57,8 +68,8 @@ bool tusb_rhport_init(uint8_t rhport, const tusb_rhport_init_t* rh_init) {
.role = TUSB_ROLE_DEVICE,
.speed = TUD_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL
};
TU_ASSERT ( tud_rhport_init(rhport, &dev_init) );
_rhport_role[TUD_OPT_RHPORT] = TUSB_ROLE_DEVICE;
TU_ASSERT ( tud_rhport_init(TUD_OPT_RHPORT, &dev_init) );
_tusb_rhport_role[TUD_OPT_RHPORT] = TUSB_ROLE_DEVICE;
#endif
#if CFG_TUH_ENABLED && defined(TUH_OPT_RHPORT)
@@ -68,7 +79,7 @@ bool tusb_rhport_init(uint8_t rhport, const tusb_rhport_init_t* rh_init) {
.speed = TUH_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL
};
TU_ASSERT( tuh_rhport_init(TUH_OPT_RHPORT, &host_init) );
_rhport_role[TUH_OPT_RHPORT] = TUSB_ROLE_HOST;
_tusb_rhport_role[TUH_OPT_RHPORT] = TUSB_ROLE_HOST;
#endif
return true;
@@ -77,6 +88,7 @@ bool tusb_rhport_init(uint8_t rhport, const tusb_rhport_init_t* rh_init) {
// new API with explicit rhport and role
TU_ASSERT(rhport < TUP_USBIP_CONTROLLER_NUM && rh_init->role != TUSB_ROLE_INVALID);
_tusb_rhport_role[rhport] = rh_init->role;
#if CFG_TUD_ENABLED
if (rh_init->role == TUSB_ROLE_DEVICE) {
@@ -90,7 +102,6 @@ bool tusb_rhport_init(uint8_t rhport, const tusb_rhport_init_t* rh_init) {
}
#endif
_rhport_role[rhport] = rh_init->role;
return true;
}
@@ -112,14 +123,14 @@ void tusb_int_handler(uint8_t rhport, bool in_isr) {
TU_VERIFY(rhport < TUP_USBIP_CONTROLLER_NUM,);
#if CFG_TUD_ENABLED
if (_rhport_role[rhport] == TUSB_ROLE_DEVICE) {
if (_tusb_rhport_role[rhport] == TUSB_ROLE_DEVICE) {
(void) in_isr;
dcd_int_handler(rhport);
}
#endif
#if CFG_TUH_ENABLED
if (_rhport_role[rhport] == TUSB_ROLE_HOST) {
if (_tusb_rhport_role[rhport] == TUSB_ROLE_HOST) {
hcd_int_handler(rhport, in_isr);
}
#endif

View File

@@ -127,10 +127,8 @@
//--------------------------------------------------------------------+
// APPLICATION API
// User API
//--------------------------------------------------------------------+
#if CFG_TUH_ENABLED || CFG_TUD_ENABLED
// Internal helper for backward compatible with tusb_init(void)
@@ -167,6 +165,15 @@ void tusb_int_handler(uint8_t rhport, bool in_isr);
#endif
//--------------------------------------------------------------------+
// API Implemented by user
//--------------------------------------------------------------------+
// Get current milliseconds, required by some port/configuration without RTOS
uint32_t tusb_time_millis_api(void);
// Delay in milliseconds, use tusb_time_millis_api() by default. required by some port/configuration with no RTOS
void tusb_time_delay_ms_api(uint32_t ms);
#ifdef __cplusplus
}

View File

@@ -125,7 +125,8 @@
#define OPT_MCU_ESP32C2 905 ///< Espressif ESP32-C2
#define OPT_MCU_ESP32H2 906 ///< Espressif ESP32-H2
#define OPT_MCU_ESP32P4 907 ///< Espressif ESP32-P4
#define TUP_MCU_ESPRESSIF (CFG_TUSB_MCU >= 900 && CFG_TUSB_MCU < 1000) // check if Espressif MCU
#define TUSB_MCU_VENDOR_ESPRESSIF (CFG_TUSB_MCU >= 900 && CFG_TUSB_MCU < 1000) // check if Espressif MCU
#define TUP_MCU_ESPRESSIF TUSB_MCU_VENDOR_ESPRESSIF // for backward compatibility
// Dialog
#define OPT_MCU_DA1469X 1000 ///< Dialog Semiconductor DA1469x
@@ -240,6 +241,8 @@
#include "tusb_config.h"
#endif
#include "common/tusb_mcu.h"
//--------------------------------------------------------------------+
// USBIP
//--------------------------------------------------------------------+
@@ -253,6 +256,22 @@
#define CFG_TUD_DWC2_DMA 0
#endif
// Enable DWC2 Slave mode for host
#ifndef CFG_TUH_DWC2_SLAVE_ENABLE
#ifndef CFG_TUH_DWC2_SLAVE_ENABLE_DEFAULT
#define CFG_TUH_DWC2_SLAVE_ENABLE_DEFAULT 1
#endif
#define CFG_TUH_DWC2_SLAVE_ENABLE CFG_TUH_DWC2_SLAVE_ENABLE_DEFAULT
#endif
// Enable DWC2 DMA for host
#ifndef CFG_TUH_DWC2_DMA_ENABLE
#ifndef CFG_TUH_DWC2_DMA_ENABLE_DEFAULT
#define CFG_TUH_DWC2_DMA_ENABLE_DEFAULT 1
#endif
#define CFG_TUH_DWC2_DMA_ENABLE CFG_TUH_DWC2_DMA_ENABLE_DEFAULT
#endif
// Enable PIO-USB software host controller
#ifndef CFG_TUH_RPI_PIO_USB
#define CFG_TUH_RPI_PIO_USB 0
@@ -267,7 +286,6 @@
#define CFG_TUH_MAX3421 0
#endif
#include "common/tusb_mcu.h"
//--------------------------------------------------------------------
// RootHub Mode detection