mirror of
https://github.com/hathach/tinyusb.git
synced 2025-01-17 05:32:55 +08:00
added support for frdm_kl25z
This commit is contained in:
parent
cc8329f3e4
commit
2bbfc56bd8
@ -46,7 +46,7 @@
|
||||
#include "chip.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_LPC51UXX || CFG_TUSB_MCU == OPT_MCU_LPC54XXX || \
|
||||
CFG_TUSB_MCU == OPT_MCU_LPC55XX
|
||||
CFG_TUSB_MCU == OPT_MCU_LPC55XX || CFG_TUSB_MCU == OPT_MCU_MKL25ZXX
|
||||
#include "fsl_device_registers.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_NRF5X
|
||||
|
46
hw/bsp/frdm_kl25z/board.mk
Normal file
46
hw/bsp/frdm_kl25z/board.mk
Normal file
@ -0,0 +1,46 @@
|
||||
CFLAGS += \
|
||||
-mthumb \
|
||||
-mabi=aapcs \
|
||||
-mcpu=cortex-m0plus \
|
||||
-DCPU_MKL25Z128VLK4 \
|
||||
-DCFG_TUSB_MCU=OPT_MCU_MKL25ZXX
|
||||
|
||||
# mcu driver cause following warnings
|
||||
CFLAGS += -Wno-error=unused-parameter
|
||||
|
||||
MCU_DIR = hw/mcu/nxp/sdk/devices/MKL25Z4
|
||||
|
||||
# All source paths should be relative to the top level.
|
||||
LD_FILE = $(MCU_DIR)/gcc/MKL25Z128xxx4_flash.ld
|
||||
|
||||
SRC_C += \
|
||||
$(MCU_DIR)/system_MKL25Z4.c \
|
||||
$(MCU_DIR)/project_template/clock_config.c \
|
||||
$(MCU_DIR)/drivers/fsl_clock.c \
|
||||
$(MCU_DIR)/drivers/fsl_gpio.c \
|
||||
$(MCU_DIR)/drivers/fsl_lpsci.c
|
||||
|
||||
INC += \
|
||||
$(TOP)/hw/bsp/$(BOARD) \
|
||||
$(TOP)/$(MCU_DIR)/../../CMSIS/Include \
|
||||
$(TOP)/$(MCU_DIR) \
|
||||
$(TOP)/$(MCU_DIR)/drivers \
|
||||
$(TOP)/$(MCU_DIR)/project_template \
|
||||
|
||||
SRC_S += $(MCU_DIR)/gcc/startup_MKL25Z4.S
|
||||
|
||||
# For TinyUSB port source
|
||||
VENDOR = nxp
|
||||
CHIP_FAMILY = khci
|
||||
|
||||
# For freeRTOS port source
|
||||
FREERTOS_PORT = ARM_CM0
|
||||
|
||||
# For flash-jlink target
|
||||
JLINK_DEVICE = MKL25Z128xxx4
|
||||
|
||||
# For flash-pyocd target
|
||||
PYOCD_TARGET = mkl25zl128
|
||||
|
||||
# flash using pyocd
|
||||
flash: flash-pyocd
|
148
hw/bsp/frdm_kl25z/frdm_kl25z.c
Normal file
148
hw/bsp/frdm_kl25z/frdm_kl25z.c
Normal file
@ -0,0 +1,148 @@
|
||||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2018, hathach (tinyusb.org)
|
||||
* Copyright (c) 2020, Koji Kitayama
|
||||
*
|
||||
* 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 "../board.h"
|
||||
#include "fsl_device_registers.h"
|
||||
#include "fsl_gpio.h"
|
||||
#include "fsl_port.h"
|
||||
#include "fsl_clock.h"
|
||||
#include "fsl_lpsci.h"
|
||||
|
||||
#include "clock_config.h"
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Forward USB interrupt events to TinyUSB IRQ Handler
|
||||
//--------------------------------------------------------------------+
|
||||
void USB0_IRQHandler(void)
|
||||
{
|
||||
tud_int_handler(0);
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// MACRO TYPEDEF CONSTANT ENUM DECLARATION
|
||||
//--------------------------------------------------------------------+
|
||||
// LED
|
||||
#define LED_PINMUX IOMUXC_GPIO_AD_B0_09_GPIO1_IO09
|
||||
#define LED_PORT GPIOB
|
||||
#define LED_PIN_CLOCK kCLOCK_PortB
|
||||
#define LED_PIN_PORT PORTB
|
||||
#define LED_PIN 19U
|
||||
#define LED_PIN_FUNCTION kPORT_MuxAsGpio
|
||||
#define LED_STATE_ON 0
|
||||
|
||||
// UART
|
||||
#define UART_PORT UART0
|
||||
#define UART_PIN_CLOCK kCLOCK_PortA
|
||||
#define UART_PIN_PORT PORTA
|
||||
#define UART_PIN_RX 1u
|
||||
#define UART_PIN_TX 2u
|
||||
#define UART_PIN_FUNCTION kPORT_MuxAlt2
|
||||
#define SOPT5_UART0RXSRC_UART_RX 0x00u /*!< UART0 receive data source select: UART0_RX pin */
|
||||
#define SOPT5_UART0TXSRC_UART_TX 0x00u /*!< UART0 transmit data source select: UART0_TX pin */
|
||||
|
||||
const uint8_t dcd_data[] = { 0x00 };
|
||||
|
||||
void board_init(void)
|
||||
{
|
||||
BOARD_BootClockRUN();
|
||||
SystemCoreClockUpdate();
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
// 1ms tick timer
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
#elif CFG_TUSB_OS == OPT_OS_FREERTOS
|
||||
// If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher )
|
||||
NVIC_SetPriority(USB0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY );
|
||||
#endif
|
||||
|
||||
// LED
|
||||
CLOCK_EnableClock(LED_PIN_CLOCK);
|
||||
PORT_SetPinMux(LED_PIN_PORT, LED_PIN, LED_PIN_FUNCTION);
|
||||
gpio_pin_config_t led_config = { kGPIO_DigitalOutput, 0 };
|
||||
GPIO_PinInit(LED_PORT, LED_PIN, &led_config);
|
||||
board_led_write(true);
|
||||
|
||||
// UART
|
||||
CLOCK_EnableClock(UART_PIN_CLOCK);
|
||||
PORT_SetPinMux(UART_PIN_PORT, UART_PIN_RX, UART_PIN_FUNCTION);
|
||||
PORT_SetPinMux(UART_PIN_PORT, UART_PIN_TX, UART_PIN_FUNCTION);
|
||||
SIM->SOPT5 = ((SIM->SOPT5 &
|
||||
(~(SIM_SOPT5_UART0TXSRC_MASK | SIM_SOPT5_UART0RXSRC_MASK)))
|
||||
| SIM_SOPT5_UART0TXSRC(SOPT5_UART0TXSRC_UART_TX)
|
||||
| SIM_SOPT5_UART0RXSRC(SOPT5_UART0RXSRC_UART_RX)
|
||||
);
|
||||
|
||||
lpsci_config_t uart_config;
|
||||
CLOCK_SetLpsci0Clock(1);
|
||||
LPSCI_GetDefaultConfig(&uart_config);
|
||||
uart_config.baudRate_Bps = CFG_BOARD_UART_BAUDRATE;
|
||||
uart_config.enableTx = true;
|
||||
uart_config.enableRx = true;
|
||||
LPSCI_Init(UART_PORT, &uart_config, CLOCK_GetPllFllSelClkFreq());
|
||||
|
||||
// USB
|
||||
CLOCK_EnableUsbfs0Clock(kCLOCK_UsbSrcPll0, CLOCK_GetFreq(kCLOCK_PllFllSelClk));
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Board porting API
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
void board_led_write(bool state)
|
||||
{
|
||||
GPIO_WritePinOutput(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
|
||||
}
|
||||
|
||||
uint32_t board_button_read(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
int board_uart_read(uint8_t* buf, int len)
|
||||
{
|
||||
LPSCI_ReadBlocking(UART_PORT, buf, len);
|
||||
return len;
|
||||
}
|
||||
|
||||
int board_uart_write(void const * buf, int len)
|
||||
{
|
||||
LPSCI_WriteBlocking(UART_PORT, (uint8_t*)buf, len);
|
||||
return len;
|
||||
}
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
volatile uint32_t system_ticks = 0;
|
||||
void SysTick_Handler(void)
|
||||
{
|
||||
system_ticks++;
|
||||
}
|
||||
|
||||
uint32_t board_millis(void)
|
||||
{
|
||||
return system_ticks;
|
||||
}
|
||||
#endif
|
459
src/portable/nxp/khci/dcd_khci.c
Normal file
459
src/portable/nxp/khci/dcd_khci.c
Normal file
@ -0,0 +1,459 @@
|
||||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020 Koji Kitayama
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#include "tusb_option.h"
|
||||
|
||||
#if TUSB_OPT_DEVICE_ENABLED && ( CFG_TUSB_MCU == OPT_MCU_MKL25ZXX )
|
||||
|
||||
#include "fsl_device_registers.h"
|
||||
#define KHCI USB0
|
||||
|
||||
#include "device/dcd.h"
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// MACRO TYPEDEF CONSTANT ENUM DECLARATION
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
enum {
|
||||
TOK_PID_OUT = 0x1u,
|
||||
TOK_PID_IN = 0x9u,
|
||||
TOK_PID_SETUP = 0xDu,
|
||||
};
|
||||
|
||||
typedef struct TU_ATTR_PACKED
|
||||
{
|
||||
union {
|
||||
uint32_t head;
|
||||
struct {
|
||||
union {
|
||||
uint16_t ctl;
|
||||
struct {
|
||||
uint16_t zeros : 2;
|
||||
uint16_t tok_pid : 4;
|
||||
uint16_t data : 1;
|
||||
uint16_t own : 1;
|
||||
uint16_t rsvd0 : 8;
|
||||
};
|
||||
struct {
|
||||
uint16_t dmy0 : 2;
|
||||
uint16_t bdt_stall: 1;
|
||||
uint16_t dts : 1;
|
||||
uint16_t ninc : 1;
|
||||
uint16_t keep : 1;
|
||||
uint16_t dmy1 : 10;
|
||||
};
|
||||
};
|
||||
uint16_t bc : 10;
|
||||
uint16_t rsvd1 : 6;
|
||||
};
|
||||
};
|
||||
uint8_t *addr;
|
||||
}buffer_descriptor_t;
|
||||
|
||||
TU_VERIFY_STATIC( sizeof(buffer_descriptor_t) == 8, "size is not correct" );
|
||||
|
||||
typedef struct TU_ATTR_PACKED
|
||||
{
|
||||
union {
|
||||
uint32_t state;
|
||||
struct {
|
||||
uint32_t max_packet_size: 11;
|
||||
uint32_t reserved0 : 5;
|
||||
uint32_t odd : 1;
|
||||
uint32_t reserved1 :15;
|
||||
};
|
||||
};
|
||||
uint16_t length;
|
||||
uint16_t remaining;
|
||||
}endpoint_state_t;
|
||||
|
||||
TU_VERIFY_STATIC( sizeof(endpoint_state_t) == 8, "size is not correct" );
|
||||
|
||||
typedef struct
|
||||
{
|
||||
union {
|
||||
/* [#EP][OUT,IN][EVEN,ODD] */
|
||||
buffer_descriptor_t bdt[16][2][2];
|
||||
uint16_t bda[512];
|
||||
};
|
||||
TU_ATTR_ALIGNED(4) union {
|
||||
endpoint_state_t endpoint[16][2];
|
||||
endpoint_state_t endpoint_unified[16 * 2];
|
||||
};
|
||||
uint8_t setup_packet[8];
|
||||
uint8_t addr;
|
||||
}dcd_data_t;
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// INTERNAL OBJECT & FUNCTION DECLARATION
|
||||
//--------------------------------------------------------------------+
|
||||
// BDT(Buffer Descriptor Table) must be 256-byte aligned
|
||||
CFG_TUSB_MEM_SECTION TU_ATTR_ALIGNED(512) static dcd_data_t _dcd;
|
||||
|
||||
TU_VERIFY_STATIC( sizeof(_dcd.bdt) == 512, "size is not correct" );
|
||||
|
||||
static void prepare_next_setup_packet(uint8_t rhport)
|
||||
{
|
||||
const unsigned out_odd = _dcd.endpoint[0][0].odd;
|
||||
const unsigned in_odd = _dcd.endpoint[0][1].odd;
|
||||
if (_dcd.bdt[0][0][out_odd].own) {
|
||||
TU_LOG1("DCD fail to prepare the next SETUP %d %d\r\n", out_odd, in_odd);
|
||||
return;
|
||||
}
|
||||
_dcd.bdt[0][0][out_odd].data = 0;
|
||||
_dcd.bdt[0][0][out_odd ^ 1].data = 1;
|
||||
_dcd.bdt[0][1][in_odd].data = 1;
|
||||
_dcd.bdt[0][1][in_odd ^ 1].data = 0;
|
||||
dcd_edpt_xfer(rhport, tu_edpt_addr(0, TUSB_DIR_OUT),
|
||||
_dcd.setup_packet, sizeof(_dcd.setup_packet));
|
||||
}
|
||||
|
||||
static void process_stall(uint8_t rhport)
|
||||
{
|
||||
if (KHCI->ENDPOINT[0].ENDPT & USB_ENDPT_EPSTALL_MASK) {
|
||||
/* clear stall condition of the control pipe */
|
||||
prepare_next_setup_packet(rhport);
|
||||
KHCI->ENDPOINT[0].ENDPT &= ~USB_ENDPT_EPSTALL_MASK;
|
||||
KHCI->ENDPOINT[1].ENDPT &= ~USB_ENDPT_EPSTALL_MASK;
|
||||
}
|
||||
}
|
||||
|
||||
static void process_tokdne(uint8_t rhport)
|
||||
{
|
||||
const unsigned s = KHCI->STAT;
|
||||
KHCI->ISTAT = USB_ISTAT_TOKDNE_MASK; /* fetch the next token if received */
|
||||
buffer_descriptor_t *bd = (buffer_descriptor_t *)&_dcd.bda[s];
|
||||
endpoint_state_t *ep = &_dcd.endpoint_unified[s >> 3];
|
||||
unsigned odd = (s & USB_STAT_ODD_MASK) ? 1 : 0;
|
||||
|
||||
/* fetch pid before discarded by the next steps */
|
||||
const unsigned pid = bd->tok_pid;
|
||||
/* reset values for a next transfer */
|
||||
bd->bdt_stall = 0;
|
||||
bd->dts = 1;
|
||||
bd->ninc = 0;
|
||||
bd->keep = 0;
|
||||
/* update the odd variable to prepare for the next transfer */
|
||||
ep->odd = odd ^ 1;
|
||||
if (pid == TOK_PID_SETUP) {
|
||||
dcd_event_setup_received(rhport, bd->addr, true);
|
||||
KHCI->CTL &= ~USB_CTL_TXSUSPENDTOKENBUSY_MASK;
|
||||
return;
|
||||
}
|
||||
|
||||
const unsigned bc = bd->bc;
|
||||
const unsigned remaining = ep->remaining - bc;
|
||||
if (remaining && bc == ep->max_packet_size) {
|
||||
/* continue the transferring consecutive data */
|
||||
ep->remaining = remaining;
|
||||
const int next_remaining = remaining - ep->max_packet_size;
|
||||
if (next_remaining > 0) {
|
||||
/* prepare to the after next transfer */
|
||||
bd->addr += ep->max_packet_size * 2;
|
||||
bd->bc = next_remaining > ep->max_packet_size ? ep->max_packet_size: next_remaining;
|
||||
__DSB();
|
||||
bd->own = 1; /* the own bit must set after addr */
|
||||
}
|
||||
return;
|
||||
}
|
||||
const unsigned length = ep->length;
|
||||
dcd_event_xfer_complete(rhport,
|
||||
((s & USB_STAT_TX_MASK) << 4) | (s >> USB_STAT_ENDP_SHIFT),
|
||||
length - remaining, XFER_RESULT_SUCCESS, true);
|
||||
if (0 == (s & USB_STAT_ENDP_MASK) && 0 == length) {
|
||||
/* After completion a ZLP of control transfer,
|
||||
* it prepares for the next steup transfer. */
|
||||
if (_dcd.addr) {
|
||||
/* When the transfer was the SetAddress,
|
||||
* the device address should be updated here. */
|
||||
KHCI->ADDR = _dcd.addr;
|
||||
_dcd.addr = 0;
|
||||
}
|
||||
prepare_next_setup_packet(rhport);
|
||||
}
|
||||
}
|
||||
|
||||
static void process_bus_reset(uint8_t rhport)
|
||||
{
|
||||
KHCI->USBCTRL &= ~USB_USBCTRL_SUSP_MASK;
|
||||
KHCI->CTL |= USB_CTL_ODDRST_MASK;
|
||||
KHCI->ADDR = 0;
|
||||
KHCI->INTEN = (KHCI->INTEN & ~USB_INTEN_RESUMEEN_MASK) | USB_INTEN_SLEEPEN_MASK;
|
||||
|
||||
KHCI->ENDPOINT[0].ENDPT = USB_ENDPT_EPHSHK_MASK | USB_ENDPT_EPRXEN_MASK | USB_ENDPT_EPTXEN_MASK;
|
||||
for (unsigned i = 1; i < 16; ++i) {
|
||||
KHCI->ENDPOINT[i].ENDPT = 0;
|
||||
}
|
||||
buffer_descriptor_t *bd = _dcd.bdt[0][0];
|
||||
for (unsigned i = 0; i < sizeof(_dcd.bdt)/sizeof(*bd); ++i, ++bd) {
|
||||
bd->head = 0;
|
||||
}
|
||||
const endpoint_state_t ep0 = {
|
||||
.max_packet_size = CFG_TUD_ENDPOINT0_SIZE,
|
||||
.odd = 0,
|
||||
.length = 0,
|
||||
.remaining = 0,
|
||||
};
|
||||
_dcd.endpoint[0][0] = ep0;
|
||||
_dcd.endpoint[0][1] = ep0;
|
||||
tu_memclr(_dcd.endpoint[1], sizeof(_dcd.endpoint) - sizeof(_dcd.endpoint[0]));
|
||||
_dcd.addr = 0;
|
||||
prepare_next_setup_packet(rhport);
|
||||
KHCI->CTL &= ~USB_CTL_ODDRST_MASK;
|
||||
dcd_event_bus_signal(rhport, DCD_EVENT_BUS_RESET, true);
|
||||
}
|
||||
|
||||
static void process_bus_inactive(uint8_t rhport)
|
||||
{
|
||||
(void) rhport;
|
||||
const unsigned inten = KHCI->INTEN;
|
||||
KHCI->INTEN = (inten & ~USB_INTEN_SLEEPEN_MASK) | USB_INTEN_RESUMEEN_MASK;
|
||||
KHCI->USBCTRL |= USB_USBCTRL_SUSP_MASK;
|
||||
dcd_event_bus_signal(rhport, DCD_EVENT_SUSPEND, true);
|
||||
}
|
||||
|
||||
static void process_bus_active(uint8_t rhport)
|
||||
{
|
||||
(void) rhport;
|
||||
KHCI->USBCTRL &= ~USB_USBCTRL_SUSP_MASK;
|
||||
const unsigned inten = KHCI->INTEN;
|
||||
KHCI->INTEN = (inten & ~USB_INTEN_RESUMEEN_MASK) | USB_INTEN_SLEEPEN_MASK;
|
||||
dcd_event_bus_signal(rhport, DCD_EVENT_RESUME, true);
|
||||
}
|
||||
|
||||
/*------------------------------------------------------------------*/
|
||||
/* Device API
|
||||
*------------------------------------------------------------------*/
|
||||
void dcd_init(uint8_t rhport)
|
||||
{
|
||||
(void) rhport;
|
||||
|
||||
KHCI->USBTRC0 |= USB_USBTRC0_USBRESET_MASK;
|
||||
while (KHCI->USBTRC0 & USB_USBTRC0_USBRESET_MASK);
|
||||
tu_memclr(&_dcd, sizeof(_dcd));
|
||||
KHCI->USBTRC0 |= TU_BIT(6); /* software must set this bit to 1 */
|
||||
KHCI->BDTPAGE1 = (uint8_t)((uintptr_t)_dcd.bdt >> 8);
|
||||
KHCI->BDTPAGE2 = (uint8_t)((uintptr_t)_dcd.bdt >> 16);
|
||||
KHCI->BDTPAGE3 = (uint8_t)((uintptr_t)_dcd.bdt >> 24);
|
||||
|
||||
dcd_connect(rhport);
|
||||
NVIC_ClearPendingIRQ(USB0_IRQn);
|
||||
}
|
||||
|
||||
void dcd_int_enable(uint8_t rhport)
|
||||
{
|
||||
(void) rhport;
|
||||
KHCI->INTEN = USB_INTEN_USBRSTEN_MASK | USB_INTEN_TOKDNEEN_MASK |
|
||||
USB_INTEN_SLEEPEN_MASK | USB_INTEN_ERROREN_MASK | USB_INTEN_STALLEN_MASK;
|
||||
NVIC_EnableIRQ(USB0_IRQn);
|
||||
}
|
||||
|
||||
void dcd_int_disable(uint8_t rhport)
|
||||
{
|
||||
(void) rhport;
|
||||
NVIC_DisableIRQ(USB0_IRQn);
|
||||
KHCI->INTEN = 0;
|
||||
}
|
||||
|
||||
void dcd_set_address(uint8_t rhport, uint8_t dev_addr)
|
||||
{
|
||||
(void) rhport;
|
||||
_dcd.addr = dev_addr & 0x7F;
|
||||
/* Response with status first before changing device address */
|
||||
dcd_edpt_xfer(rhport, tu_edpt_addr(0, TUSB_DIR_IN), NULL, 0);
|
||||
}
|
||||
|
||||
void dcd_remote_wakeup(uint8_t rhport)
|
||||
{
|
||||
(void) rhport;
|
||||
unsigned cnt = SystemCoreClock / 100;
|
||||
KHCI->CTL |= USB_CTL_RESUME_MASK;
|
||||
while (cnt--) __NOP();
|
||||
KHCI->CTL &= ~USB_CTL_RESUME_MASK;
|
||||
}
|
||||
|
||||
void dcd_connect(uint8_t rhport)
|
||||
{
|
||||
(void) rhport;
|
||||
KHCI->USBCTRL = 0;
|
||||
KHCI->CONTROL |= USB_CONTROL_DPPULLUPNONOTG_MASK;
|
||||
KHCI->CTL |= USB_CTL_USBENSOFEN_MASK;
|
||||
}
|
||||
|
||||
void dcd_disconnect(uint8_t rhport)
|
||||
{
|
||||
(void) rhport;
|
||||
KHCI->CTL = 0;
|
||||
KHCI->CONTROL &= ~USB_CONTROL_DPPULLUPNONOTG_MASK;
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Endpoint API
|
||||
//--------------------------------------------------------------------+
|
||||
bool dcd_edpt_open(uint8_t rhport, tusb_desc_endpoint_t const * ep_desc)
|
||||
{
|
||||
(void) rhport;
|
||||
|
||||
const unsigned ep_addr = ep_desc->bEndpointAddress;
|
||||
const unsigned epn = ep_addr & 0xFu;
|
||||
const unsigned dir = ep_addr & TUSB_DIR_IN_MASK ? 1 : 0;
|
||||
const unsigned xfer = ep_desc->bmAttributes.xfer;
|
||||
endpoint_state_t *ep = &_dcd.endpoint[epn][dir];
|
||||
const unsigned odd = ep->odd;
|
||||
buffer_descriptor_t *bd = &_dcd.bdt[epn][dir][0];
|
||||
|
||||
/* No support for control transfer */
|
||||
TU_ASSERT(epn && (xfer != TUSB_XFER_CONTROL));
|
||||
|
||||
ep->max_packet_size = ep_desc->wMaxPacketSize.size;
|
||||
unsigned val = USB_ENDPT_EPCTLDIS_MASK;
|
||||
val |= (xfer != TUSB_XFER_ISOCHRONOUS) ? USB_ENDPT_EPHSHK_MASK: 0;
|
||||
val |= dir ? USB_ENDPT_EPRXEN_MASK : USB_ENDPT_EPTXEN_MASK;
|
||||
KHCI->ENDPOINT[epn].ENDPT |= val;
|
||||
|
||||
if (xfer != TUSB_XFER_ISOCHRONOUS) {
|
||||
bd[odd].dts = 1;
|
||||
bd[odd].data = 0;
|
||||
bd[odd ^ 1].dts = 1;
|
||||
bd[odd ^ 1].data = 1;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void dcd_edpt_close(uint8_t rhport, uint8_t ep_addr)
|
||||
{
|
||||
(void) rhport;
|
||||
|
||||
const unsigned epn = ep_addr & 0xFu;
|
||||
const unsigned dir = ep_addr & TUSB_DIR_IN_MASK ? 1 : 0;
|
||||
endpoint_state_t *ep = &_dcd.endpoint[epn][dir];
|
||||
buffer_descriptor_t *bd = &_dcd.bdt[epn][dir][0];
|
||||
|
||||
KHCI->ENDPOINT[epn].ENDPT = 0;
|
||||
ep->max_packet_size = 0;
|
||||
ep->length = 0;
|
||||
ep->remaining = 0;
|
||||
bd->head = 0;
|
||||
}
|
||||
|
||||
bool dcd_edpt_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, uint16_t total_bytes)
|
||||
{
|
||||
(void) rhport;
|
||||
NVIC_DisableIRQ(USB0_IRQn);
|
||||
const unsigned epn = ep_addr & 0xFu;
|
||||
const unsigned dir = (ep_addr & TUSB_DIR_IN_MASK) ? TUSB_DIR_IN : TUSB_DIR_OUT;
|
||||
endpoint_state_t *ep = &_dcd.endpoint[epn][dir];
|
||||
buffer_descriptor_t *bd = &_dcd.bdt[epn][dir][ep->odd];
|
||||
|
||||
if (bd->own) {
|
||||
TU_LOG1("DCD XFER fail %x %d %lx %lx\r\n", ep_addr, total_bytes, ep->state, bd->head);
|
||||
return false; /* The last transfer has not completed */
|
||||
}
|
||||
ep->length = total_bytes;
|
||||
ep->remaining = total_bytes;
|
||||
|
||||
const unsigned mps = ep->max_packet_size;
|
||||
if (total_bytes > mps) {
|
||||
buffer_descriptor_t *next = ep->odd ? bd - 1: bd + 1;
|
||||
/* When total_bytes is greater than the max packet size,
|
||||
* it prepares to the next transfer to avoid NAK in advance. */
|
||||
next->bc = total_bytes >= 2 * mps ? mps: total_bytes - mps;
|
||||
next->addr = buffer + mps;
|
||||
next->own = 1;
|
||||
}
|
||||
bd->bc = total_bytes >= mps ? mps: total_bytes;
|
||||
bd->addr = buffer;
|
||||
__DSB();
|
||||
bd->own = 1; /* the own bit must set after addr */
|
||||
NVIC_EnableIRQ(USB0_IRQn);
|
||||
return true;
|
||||
}
|
||||
|
||||
void dcd_edpt_stall(uint8_t rhport, uint8_t ep_addr)
|
||||
{
|
||||
(void) rhport;
|
||||
const unsigned epn = ep_addr & 0xFu;
|
||||
KHCI->ENDPOINT[epn].ENDPT |= USB_ENDPT_EPSTALL_MASK;
|
||||
}
|
||||
|
||||
void dcd_edpt_clear_stall(uint8_t rhport, uint8_t ep_addr)
|
||||
{
|
||||
(void) rhport;
|
||||
const unsigned epn = ep_addr & 0xFu;
|
||||
KHCI->ENDPOINT[epn].ENDPT &= ~USB_ENDPT_EPSTALL_MASK;
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// ISR
|
||||
//--------------------------------------------------------------------+
|
||||
void dcd_int_handler(uint8_t rhport)
|
||||
{
|
||||
(void) rhport;
|
||||
|
||||
uint32_t is = KHCI->ISTAT;
|
||||
uint32_t msk = KHCI->INTEN;
|
||||
KHCI->ISTAT = is & ~msk;
|
||||
is &= msk;
|
||||
if (is & USB_ISTAT_ERROR_MASK) {
|
||||
/* TODO: */
|
||||
uint32_t es = KHCI->ERRSTAT;
|
||||
KHCI->ERRSTAT = es;
|
||||
KHCI->ISTAT = is; /* discard any pending events */
|
||||
return;
|
||||
}
|
||||
|
||||
if (is & USB_ISTAT_USBRST_MASK) {
|
||||
KHCI->ISTAT = is; /* discard any pending events */
|
||||
process_bus_reset(rhport);
|
||||
return;
|
||||
}
|
||||
if (is & USB_ISTAT_SLEEP_MASK) {
|
||||
KHCI->ISTAT = USB_ISTAT_SLEEP_MASK;
|
||||
process_bus_inactive(rhport);
|
||||
return;
|
||||
}
|
||||
if (is & USB_ISTAT_RESUME_MASK) {
|
||||
KHCI->ISTAT = USB_ISTAT_RESUME_MASK;
|
||||
process_bus_active(rhport);
|
||||
return;
|
||||
}
|
||||
if (is & USB_ISTAT_SOFTOK_MASK) {
|
||||
KHCI->ISTAT = USB_ISTAT_SOFTOK_MASK;
|
||||
dcd_event_bus_signal(rhport, DCD_EVENT_SOF, true);
|
||||
return;
|
||||
}
|
||||
if (is & USB_ISTAT_STALL_MASK) {
|
||||
KHCI->ISTAT = USB_ISTAT_STALL_MASK;
|
||||
process_stall(rhport);
|
||||
return;
|
||||
}
|
||||
if (is & USB_ISTAT_TOKDNE_MASK) {
|
||||
process_tokdne(rhport);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
@ -97,6 +97,10 @@
|
||||
// Dialog
|
||||
#define OPT_MCU_DA1469X 1000 ///< Dialog Semiconductor DA1469x
|
||||
|
||||
// NXP Kinetis
|
||||
#define OPT_MCU_MKL25ZXX 1100 ///< NXP MKL25Zxx
|
||||
|
||||
|
||||
/** @} */
|
||||
|
||||
/** \defgroup group_supported_os Supported RTOS
|
||||
|
Loading…
x
Reference in New Issue
Block a user