1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-12 19:10:32 +03:00

Cleanup of USB drivers for AT32F4 (#12441)

* Cleanup of USB drivers for AT32F4
* F4 has different directories
This commit is contained in:
J Blackman 2023-03-09 18:14:16 +11:00 committed by GitHub
parent deeebb4c1c
commit c224c075f8
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
31 changed files with 53 additions and 7458 deletions

View file

@ -138,6 +138,7 @@ void usbd_core_out_handler(usbd_core_type *udev, uint8_t ept_addr)
*/
void usbd_core_setup_handler(usbd_core_type *udev, uint8_t ept_num)
{
UNUSED(ept_num);
/* setup parse */
usbd_setup_request_parse(&udev->setup, udev->setup_buffer);
@ -745,6 +746,7 @@ usb_sts_type usbd_core_init(usbd_core_type *udev,
usbd_desc_handler *desc_handler,
uint8_t core_id)
{
UNUSED(core_id);
usb_reg_type *usbx;
otg_device_type *dev;
otg_eptin_type *ept_in;

View file

@ -502,6 +502,7 @@ usb_sts_type usbh_core_init(usbh_core_type *uhost,
usbh_user_handler_type *user_handler,
uint8_t core_id)
{
UNUSED(core_id);
usb_sts_type status = USB_OK;
uint32_t i_index;
otg_global_type *usbx = usb_reg;
@ -552,8 +553,8 @@ usb_sts_type usbh_core_init(usbh_core_type *uhost,
if(usbx == OTG1_GLOBAL)
{
/* set receive fifo size */
usbx->grxfsiz = USBH_RX_FIFO_SIZE;
/* set receive fifo size */
usbx->grxfsiz = USBH_RX_FIFO_SIZE;
/* set non-periodic transmit fifo start address and depth */
usbx->gnptxfsiz_ept0tx_bit.nptxfstaddr = USBH_RX_FIFO_SIZE;
@ -566,8 +567,8 @@ usb_sts_type usbh_core_init(usbh_core_type *uhost,
#ifdef OTG2_GLOBAL
if(usbx == OTG2_GLOBAL)
{
/* set receive fifo size */
usbx->grxfsiz = USBH2_RX_FIFO_SIZE;
/* set receive fifo size */
usbx->grxfsiz = USBH2_RX_FIFO_SIZE;
/* set non-periodic transmit fifo start address and depth */
usbx->gnptxfsiz_ept0tx_bit.nptxfstaddr = USBH2_RX_FIFO_SIZE;
@ -808,8 +809,6 @@ usb_sts_type usbh_enum_handler(usbh_core_type *uhost)
if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_SET_ADDR) == USB_OK)
{
usbh_parse_dev_desc(uhost, uhost->rx_buffer, 18);
USBH_DEBUG("VID: %xh", uhost->dev.dev_desc.idVendor);
USBH_DEBUG("PID: %xh", uhost->dev.dev_desc.idProduct);
}
break;
@ -818,7 +817,6 @@ usb_sts_type usbh_enum_handler(usbh_core_type *uhost)
if(uhost->ctrl.state == CONTROL_IDLE)
{
uhost->dev.address = usbh_alloc_address();
USBH_DEBUG("Set Address: %d", uhost->dev.address);
usbh_set_address(uhost, uhost->dev.address);
}
if (usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_CFG) == USB_OK)
@ -1096,7 +1094,6 @@ static void usbh_wakeup(usbh_core_type *uhost)
if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK)
{
uhost->global_state = USBH_CLASS_REQUEST;
USBH_DEBUG("Remote Wakeup");
}
}

View file

@ -204,6 +204,7 @@ usb_sts_type usbh_ctrl_data_in_handler(usbh_core_type *uhost)
*/
usb_sts_type usbh_ctrl_data_in_wait_handler(usbh_core_type *uhost, uint32_t timeout)
{
UNUSED(timeout);
usb_sts_type status = USB_OK;
urb_sts_type urb_state;
urb_state = uhost->urb_state[uhost->ctrl.hch_in];
@ -260,6 +261,7 @@ usb_sts_type usbh_ctrl_data_out_handler(usbh_core_type *uhost)
*/
usb_sts_type usbh_ctrl_data_out_wait_handler(usbh_core_type *uhost, uint32_t timeout)
{
UNUSED(timeout);
usb_sts_type status = USB_OK;
urb_sts_type urb_state;
urb_state = uhost->urb_state[uhost->ctrl.hch_out];
@ -316,6 +318,7 @@ usb_sts_type usbh_ctrl_status_in_handler(usbh_core_type *uhost)
*/
usb_sts_type usbh_ctrl_status_in_wait_handler(usbh_core_type *uhost, uint32_t timeout)
{
UNUSED(timeout);
usb_sts_type status = USB_OK;
urb_sts_type urb_state;
urb_state = uhost->urb_state[uhost->ctrl.hch_in];
@ -369,6 +372,7 @@ usb_sts_type usbh_ctrl_status_out_handler(usbh_core_type *uhost)
*/
usb_sts_type usbh_ctrl_status_out_wait_handler(usbh_core_type *uhost, uint32_t timeout)
{
UNUSED(timeout);
usb_sts_type status = USB_OK;
urb_sts_type urb_state;
urb_state = uhost->urb_state[uhost->ctrl.hch_out];
@ -418,7 +422,6 @@ usb_sts_type usbh_ctrl_error_handler(usbh_core_type *uhost)
uhost->ctrl.sts = CTRL_FAIL;
uhost->global_state = USBH_ERROR_STATE;
uhost->ctrl.err_cnt = 0;
USBH_DEBUG("control error: **** Device No Response ****");
status = USB_ERROR;
}
return status;
@ -431,6 +434,7 @@ usb_sts_type usbh_ctrl_error_handler(usbh_core_type *uhost)
*/
usb_sts_type usbh_ctrl_stall_handler(usbh_core_type *uhost)
{
UNUSED(uhost);
return USB_NOT_SUPPORT;
}
@ -441,6 +445,7 @@ usb_sts_type usbh_ctrl_stall_handler(usbh_core_type *uhost)
*/
usb_sts_type usbh_ctrl_complete_handler(usbh_core_type *uhost)
{
UNUSED(uhost);
return USB_OK;
}
@ -810,6 +815,8 @@ usb_sts_type usbh_get_configure_descriptor(usbh_core_type *uhost, uint16_t lengt
usb_sts_type usbh_get_sting_descriptor(usbh_core_type *uhost, uint8_t string_id,
uint8_t *buffer, uint16_t length)
{
UNUSED(buffer);
usb_sts_type status = USB_WAIT;
uint8_t bm_req;
uint16_t wvalue;
@ -941,6 +948,7 @@ usb_sts_type usbh_clear_dev_feature(usbh_core_type *uhost, uint8_t feature, uint
*/
usb_sts_type usbh_clear_ept_feature(usbh_core_type *uhost, uint8_t ept_num, uint8_t hc_num)
{
UNUSED(hc_num);
usb_sts_type status = USB_WAIT;
uint8_t bm_req;
if(uhost->ctrl.state == CONTROL_IDLE )

View file

@ -191,6 +191,7 @@ static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup)
*/
static usb_sts_type class_ept0_tx_handler(void *udev)
{
UNUSED(udev);
usb_sts_type status = USB_OK;
/* ...user code... */
@ -268,6 +269,7 @@ static usb_sts_type class_out_handler(void *udev, uint8_t ept_num)
*/
static usb_sts_type class_sof_handler(void *udev)
{
UNUSED(udev);
usb_sts_type status = USB_OK;
/* ...user code... */
@ -283,6 +285,7 @@ static usb_sts_type class_sof_handler(void *udev)
*/
static usb_sts_type class_event_handler(void *udev, usbd_event_type event)
{
UNUSED(udev);
usb_sts_type status = USB_OK;
switch(event)
{
@ -391,6 +394,7 @@ error_status usb_vcp_send_data(void *udev, uint8_t *send_data, uint16_t len)
*/
static void usb_vcp_cmd_process(void *udev, uint8_t cmd, uint8_t *buff, uint16_t len)
{
UNUSED(len);
usbd_core_type *pudev = (usbd_core_type *)udev;
cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata;
switch(cmd)

View file

@ -8,6 +8,9 @@ CMSIS_DIR := $(ROOT)/lib/main/STM32F4/Drivers/CMSIS
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4/Drivers/STM32F4xx_HAL_Driver
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c))
EXCLUDES =
VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
else
CMSIS_DIR := $(ROOT)/lib/main/CMSIS
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver
@ -31,6 +34,8 @@ EXCLUDES = stm32f4xx_crc.c \
stm32f4xx_dbgmcu.c \
stm32f4xx_cryp_tdes.c \
stm32f4xx_hash_sha1.c
VPATH := $(VPATH):$(STDPERIPH_DIR)/src
endif
ifeq ($(TARGET_MCU),$(filter $(TARGET_MCU),STM32F411xE STM32F446xx))

View file

@ -88,7 +88,7 @@ USBMSC_SRC = $(notdir $(wildcard $(USBMSC_DIR)/Src/*.c))
EXCLUDES = usbd_msc_storage_template.c
USBMSC_SRC := $(filter-out ${EXCLUDES}, $(USBMSC_SRC))
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src:$(STDPERIPH_DIR)/src
DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
$(USBCORE_SRC) \
@ -99,6 +99,7 @@ DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
#CMSIS
VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32F7xx
VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
CMSIS_SRC :=
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(STDPERIPH_DIR)/Inc \

View file

@ -91,7 +91,7 @@ USBMSC_SRC = $(notdir $(wildcard $(USBMSC_DIR)/Src/*.c))
EXCLUDES = usbd_msc_storage_template.c
USBMSC_SRC := $(filter-out ${EXCLUDES}, $(USBMSC_SRC))
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src:$(STDPERIPH_DIR)/src
DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
$(USBCORE_SRC) \

View file

@ -111,7 +111,7 @@ USBMSC_SRC = $(notdir $(wildcard $(USBMSC_DIR)/Src/*.c))
EXCLUDES = usbd_msc_storage_template.c
USBMSC_SRC := $(filter-out ${EXCLUDES}, $(USBMSC_SRC))
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src:$(STDPERIPH_DIR)/src
DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
$(USBCORE_SRC) \

View file

@ -469,9 +469,6 @@ SRC += $(VCP_SRC)
# end target specific make file checks
# Search path and source files for the ST stdperiph library
VPATH := $(VPATH):$(STDPERIPH_DIR)/src
# Search path and source files for the Open Location Code library
OLC_DIR = $(ROOT)/lib/main/google/olc

View file

@ -36,11 +36,11 @@
#include "pg/usb.h"
#include "at32f435_437_clock.h"
#include "drivers/at32/usb/usb_conf.h"
#include "drivers/at32/usb/usb_core.h"
#include "drivers/at32/usb/usbd_int.h"
#include "drivers/at32/usb/cdc_class.h"
#include "drivers/at32/usb/cdc_desc.h"
#include "usb_conf.h"
#include "usb_core.h"
#include "usbd_int.h"
#include "cdc_class.h"
#include "cdc_desc.h"
#include "drivers/time.h"
#include "drivers/serial.h"
@ -285,7 +285,7 @@ void TMR20_OVF_IRQHandler(void)
lastBuffsize = 0;
if (needZeroLengthPacket) {
usb_vcp_send_data(&otg_core_struct.dev, (uint8_t*)&UserTxBuffer[UserTxBufPtrOut], 0);
usb_vcp_send_data(&otg_core_struct.dev, (uint8_t*)&UserTxBuffer[UserTxBufPtrOut], 0);
return;
}
}
@ -310,12 +310,12 @@ void TMR20_OVF_IRQHandler(void)
uint8_t usbIsConnected(void)
{
return (USB_CONN_STATE_DEFAULT != otg_core_struct.dev.conn_state);
return (USB_CONN_STATE_DEFAULT != otg_core_struct.dev.conn_state);
}
uint8_t usbIsConfigured(void)
{
return (USB_CONN_STATE_CONFIGURED == otg_core_struct.dev.conn_state);
return (USB_CONN_STATE_CONFIGURED == otg_core_struct.dev.conn_state);
}
uint8_t usbVcpIsConnected(void)

View file

@ -1,443 +0,0 @@
/**
**************************************************************************
* @file cdc_class.c
* @brief usb cdc class type
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
#include "platform.h"
#include "usbd_core.h"
#include "cdc_class.h"
#include "cdc_desc.h"
/** @addtogroup AT32F435_437_middlewares_usbd_class
* @{
*/
/** @defgroup USB_cdc_class
* @brief usb device class cdc demo
* @{
*/
/** @defgroup USB_cdc_class_private_functions
* @{
*/
static usb_sts_type class_init_handler(void *udev);
static usb_sts_type class_clear_handler(void *udev);
static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup);
static usb_sts_type class_ept0_tx_handler(void *udev);
static usb_sts_type class_ept0_rx_handler(void *udev);
static usb_sts_type class_in_handler(void *udev, uint8_t ept_num);
static usb_sts_type class_out_handler(void *udev, uint8_t ept_num);
static usb_sts_type class_sof_handler(void *udev);
static usb_sts_type class_event_handler(void *udev, usbd_event_type event);
static usb_sts_type cdc_struct_init(cdc_struct_type *pcdc);
extern void usb_usart_config( linecoding_type linecoding);
static void usb_vcp_cmd_process(void *udev, uint8_t cmd, uint8_t *buff, uint16_t len);
linecoding_type linecoding =
{
115200,
0,
0,
8
};
/* cdc data struct */
cdc_struct_type cdc_struct;
/* usb device class handler */
usbd_class_handler cdc_class_handler =
{
class_init_handler,
class_clear_handler,
class_setup_handler,
class_ept0_tx_handler,
class_ept0_rx_handler,
class_in_handler,
class_out_handler,
class_sof_handler,
class_event_handler,
&cdc_struct
};
/**
* @brief initialize usb custom hid endpoint
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
static usb_sts_type class_init_handler(void *udev)
{
usb_sts_type status = USB_OK;
usbd_core_type *pudev = (usbd_core_type *)udev;
cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata;
/* init cdc struct */
cdc_struct_init(pcdc);
/* open in endpoint */
usbd_ept_open(pudev, USBD_CDC_INT_EPT, EPT_INT_TYPE, USBD_CDC_CMD_MAXPACKET_SIZE);
/* open in endpoint */
usbd_ept_open(pudev, USBD_CDC_BULK_IN_EPT, EPT_BULK_TYPE, USBD_CDC_IN_MAXPACKET_SIZE);
/* open out endpoint */
usbd_ept_open(pudev, USBD_CDC_BULK_OUT_EPT, EPT_BULK_TYPE, USBD_CDC_OUT_MAXPACKET_SIZE);
/* set out endpoint to receive status */
usbd_ept_recv(pudev, USBD_CDC_BULK_OUT_EPT, pcdc->g_rx_buff, USBD_CDC_OUT_MAXPACKET_SIZE);
return status;
}
/**
* @brief clear endpoint or other state
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
static usb_sts_type class_clear_handler(void *udev)
{
usb_sts_type status = USB_OK;
usbd_core_type *pudev = (usbd_core_type *)udev;
/* close in endpoint */
usbd_ept_close(pudev, USBD_CDC_INT_EPT);
/* close in endpoint */
usbd_ept_close(pudev, USBD_CDC_BULK_IN_EPT);
/* close out endpoint */
usbd_ept_close(pudev, USBD_CDC_BULK_OUT_EPT);
return status;
}
/**
* @brief usb device class setup request handler
* @param udev: to the structure of usbd_core_type
* @param setup: setup packet
* @retval status of usb_sts_type
*/
static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup)
{
usb_sts_type status = USB_OK;
usbd_core_type *pudev = (usbd_core_type *)udev;
cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata;
switch(setup->bmRequestType & USB_REQ_TYPE_RESERVED)
{
/* class request */
case USB_REQ_TYPE_CLASS:
if(setup->wLength)
{
if(setup->bmRequestType & USB_REQ_DIR_DTH)
{
usb_vcp_cmd_process(udev, setup->bRequest, pcdc->g_cmd, setup->wLength);
usbd_ctrl_send(pudev, pcdc->g_cmd, setup->wLength);
}
else
{
pcdc->g_req = setup->bRequest;
pcdc->g_len = setup->wLength;
usbd_ctrl_recv(pudev, pcdc->g_cmd, pcdc->g_len);
}
}
break;
/* standard request */
case USB_REQ_TYPE_STANDARD:
switch(setup->bRequest)
{
case USB_STD_REQ_GET_DESCRIPTOR:
usbd_ctrl_unsupport(pudev);
break;
case USB_STD_REQ_GET_INTERFACE:
usbd_ctrl_send(pudev, (uint8_t *)&pcdc->alt_setting, 1);
break;
case USB_STD_REQ_SET_INTERFACE:
pcdc->alt_setting = setup->wValue;
break;
default:
break;
}
break;
default:
usbd_ctrl_unsupport(pudev);
break;
}
return status;
}
/**
* @brief usb device endpoint 0 in status stage complete
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
static usb_sts_type class_ept0_tx_handler(void *udev)
{
UNUSED(udev);
usb_sts_type status = USB_OK;
/* ...user code... */
return status;
}
/**
* @brief usb device endpoint 0 out status stage complete
* @param udev: usb device core handler type
* @retval status of usb_sts_type
*/
static usb_sts_type class_ept0_rx_handler(void *udev)
{
usb_sts_type status = USB_OK;
usbd_core_type *pudev = (usbd_core_type *)udev;
cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata;
uint32_t recv_len = usbd_get_recv_len(pudev, 0);
/* ...user code... */
if( pcdc->g_req == SET_LINE_CODING)
{
/* class process */
usb_vcp_cmd_process(udev, pcdc->g_req, pcdc->g_cmd, recv_len);
}
return status;
}
/**
* @brief usb device transmision complete handler
* @param udev: to the structure of usbd_core_type
* @param ept_num: endpoint number
* @retval status of usb_sts_type
*/
static usb_sts_type class_in_handler(void *udev, uint8_t ept_num)
{
usbd_core_type *pudev = (usbd_core_type *)udev;
cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata;
usb_sts_type status = USB_OK;
/* ...user code...
trans next packet data
*/
usbd_flush_tx_fifo(pudev, ept_num);
pcdc->g_tx_completed = 1;
return status;
}
/**
* @brief usb device endpoint receive data
* @param udev: to the structure of usbd_core_type
* @param ept_num: endpoint number
* @retval status of usb_sts_type
*/
static usb_sts_type class_out_handler(void *udev, uint8_t ept_num)
{
usb_sts_type status = USB_OK;
usbd_core_type *pudev = (usbd_core_type *)udev;
cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata;
/* get endpoint receive data length */
pcdc->g_rxlen = usbd_get_recv_len(pudev, ept_num);
/*set recv flag*/
pcdc->g_rx_completed = 1;
return status;
}
/**
* @brief usb device sof handler
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
static usb_sts_type class_sof_handler(void *udev)
{
UNUSED(udev);
usb_sts_type status = USB_OK;
/* ...user code... */
return status;
}
/**
* @brief usb device event handler
* @param udev: to the structure of usbd_core_type
* @param event: usb device event
* @retval status of usb_sts_type
*/
static usb_sts_type class_event_handler(void *udev, usbd_event_type event)
{
UNUSED(udev);
usb_sts_type status = USB_OK;
switch(event)
{
case USBD_RESET_EVENT:
/* ...user code... */
break;
case USBD_SUSPEND_EVENT:
/* ...user code... */
break;
case USBD_WAKEUP_EVENT:
/* ...user code... */
break;
case USBD_INISOINCOM_EVENT:
break;
case USBD_OUTISOINCOM_EVENT:
break;
default:
break;
}
return status;
}
/**
* @brief usb device cdc init
* @param pcdc: to the structure of cdc_struct
* @retval status of usb_sts_type
*/
static usb_sts_type cdc_struct_init(cdc_struct_type *pcdc)
{
pcdc->g_tx_completed = 1;
pcdc->g_rx_completed = 0;
pcdc->alt_setting = 0;
pcdc->linecoding.bitrate = linecoding.bitrate;
pcdc->linecoding.data = linecoding.data;
pcdc->linecoding.format = linecoding.format;
pcdc->linecoding.parity = linecoding.parity;
return USB_OK;
}
/**
* @brief usb device class rx data process
* @param udev: to the structure of usbd_core_type
* @param recv_data: receive buffer
* @retval receive data len
*/
uint16_t usb_vcp_get_rxdata(void *udev, uint8_t *recv_data)
{
uint16_t i_index = 0;
uint16_t tmp_len = 0;
usbd_core_type *pudev = (usbd_core_type *)udev;
cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata;
if(pcdc->g_rx_completed == 0)
{
return 0;
}
pcdc->g_rx_completed = 0;
tmp_len = pcdc->g_rxlen;
for(i_index = 0; i_index < pcdc->g_rxlen; i_index ++)
{
recv_data[i_index] = pcdc->g_rx_buff[i_index];
}
usbd_ept_recv(pudev, USBD_CDC_BULK_OUT_EPT, pcdc->g_rx_buff, USBD_CDC_OUT_MAXPACKET_SIZE);
return tmp_len;
}
/**
* @brief usb device class send data
* @param udev: to the structure of usbd_core_type
* @param send_data: send data buffer
* @param len: send length
* @retval error status
*/
error_status usb_vcp_send_data(void *udev, uint8_t *send_data, uint16_t len)
{
error_status status = SUCCESS;
usbd_core_type *pudev = (usbd_core_type *)udev;
cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata;
if(pcdc->g_tx_completed)
{
pcdc->g_tx_completed = 0;
usbd_ept_send(pudev, USBD_CDC_BULK_IN_EPT, send_data, len);
}
else
{
status = ERROR;
}
return status;
}
/**
* @brief usb device function
* @param udev: to the structure of usbd_core_type
* @param cmd: request number
* @param buff: request buffer
* @param len: buffer length
* @retval none
*/
static void usb_vcp_cmd_process(void *udev, uint8_t cmd, uint8_t *buff, uint16_t len)
{
UNUSED(len);
usbd_core_type *pudev = (usbd_core_type *)udev;
cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata;
switch(cmd)
{
case SET_LINE_CODING:
pcdc->linecoding.bitrate = (uint32_t)(buff[0] | (buff[1] << 8) | (buff[2] << 16) | (buff[3] <<24));
pcdc->linecoding.format = buff[4];
pcdc->linecoding.parity = buff[5];
pcdc->linecoding.data = buff[6];
#ifdef USB_VIRTUAL_COMPORT
/* set hardware usart */
usb_usart_config(pcdc->linecoding);
#endif
break;
case GET_LINE_CODING:
buff[0] = (uint8_t)pcdc->linecoding.bitrate;
buff[1] = (uint8_t)(pcdc->linecoding.bitrate >> 8);
buff[2] = (uint8_t)(pcdc->linecoding.bitrate >> 16);
buff[3] = (uint8_t)(pcdc->linecoding.bitrate >> 24);
buff[4] = (uint8_t)(pcdc->linecoding.format);
buff[5] = (uint8_t)(pcdc->linecoding.parity);
buff[6] = (uint8_t)(pcdc->linecoding.data);
break;
default:
break;
}
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View file

@ -1,115 +0,0 @@
/**
**************************************************************************
* @file cdc_class.h
* @brief usb cdc class file
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __CDC_CLASS_H
#define __CDC_CLASS_H
#ifdef __cplusplus
extern "C" {
#endif
#include "usb_std.h"
#include "usbd_core.h"
/** @addtogroup AT32F435_437_middlewares_usbd_class
* @{
*/
/** @addtogroup USB_cdc_class
* @{
*/
/** @defgroup USB_cdc_class_definition
* @{
*/
/**
* @brief usb cdc use endpoint define
*/
#define USBD_CDC_INT_EPT 0x82
#define USBD_CDC_BULK_IN_EPT 0x81
#define USBD_CDC_BULK_OUT_EPT 0x01
/**
* @brief usb cdc in and out max packet size define
*/
#define USBD_CDC_IN_MAXPACKET_SIZE 0x40
#define USBD_CDC_OUT_MAXPACKET_SIZE 0x40
#define USBD_CDC_CMD_MAXPACKET_SIZE 0x08
/**
* @}
*/
/** @defgroup USB_cdc_class_exported_types
* @{
*/
/**
* @brief usb cdc class struct
*/
typedef struct
{
uint32_t alt_setting;
uint8_t g_rx_buff[USBD_CDC_OUT_MAXPACKET_SIZE];
uint8_t g_cmd[USBD_CDC_CMD_MAXPACKET_SIZE];
uint8_t g_req;
uint16_t g_len, g_rxlen;
__IO uint8_t g_tx_completed, g_rx_completed;
linecoding_type linecoding;
}cdc_struct_type;
/**
* @}
*/
/** @defgroup USB_cdc_class_exported_functions
* @{
*/
extern usbd_class_handler cdc_class_handler;
uint16_t usb_vcp_get_rxdata(void *udev, uint8_t *recv_data);
error_status usb_vcp_send_data(void *udev, uint8_t *send_data, uint16_t len);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif

View file

@ -1,447 +0,0 @@
/**
**************************************************************************
* @file cdc_desc.c
* @brief usb cdc device descriptor
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
#include "stdio.h"
#include "platform.h"
#include "usb_std.h"
#include "usbd_sdr.h"
#include "usbd_core.h"
#include "cdc_desc.h"
/** @addtogroup AT32F435_437_middlewares_usbd_class
* @{
*/
/** @defgroup USB_cdc_desc
* @brief usb device cdc descriptor
* @{
*/
/** @defgroup USB_cdc_desc_private_functions
* @{
*/
static usbd_desc_t *get_device_descriptor(void);
static usbd_desc_t *get_device_qualifier(void);
static usbd_desc_t *get_device_configuration(void);
static usbd_desc_t *get_device_other_speed(void);
static usbd_desc_t *get_device_lang_id(void);
static usbd_desc_t *get_device_manufacturer_string(void);
static usbd_desc_t *get_device_product_string(void);
static usbd_desc_t *get_device_serial_string(void);
static usbd_desc_t *get_device_interface_string(void);
static usbd_desc_t *get_device_config_string(void);
static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf);
static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len);
static void get_serial_num(void);
static uint8_t g_usbd_desc_buffer[256];
/**
* @brief device descriptor handler structure
*/
usbd_desc_handler cdc_desc_handler =
{
get_device_descriptor,
get_device_qualifier,
get_device_configuration,
get_device_other_speed,
get_device_lang_id,
get_device_manufacturer_string,
get_device_product_string,
get_device_serial_string,
get_device_interface_string,
get_device_config_string,
};
/**
* @brief usb device standard descriptor
*/
#if defined ( __ICCARM__ ) /* iar compiler */
#pragma data_alignment=4
#endif
ALIGNED_HEAD static uint8_t g_usbd_descriptor[USB_DEVICE_DESC_LEN] ALIGNED_TAIL =
{
USB_DEVICE_DESC_LEN, /* bLength */
USB_DESCIPTOR_TYPE_DEVICE, /* bDescriptorType */
0x00, /* bcdUSB */
0x02,
0x02, /* bDeviceClass */
0x00, /* bDeviceSubClass */
0x00, /* bDeviceProtocol */
USB_MAX_EP0_SIZE, /* bMaxPacketSize */
LBYTE(USBD_CDC_VENDOR_ID), /* idVendor */
HBYTE(USBD_CDC_VENDOR_ID), /* idVendor */
LBYTE(USBD_CDC_PRODUCT_ID), /* idProduct */
HBYTE(USBD_CDC_PRODUCT_ID), /* idProduct */
0x00, /* bcdDevice rel. 2.00 */
0x02,
USB_MFC_STRING, /* Index of manufacturer string */
USB_PRODUCT_STRING, /* Index of product string */
USB_SERIAL_STRING, /* Index of serial number string */
1 /* bNumConfigurations */
};
/**
* @brief usb configuration standard descriptor
*/
#if defined ( __ICCARM__ ) /* iar compiler */
#pragma data_alignment=4
#endif
ALIGNED_HEAD static uint8_t g_usbd_configuration[USBD_CDC_CONFIG_DESC_SIZE] ALIGNED_TAIL =
{
USB_DEVICE_CFG_DESC_LEN, /* bLength: configuration descriptor size */
USB_DESCIPTOR_TYPE_CONFIGURATION, /* bDescriptorType: configuration */
LBYTE(USBD_CDC_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */
HBYTE(USBD_CDC_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */
0x02, /* bNumInterfaces: 2 interface */
0x01, /* bConfigurationValue: configuration value */
0x00, /* iConfiguration: index of string descriptor describing
the configuration */
0xC0, /* bmAttributes: self powered */
0x32, /* MaxPower 100 mA: this current is used for detecting vbus */
USB_DEVICE_IF_DESC_LEN, /* bLength: interface descriptor size */
USB_DESCIPTOR_TYPE_INTERFACE, /* bDescriptorType: interface descriptor type */
0x00, /* bInterfaceNumber: number of interface */
0x00, /* bAlternateSetting: alternate set */
0x01, /* bNumEndpoints: number of endpoints */
USB_CLASS_CODE_CDC, /* bInterfaceClass: CDC class code */
0x02, /* bInterfaceSubClass: subclass code, Abstract Control Model*/
0x01, /* bInterfaceProtocol: protocol code, AT Command */
0x00, /* iInterface: index of string descriptor */
0x05, /* bFunctionLength: size of this descriptor in bytes */
USBD_CDC_CS_INTERFACE, /* bDescriptorType: CDC interface descriptor type */
USBD_CDC_SUBTYPE_HEADER, /* bDescriptorSubtype: Header function Descriptor 0x00*/
LBYTE(CDC_BCD_NUM),
HBYTE(CDC_BCD_NUM), /* bcdCDC: USB class definitions for communications */
0x05, /* bFunctionLength: size of this descriptor in bytes */
USBD_CDC_CS_INTERFACE, /* bDescriptorType: CDC interface descriptor type */
USBD_CDC_SUBTYPE_CMF, /* bDescriptorSubtype: Call Management function descriptor subtype 0x01 */
0x00, /* bmCapabilities: 0x00*/
0x01, /* bDataInterface: interface number of data class interface optionally used for call management */
0x04, /* bFunctionLength: size of this descriptor in bytes */
USBD_CDC_CS_INTERFACE, /* bDescriptorType: CDC interface descriptor type */
USBD_CDC_SUBTYPE_ACM, /* bDescriptorSubtype: Abstract Control Management functional descriptor subtype 0x02 */
0x02, /* bmCapabilities: Support Set_Line_Coding and Get_Line_Coding 0x02 */
0x05, /* bFunctionLength: size of this descriptor in bytes */
USBD_CDC_CS_INTERFACE, /* bDescriptorType: CDC interface descriptor type */
USBD_CDC_SUBTYPE_UFD, /* bDescriptorSubtype: Union Function Descriptor subtype 0x06 */
0x00, /* bControlInterface: The interface number of the communications or data class interface 0x00 */
0x01, /* bSubordinateInterface0: interface number of first subordinate interface in the union */
USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */
USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */
USBD_CDC_INT_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */
USB_EPT_DESC_INTERRUPT, /* bmAttributes: endpoint attributes */
LBYTE(USBD_CDC_CMD_MAXPACKET_SIZE),
HBYTE(USBD_CDC_CMD_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */
CDC_HID_BINTERVAL_TIME, /* bInterval: interval for polling endpoint for data transfers */
USB_DEVICE_IF_DESC_LEN, /* bLength: interface descriptor size */
USB_DESCIPTOR_TYPE_INTERFACE, /* bDescriptorType: interface descriptor type */
0x01, /* bInterfaceNumber: number of interface */
0x00, /* bAlternateSetting: alternate set */
0x02, /* bNumEndpoints: number of endpoints */
USB_CLASS_CODE_CDCDATA, /* bInterfaceClass: CDC-data class code */
0x00, /* bInterfaceSubClass: Data interface subclass code 0x00*/
0x00, /* bInterfaceProtocol: data class protocol code 0x00 */
0x00, /* iInterface: index of string descriptor */
USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */
USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */
USBD_CDC_BULK_IN_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */
USB_EPT_DESC_BULK, /* bmAttributes: endpoint attributes */
LBYTE(USBD_CDC_IN_MAXPACKET_SIZE),
HBYTE(USBD_CDC_IN_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */
0x00, /* bInterval: interval for polling endpoint for data transfers */
USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */
USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */
USBD_CDC_BULK_OUT_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */
USB_EPT_DESC_BULK, /* bmAttributes: endpoint attributes */
LBYTE(USBD_CDC_OUT_MAXPACKET_SIZE),
HBYTE(USBD_CDC_OUT_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */
0x00, /* bInterval: interval for polling endpoint for data transfers */
};
/**
* @brief usb string lang id
*/
#if defined ( __ICCARM__ ) /* iar compiler */
#pragma data_alignment=4
#endif
ALIGNED_HEAD static uint8_t g_string_lang_id[USBD_CDC_SIZ_STRING_LANGID] ALIGNED_TAIL =
{
USBD_CDC_SIZ_STRING_LANGID,
USB_DESCIPTOR_TYPE_STRING,
0x09,
0x04,
};
/**
* @brief usb string serial
*/
#if defined ( __ICCARM__ ) /* iar compiler */
#pragma data_alignment=4
#endif
ALIGNED_HEAD static uint8_t g_string_serial[USBD_CDC_SIZ_STRING_SERIAL] ALIGNED_TAIL =
{
USBD_CDC_SIZ_STRING_SERIAL,
USB_DESCIPTOR_TYPE_STRING,
};
/* device descriptor */
static usbd_desc_t device_descriptor =
{
USB_DEVICE_DESC_LEN,
g_usbd_descriptor
};
/* config descriptor */
static usbd_desc_t config_descriptor =
{
USBD_CDC_CONFIG_DESC_SIZE,
g_usbd_configuration
};
/* langid descriptor */
static usbd_desc_t langid_descriptor =
{
USBD_CDC_SIZ_STRING_LANGID,
g_string_lang_id
};
/* serial descriptor */
static usbd_desc_t serial_descriptor =
{
USBD_CDC_SIZ_STRING_SERIAL,
g_string_serial
};
static usbd_desc_t vp_desc;
/**
* @brief standard usb unicode convert
* @param string: source string
* @param unicode_buf: unicode buffer
* @retval length
*/
static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf)
{
uint16_t str_len = 0, id_pos = 2;
uint8_t *tmp_str = string;
while(*tmp_str != '\0')
{
str_len ++;
unicode_buf[id_pos ++] = *tmp_str ++;
unicode_buf[id_pos ++] = 0x00;
}
str_len = str_len * 2 + 2;
unicode_buf[0] = (uint8_t)str_len;
unicode_buf[1] = USB_DESCIPTOR_TYPE_STRING;
return str_len;
}
/**
* @brief usb int convert to unicode
* @param value: int value
* @param pbus: unicode buffer
* @param len: length
* @retval none
*/
static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len)
{
uint8_t idx = 0;
for( idx = 0 ; idx < len ; idx ++)
{
if( ((value >> 28)) < 0xA )
{
pbuf[ 2 * idx] = (value >> 28) + '0';
}
else
{
pbuf[2 * idx] = (value >> 28) + 'A' - 10;
}
value = value << 4;
pbuf[2 * idx + 1] = 0;
}
}
/**
* @brief usb get serial number
* @param none
* @retval none
*/
static void get_serial_num(void)
{
uint32_t serial0, serial1, serial2;
serial0 = *(uint32_t*)MCU_ID1;
serial1 = *(uint32_t*)MCU_ID2;
serial2 = *(uint32_t*)MCU_ID3;
serial0 += serial2;
if (serial0 != 0)
{
usbd_int_to_unicode (serial0, &g_string_serial[2] ,8);
usbd_int_to_unicode (serial1, &g_string_serial[18] ,4);
}
}
/**
* @brief get device descriptor
* @param none
* @retval usbd_desc
*/
static usbd_desc_t *get_device_descriptor(void)
{
return &device_descriptor;
}
/**
* @brief get device qualifier
* @param none
* @retval usbd_desc
*/
static usbd_desc_t * get_device_qualifier(void)
{
return NULL;
}
/**
* @brief get config descriptor
* @param none
* @retval usbd_desc
*/
static usbd_desc_t *get_device_configuration(void)
{
return &config_descriptor;
}
/**
* @brief get other speed descriptor
* @param none
* @retval usbd_desc
*/
static usbd_desc_t *get_device_other_speed(void)
{
return NULL;
}
/**
* @brief get lang id descriptor
* @param none
* @retval usbd_desc
*/
static usbd_desc_t *get_device_lang_id(void)
{
return &langid_descriptor;
}
/**
* @brief get manufacturer descriptor
* @param none
* @retval usbd_desc
*/
static usbd_desc_t *get_device_manufacturer_string(void)
{
vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_CDC_DESC_MANUFACTURER_STRING, g_usbd_desc_buffer);
vp_desc.descriptor = g_usbd_desc_buffer;
return &vp_desc;
}
/**
* @brief get product descriptor
* @param none
* @retval usbd_desc
*/
static usbd_desc_t *get_device_product_string(void)
{
vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_CDC_DESC_PRODUCT_STRING, g_usbd_desc_buffer);
vp_desc.descriptor = g_usbd_desc_buffer;
return &vp_desc;
}
/**
* @brief get serial descriptor
* @param none
* @retval usbd_desc
*/
static usbd_desc_t *get_device_serial_string(void)
{
get_serial_num();
return &serial_descriptor;
}
/**
* @brief get interface descriptor
* @param none
* @retval usbd_desc
*/
static usbd_desc_t *get_device_interface_string(void)
{
vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_CDC_DESC_INTERFACE_STRING, g_usbd_desc_buffer);
vp_desc.descriptor = g_usbd_desc_buffer;
return &vp_desc;
}
/**
* @brief get device config descriptor
* @param none
* @retval usbd_desc
*/
static usbd_desc_t *get_device_config_string(void)
{
vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_CDC_DESC_CONFIGURATION_STRING, g_usbd_desc_buffer);
vp_desc.descriptor = g_usbd_desc_buffer;
return &vp_desc;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View file

@ -1,102 +0,0 @@
/**
**************************************************************************
* @file cdc_desc.h
* @brief usb cdc descriptor header file
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __CDC_DESC_H
#define __CDC_DESC_H
#ifdef __cplusplus
extern "C" {
#endif
#include "cdc_class.h"
#include "usbd_core.h"
/** @addtogroup AT32F435_437_middlewares_usbd_class
* @{
*/
/** @addtogroup USB_cdc_desc
* @{
*/
/** @defgroup USB_cdc_desc_definition
* @{
*/
/**
* @brief usb bcd number define
*/
#define CDC_BCD_NUM 0x0110
/**
* @brief usb vendor id and product id define
*/
#define USBD_CDC_VENDOR_ID 0x2E3C
#define USBD_CDC_PRODUCT_ID 0x5740
/**
* @brief usb descriptor size define
*/
#define USBD_CDC_CONFIG_DESC_SIZE 67
#define USBD_CDC_SIZ_STRING_LANGID 4
#define USBD_CDC_SIZ_STRING_SERIAL 0x1A
/**
* @brief usb string define(vendor, product configuration, interface)
*/
#define USBD_CDC_DESC_MANUFACTURER_STRING "Artery"
#define USBD_CDC_DESC_PRODUCT_STRING "AT32 Virtual Com Port "
#define USBD_CDC_DESC_CONFIGURATION_STRING "Virtual ComPort Config"
#define USBD_CDC_DESC_INTERFACE_STRING "Virtual ComPort Interface"
/**
* @brief usb endpoint interval define
*/
#define CDC_HID_BINTERVAL_TIME 0xFF
/**
* @brief usb mcu id address deine
*/
#define MCU_ID1 (0x1FFFF7E8)
#define MCU_ID2 (0x1FFFF7EC)
#define MCU_ID3 (0x1FFFF7F0)
/**
* @}
*/
extern usbd_desc_handler cdc_desc_handler;
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif

View file

@ -1,189 +0,0 @@
/**
**************************************************************************
* @file usb_core.c
* @brief usb driver
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
#include "platform.h"
#include "usb_core.h"
/** @addtogroup AT32F435_437_middlewares_usb_drivers
* @{
*/
/** @defgroup USB_drivers_core
* @brief usb global drivers core
* @{
*/
/** @defgroup USB_core_private_functions
* @{
*/
usb_sts_type usb_core_config(otg_core_type *udev, uint8_t core_id);
/**
* @brief usb core config
* @param otgdev: to the structure of otg_core_type
* @param core_id: usb core id number (USB_FULL_SPEED_CORE_ID)
* @retval usb_sts_type
*/
usb_sts_type usb_core_config(otg_core_type *otgdev, uint8_t core_id)
{
/* set usb speed and core id */
otgdev->cfg.speed = core_id;
otgdev->cfg.core_id = core_id;
/* default sof out and vbus ignore */
otgdev->cfg.sof_out = FALSE;
otgdev->cfg.vbusig = FALSE;
/* set max size */
otgdev->cfg.max_size = 64;
/* set support number of channel and endpoint */
#ifdef USE_OTG_HOST_MODE
otgdev->cfg.hc_num = USB_HOST_CHANNEL_NUM;
#endif
#ifdef USE_OTG_DEVICE_MODE
otgdev->cfg.ept_num = USB_EPT_MAX_NUM;
#endif
otgdev->cfg.fifo_size = OTG_FIFO_SIZE;
if(core_id == USB_FULL_SPEED_CORE_ID)
{
otgdev->cfg.phy_itface = 2;
}
#ifdef USB_SOF_OUTPUT_ENABLE
otgdev->cfg.sof_out = TRUE;
#endif
#ifdef USB_VBUS_IGNORE
otgdev->cfg.vbusig = TRUE;
#endif
return USB_OK;
}
#ifdef USE_OTG_DEVICE_MODE
/**
* @brief usb device initialization
* @param otgdev: to the structure of otg_core_type
* @param core_id: usb core id number (USB_FULL_SPEED_CORE_ID)
* @param usb_id: select use OTG1 or OTG2
* this parameter can be one of the following values:
* - USB_OTG1_ID
* - USB_OTG2_ID
* @param dev_handler: usb class callback handler
* @param desc_handler: device config callback handler
* @retval usb_sts_type
*/
usb_sts_type usbd_init(otg_core_type *otgdev,
uint8_t core_id, uint8_t usb_id,
usbd_class_handler *class_handler,
usbd_desc_handler *desc_handler)
{
usb_sts_type usb_sts = USB_OK;
/* select use OTG1 or OTG2 */
otgdev->usb_reg = usb_global_select_core(usb_id);
/* usb device core config */
usb_core_config(otgdev, core_id);
if(otgdev->cfg.sof_out)
{
otgdev->usb_reg->gccfg_bit.sofouten = TRUE;
}
if(otgdev->cfg.vbusig)
{
otgdev->usb_reg->gccfg_bit.vbusig = TRUE;
}
/* usb device core init */
usbd_core_init(&(otgdev->dev), otgdev->usb_reg,
class_handler,
desc_handler,
core_id);
return usb_sts;
}
#endif
#ifdef USE_OTG_HOST_MODE
/**
* @brief usb host initialization.
* @param otgdev: to the structure of otg_core_type
* @param core_id: usb core id number (USB_FULL_SPEED_CORE_ID)
* @param usb_id: select use OTG1 or OTG2
* this parameter can be one of the following values:
* - USB_OTG1_ID
* - USB_OTG2_ID
* @param class_handler: usb class callback handler
* @param user_handler: user callback handler
* @retval usb_sts_type
*/
usb_sts_type usbh_init(otg_core_type *otgdev,
uint8_t core_id, uint8_t usb_id,
usbh_class_handler_type *class_handler,
usbh_user_handler_type *user_handler)
{
usb_sts_type status = USB_OK;
/* select use otg1 or otg2 */
otgdev->usb_reg = usb_global_select_core(usb_id);
/* usb core config */
usb_core_config(otgdev, core_id);
if(otgdev->cfg.sof_out)
{
otgdev->usb_reg->gccfg_bit.sofouten = TRUE;
}
if(otgdev->cfg.vbusig)
{
otgdev->usb_reg->gccfg_bit.vbusig = TRUE;
}
/* usb host core init */
usbh_core_init(&otgdev->host, otgdev->usb_reg,
class_handler,
user_handler,
core_id);
return status;
}
#endif
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View file

@ -1,134 +0,0 @@
/**
**************************************************************************
* @file usb_core.h
* @brief usb core header file
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_CORE_H
#define __USB_CORE_H
#ifdef __cplusplus
extern "C" {
#endif
#include "usb_std.h"
#include "usb_conf.h"
#ifdef USE_OTG_DEVICE_MODE
#include "usbd_core.h"
#endif
#ifdef USE_OTG_HOST_MODE
#include "usbh_core.h"
#endif
/** @addtogroup AT32F435_437_middlewares_usb_drivers
* @{
*/
/** @addtogroup USB_drivers_core
* @{
*/
/** @defgroup USB_core_exported_types
* @{
*/
/**
* @brief usb core speed select
*/
typedef enum
{
USB_LOW_SPEED_CORE_ID, /*!< usb low speed core id */
USB_FULL_SPEED_CORE_ID, /*!< usb full speed core id */
USB_HIGH_SPEED_CORE_ID, /*!< usb high speed core id */
} usb_speed_type;
/**
* @brief usb core cofig struct
*/
typedef struct
{
uint8_t speed; /*!< otg speed */
uint8_t dma_en; /*!< dma enable state, not use*/
uint8_t hc_num; /*!< the otg host support number of channel */
uint8_t ept_num; /*!< the otg device support number of endpoint */
uint16_t max_size; /*!< support max packet size */
uint16_t fifo_size; /*!< the usb otg total file size */
uint8_t phy_itface; /*!< usb phy select */
uint8_t core_id; /*!< the usb otg core id */
uint8_t low_power; /*!< the usb otg low power option */
uint8_t sof_out; /*!< the sof signal output */
uint8_t usb_id; /*!< select otgfs1 or otgfs2 */
uint8_t vbusig; /*!< vbus ignore */
} usb_core_cfg;
/**
* @brief usb otg core struct type
*/
typedef struct
{
usb_reg_type *usb_reg; /*!< the usb otg register type */
#ifdef USE_OTG_DEVICE_MODE
usbd_core_type dev; /*!< the usb device core type */
#endif
#ifdef USE_OTG_HOST_MODE
usbh_core_type host; /*!< the usb host core type */
#endif
usb_core_cfg cfg; /*!< the usb otg core config type */
} otg_core_type;
usb_sts_type usb_core_config(otg_core_type *otgdev, uint8_t core_id);
#ifdef USE_OTG_DEVICE_MODE
usb_sts_type usbd_init(otg_core_type *udev,
uint8_t core_id, uint8_t usb_id,
usbd_class_handler *class_handler,
usbd_desc_handler *desc_handler);
#endif
#ifdef USE_OTG_HOST_MODE
usb_sts_type usbh_init(otg_core_type *hdev,
uint8_t core_id, uint8_t usb_id,
usbh_class_handler_type *class_handler,
usbh_user_handler_type *user_handler);
#endif
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif

View file

@ -1,383 +0,0 @@
/**
**************************************************************************
* @file usb_std.h
* @brief usb standard header file
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_STD_H
#define __USB_STD_H
#ifdef __cplusplus
extern "C" {
#endif
/* includes ------------------------------------------------------------------*/
#include "usb_conf.h"
/** @addtogroup AT32F435_437_middlewares_usb_drivers
* @{
*/
/** @addtogroup USB_standard
* @{
*/
/** @defgroup USB_standard_define
* @{
*/
/**
* @brief usb request recipient
*/
#define USB_REQ_RECIPIENT_DEVICE 0x00 /*!< usb request recipient device */
#define USB_REQ_RECIPIENT_INTERFACE 0x01 /*!< usb request recipient interface */
#define USB_REQ_RECIPIENT_ENDPOINT 0x02 /*!< usb request recipient endpoint */
#define USB_REQ_RECIPIENT_OTHER 0x03 /*!< usb request recipient other */
#define USB_REQ_RECIPIENT_MASK 0x1F /*!< usb request recipient mask */
/**
* @brief usb request type
*/
#define USB_REQ_TYPE_STANDARD 0x00 /*!< usb request type standard */
#define USB_REQ_TYPE_CLASS 0x20 /*!< usb request type class */
#define USB_REQ_TYPE_VENDOR 0x40 /*!< usb request type vendor */
#define USB_REQ_TYPE_RESERVED 0x60 /*!< usb request type reserved */
/**
* @brief usb request data transfer direction
*/
#define USB_REQ_DIR_HTD 0x00 /*!< usb request data transfer direction host to device */
#define USB_REQ_DIR_DTH 0x80 /*!< usb request data transfer direction device to host */
/**
* @brief usb standard device requests codes
*/
#define USB_STD_REQ_GET_STATUS 0 /*!< usb request code status */
#define USB_STD_REQ_CLEAR_FEATURE 1 /*!< usb request code clear feature */
#define USB_STD_REQ_SET_FEATURE 3 /*!< usb request code feature */
#define USB_STD_REQ_SET_ADDRESS 5 /*!< usb request code address */
#define USB_STD_REQ_GET_DESCRIPTOR 6 /*!< usb request code get descriptor */
#define USB_STD_REQ_SET_DESCRIPTOR 7 /*!< usb request code set descriptor */
#define USB_STD_REQ_GET_CONFIGURATION 8 /*!< usb request code get configuration */
#define USB_STD_REQ_SET_CONFIGURATION 9 /*!< usb request code set configuration */
#define USB_STD_REQ_GET_INTERFACE 10 /*!< usb request code get interface */
#define USB_STD_REQ_SET_INTERFACE 11 /*!< usb request code set interface */
#define USB_STD_REQ_SYNCH_FRAME 12 /*!< usb request code synch frame */
/**
* @brief usb standard device type
*/
#define USB_DESCIPTOR_TYPE_DEVICE 1 /*!< usb standard device type device */
#define USB_DESCIPTOR_TYPE_CONFIGURATION 2 /*!< usb standard device type configuration */
#define USB_DESCIPTOR_TYPE_STRING 3 /*!< usb standard device type string */
#define USB_DESCIPTOR_TYPE_INTERFACE 4 /*!< usb standard device type interface */
#define USB_DESCIPTOR_TYPE_ENDPOINT 5 /*!< usb standard device type endpoint */
#define USB_DESCIPTOR_TYPE_DEVICE_QUALIFIER 6 /*!< usb standard device type qualifier */
#define USB_DESCIPTOR_TYPE_OTHER_SPEED 7 /*!< usb standard device type other speed */
#define USB_DESCIPTOR_TYPE_INTERFACE_POWER 8 /*!< usb standard device type interface power */
/**
* @brief usb standard string type
*/
#define USB_LANGID_STRING 0 /*!< usb standard string type lang id */
#define USB_MFC_STRING 1 /*!< usb standard string type mfc */
#define USB_PRODUCT_STRING 2 /*!< usb standard string type product */
#define USB_SERIAL_STRING 3 /*!< usb standard string type serial */
#define USB_CONFIG_STRING 4 /*!< usb standard string type config */
#define USB_INTERFACE_STRING 5 /*!< usb standard string type interface */
/**
* @brief usb configuration attributes
*/
#define USB_CONF_REMOTE_WAKEUP 2 /*!< usb configuration attributes remote wakeup */
#define USB_CONF_SELF_POWERED 1 /*!< usb configuration attributes self powered */
/**
* @brief usb standard feature selectors
*/
#define USB_FEATURE_EPT_HALT 0 /*!< usb standard feature selectors endpoint halt */
#define USB_FEATURE_REMOTE_WAKEUP 1 /*!< usb standard feature selectors remote wakeup */
#define USB_FEATURE_TEST_MODE 2 /*!< usb standard feature selectors test mode */
/**
* @brief usb device connect state
*/
typedef enum
{
USB_CONN_STATE_DEFAULT =1, /*!< usb device connect state default */
USB_CONN_STATE_ADDRESSED, /*!< usb device connect state address */
USB_CONN_STATE_CONFIGURED, /*!< usb device connect state configured */
USB_CONN_STATE_SUSPENDED /*!< usb device connect state suspend */
}usbd_conn_state;
/**
* @brief endpoint 0 state
*/
#define USB_EPT0_IDLE 0 /*!< usb endpoint state idle */
#define USB_EPT0_SETUP 1 /*!< usb endpoint state setup */
#define USB_EPT0_DATA_IN 2 /*!< usb endpoint state data in */
#define USB_EPT0_DATA_OUT 3 /*!< usb endpoint state data out */
#define USB_EPT0_STATUS_IN 4 /*!< usb endpoint state status in */
#define USB_EPT0_STATUS_OUT 5 /*!< usb endpoint state status out */
#define USB_EPT0_STALL 6 /*!< usb endpoint state stall */
/**
* @brief usb descriptor length
*/
#define USB_DEVICE_QUALIFIER_DESC_LEN 0x0A /*!< usb qualifier descriptor length */
#define USB_DEVICE_DESC_LEN 0x12 /*!< usb device descriptor length */
#define USB_DEVICE_CFG_DESC_LEN 0x09 /*!< usb configuration descriptor length */
#define USB_DEVICE_IF_DESC_LEN 0x09 /*!< usb interface descriptor length */
#define USB_DEVICE_EPT_LEN 0x07 /*!< usb endpoint descriptor length */
#define USB_DEVICE_OTG_DESC_LEN 0x03 /*!< usb otg descriptor length */
#define USB_DEVICE_LANGID_STR_DESC_LEN 0x04 /*!< usb lang id string descriptor length */
#define USB_DEVICE_OTHER_SPEED_DESC_SIZ_LEN 0x09 /*!< usb other speed descriptor length */
/**
* @brief usb class code
*/
#define USB_CLASS_CODE_AUDIO 0x01 /*!< usb class code audio */
#define USB_CLASS_CODE_CDC 0x02 /*!< usb class code cdc */
#define USB_CLASS_CODE_HID 0x03 /*!< usb class code hid */
#define USB_CLASS_CODE_PRINTER 0x07 /*!< usb class code printer */
#define USB_CLASS_CODE_MSC 0x08 /*!< usb class code msc */
#define USB_CLASS_CODE_HUB 0x09 /*!< usb class code hub */
#define USB_CLASS_CODE_CDCDATA 0x0A /*!< usb class code cdc data */
#define USB_CLASS_CODE_CCID 0x0B /*!< usb class code ccid */
#define USB_CLASS_CODE_VIDEO 0x0E /*!< usb class code video */
#define USB_CLASS_CODE_VENDOR 0xFF /*!< usb class code vendor */
/**
* @brief usb endpoint type
*/
#define USB_EPT_DESC_CONTROL 0x00 /*!< usb endpoint description type control */
#define USB_EPT_DESC_ISO 0x01 /*!< usb endpoint description type iso */
#define USB_EPT_DESC_BULK 0x02 /*!< usb endpoint description type bulk */
#define USB_EPT_DESC_INTERRUPT 0x03 /*!< usb endpoint description type interrupt */
#define USB_EPT_DESC_NSYNC 0x00 /*!< usb endpoint description nsync */
#define USB_ETP_DESC_ASYNC 0x04 /*!< usb endpoint description async */
#define USB_ETP_DESC_ADAPTIVE 0x08 /*!< usb endpoint description adaptive */
#define USB_ETP_DESC_SYNC 0x0C /*!< usb endpoint description sync */
#define USB_EPT_DESC_DATA_EPT 0x00 /*!< usb endpoint description data */
#define USB_EPT_DESC_FD_EPT 0x10 /*!< usb endpoint description fd */
#define USB_EPT_DESC_FDDATA_EPT 0x20 /*!< usb endpoint description fddata */
/**
* @brief usb cdc class descriptor define
*/
#define USBD_CDC_CS_INTERFACE 0x24
#define USBD_CDC_CS_ENDPOINT 0x25
/**
* @brief usb cdc class sub-type define
*/
#define USBD_CDC_SUBTYPE_HEADER 0x00
#define USBD_CDC_SUBTYPE_CMF 0x01
#define USBD_CDC_SUBTYPE_ACM 0x02
#define USBD_CDC_SUBTYPE_UFD 0x06
/**
* @brief usb cdc class request code define
*/
#define SET_LINE_CODING 0x20
#define GET_LINE_CODING 0x21
/**
* @brief usb cdc class set line coding struct
*/
typedef struct
{
uint32_t bitrate; /* line coding baud rate */
uint8_t format; /* line coding foramt */
uint8_t parity; /* line coding parity */
uint8_t data; /* line coding data bit */
}linecoding_type;
/**
* @brief usb hid class descriptor define
*/
#define HID_CLASS_DESC_HID 0x21
#define HID_CLASS_DESC_REPORT 0x22
#define HID_CLASS_DESC_PHYSICAL 0x23
/**
* @brief usb hid class request code define
*/
#define HID_REQ_SET_PROTOCOL 0x0B
#define HID_REQ_GET_PROTOCOL 0x03
#define HID_REQ_SET_IDLE 0x0A
#define HID_REQ_GET_IDLE 0x02
#define HID_REQ_SET_REPORT 0x09
#define HID_REQ_GET_REPORT 0x01
#define HID_DESCRIPTOR_TYPE 0x21
#define HID_REPORT_DESC 0x22
/**
* @brief endpoint 0 max size
*/
#define USB_MAX_EP0_SIZE 64 /*!< usb endpoint 0 max size */
/**
* @brief usb swap address
*/
#define SWAPBYTE(addr) (uint16_t)(((uint16_t)(*((uint8_t *)(addr)))) + \
(((uint16_t)(*(((uint8_t *)(addr)) + 1))) << 8)) /*!< swap address */
/**
* @brief min and max define
*/
#define MIN(a, b) (uint16_t)(((a) < (b)) ? (a) : (b)) /*!< min define*/
#define MAX(a, b) (uint16_t)(((a) > (b)) ? (a) : (b)) /*!< max define*/
/**
* @brief low byte and high byte define
*/
#define LBYTE(x) ((uint8_t)(x & 0x00FF)) /*!< low byte define */
#define HBYTE(x) ((uint8_t)((x & 0xFF00) >>8)) /*!< high byte define*/
/**
* @brief usb return status
*/
typedef enum
{
USB_OK, /*!< usb status ok */
USB_FAIL, /*!< usb status fail */
USB_WAIT, /*!< usb status wait */
USB_NOT_SUPPORT, /*!< usb status not support */
USB_ERROR, /*!< usb status error */
}usb_sts_type;
/**
* @brief format of usb setup data
*/
typedef struct
{
uint8_t bmRequestType; /*!< characteristics of request */
uint8_t bRequest; /*!< specific request */
uint16_t wValue; /*!< word-sized field that varies according to request */
uint16_t wIndex; /*!< word-sized field that varies according to request
typically used to pass an index or offset */
uint16_t wLength; /*!< number of bytes to transfer if there is a data stage */
} usb_setup_type;
/**
* @brief format of standard device descriptor
*/
typedef struct
{
uint8_t bLength; /*!< size of this descriptor in bytes */
uint8_t bDescriptorType; /*!< device descriptor type */
uint16_t bcdUSB; /*!< usb specification release number */
uint8_t bDeviceClass; /*!< class code (assigned by the usb-if) */
uint8_t bDeviceSubClass; /*!< subclass code (assigned by the usb-if) */
uint8_t bDeviceProtocol; /*!< protocol code ((assigned by the usb-if)) */
uint8_t bMaxPacketSize0; /*!< maximum packet size for endpoint zero */
uint16_t idVendor; /*!< verndor id ((assigned by the usb-if)) */
uint16_t idProduct; /*!< product id ((assigned by the usb-if)) */
uint16_t bcdDevice; /*!< device release number in binary-coded decimal */
uint8_t iManufacturer; /*!< index of string descriptor describing manufacturer */
uint8_t iProduct; /*!< index of string descriptor describing product */
uint8_t iSerialNumber; /*!< index of string descriptor describing serial number */
uint8_t bNumConfigurations; /*!< number of possible configurations */
} usb_device_desc_type;
/**
* @brief format of standard configuration descriptor
*/
typedef struct
{
uint8_t bLength; /*!< size of this descriptor in bytes */
uint8_t bDescriptorType; /*!< configuration descriptor type */
uint16_t wTotalLength; /*!< total length of data returned for this configuration */
uint8_t bNumInterfaces; /*!< number of interfaces supported by this configuration */
uint8_t bConfigurationValue; /*!< value to use as an argument to the SetConfiguration() request */
uint8_t iConfiguration; /*!< index of string descriptor describing this configuration */
uint8_t bmAttributes; /*!< configuration characteristics
D7 reserved
D6 self-powered
D5 remote wakeup
D4~D0 reserved */
uint8_t bMaxPower; /*!< maximum power consumption of the usb device from the bus */
}usb_configuration_desc_type;
/**
* @brief format of standard interface descriptor
*/
typedef struct
{
uint8_t bLength; /*!< size of this descriptor in bytes */
uint8_t bDescriptorType; /*!< interface descriptor type */
uint8_t bInterfaceNumber; /*!< number of this interface */
uint8_t bAlternateSetting; /*!< value used to select this alternate setting for the interface */
uint8_t bNumEndpoints; /*!< number of endpoints used by this interface */
uint8_t bInterfaceClass; /*!< class code (assigned by the usb-if) */
uint8_t bInterfaceSubClass; /*!< subclass code (assigned by the usb-if) */
uint8_t bInterfaceProtocol; /*!< protocol code (assigned by the usb-if) */
uint8_t iInterface; /*!< index of string descriptor describing this interface */
} usb_interface_desc_type;
/**
* @brief format of standard endpoint descriptor
*/
typedef struct
{
uint8_t bLength; /*!< size of this descriptor in bytes */
uint8_t bDescriptorType; /*!< endpoint descriptor type */
uint8_t bEndpointAddress; /*!< the address of the endpoint on the usb device described by this descriptor */
uint8_t bmAttributes; /*!< describes the endpoints attributes when it is configured using bConfiguration value */
uint16_t wMaxPacketSize; /*!< maximum packet size this endpoint */
uint8_t bInterval; /*!< interval for polling endpoint for data transfers */
} usb_endpoint_desc_type;
/**
* @brief format of header
*/
typedef struct
{
uint8_t bLength; /*!< size of this descriptor in bytes */
uint8_t bDescriptorType; /*!< descriptor type */
} usb_header_desc_type;
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif

View file

@ -1,884 +0,0 @@
/**
**************************************************************************
* @file usbd_core.c
* @brief usb device driver
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
#include "platform.h"
#include "usb_core.h"
#include "usbd_core.h"
#include "usbd_sdr.h"
/** @addtogroup AT32F435_437_middlewares_usbd_drivers
* @{
*/
/** @defgroup USBD_drivers_core
* @brief usb device drivers core
* @{
*/
/** @defgroup USBD_core_private_functions
* @{
*/
/**
* @brief usb core in transfer complete handler
* @param udev: to the structure of usbd_core_type
* @param ept_addr: endpoint number
* @retval none
*/
void usbd_core_in_handler(usbd_core_type *udev, uint8_t ept_addr)
{
/* get endpoint info*/
usb_ept_info *ept_info = &udev->ept_in[ept_addr & 0x7F];
if(ept_addr == 0)
{
if(udev->ept0_sts == USB_EPT0_DATA_IN)
{
if(ept_info->rem0_len > ept_info->maxpacket)
{
ept_info->rem0_len -= ept_info->maxpacket;
usbd_ept_send(udev, 0, ept_info->trans_buf,
MIN(ept_info->rem0_len, ept_info->maxpacket));
}
/* endpoint 0 */
else if(ept_info->last_len == ept_info->maxpacket
&& ept_info->ept0_slen >= ept_info->maxpacket
&& ept_info->ept0_slen < udev->ept0_wlength)
{
ept_info->last_len = 0;
usbd_ept_send(udev, 0, 0, 0);
usbd_ept_recv(udev, ept_addr, 0, 0);
}
else
{
if(udev->class_handler->ept0_tx_handler != 0 &&
udev->conn_state == USB_CONN_STATE_CONFIGURED)
{
udev->class_handler->ept0_tx_handler(udev);
}
usbd_ctrl_recv_status(udev);
}
}
}
else if(udev->class_handler->in_handler != 0 &&
udev->conn_state == USB_CONN_STATE_CONFIGURED)
{
/* other user define endpoint */
udev->class_handler->in_handler(udev, ept_addr);
}
}
/**
* @brief usb core out transfer complete handler
* @param udev: to the structure of usbd_core_type
* @param ept_addr: endpoint number
* @retval none
*/
void usbd_core_out_handler(usbd_core_type *udev, uint8_t ept_addr)
{
/* get endpoint info*/
usb_ept_info *ept_info = &udev->ept_out[ept_addr & 0x7F];
if(ept_addr == 0)
{
/* endpoint 0 */
if(udev->ept0_sts == USB_EPT0_DATA_OUT)
{
if(ept_info->rem0_len > ept_info->maxpacket)
{
ept_info->rem0_len -= ept_info->maxpacket;
usbd_ept_recv(udev, ept_addr, ept_info->trans_buf,
MIN(ept_info->rem0_len, ept_info->maxpacket));
}
else
{
if(udev->class_handler->ept0_rx_handler != 0)
{
udev->class_handler->ept0_rx_handler(udev);
}
usbd_ctrl_send_status(udev);
}
}
}
else if(udev->class_handler->out_handler != 0 &&
udev->conn_state == USB_CONN_STATE_CONFIGURED)
{
/* other user define endpoint */
udev->class_handler->out_handler(udev, ept_addr);
}
}
/**
* @brief usb core setup transfer complete handler
* @param udev: to the structure of usbd_core_type
* @param ept_addr: endpoint number
* @retval none
*/
void usbd_core_setup_handler(usbd_core_type *udev, uint8_t ept_num)
{
UNUSED(ept_num);
/* setup parse */
usbd_setup_request_parse(&udev->setup, udev->setup_buffer);
/* set ept0 status */
udev->ept0_sts = USB_EPT0_SETUP;
udev->ept0_wlength = udev->setup.wLength;
switch(udev->setup.bmRequestType & USB_REQ_RECIPIENT_MASK)
{
case USB_REQ_RECIPIENT_DEVICE:
/* recipient device request */
usbd_device_request(udev);
break;
case USB_REQ_RECIPIENT_INTERFACE:
/* recipient interface request */
usbd_interface_request(udev);
break;
case USB_REQ_RECIPIENT_ENDPOINT:
/* recipient endpoint request */
usbd_endpoint_request(udev);
break;
default:
break;
}
}
/**
* @brief usb control endpoint send data
* @param udev: to the structure of usbd_core_type
* @param ept_addr: endpoint number
* @param buffer: send data buffer
* @param len: send data length
* @retval none
*/
void usbd_ctrl_send(usbd_core_type *udev, uint8_t *buffer, uint16_t len)
{
usb_ept_info *ept_info = &udev->ept_in[0];
ept_info->ept0_slen = len;
ept_info->rem0_len = len;
udev->ept0_sts = USB_EPT0_DATA_IN;
usbd_ept_send(udev, 0, buffer, len);
}
/**
* @brief usb control endpoint recv data
* @param udev: to the structure of usbd_core_type
* @param ept_addr: endpoint number
* @param buffer: recv data buffer
* @param len: recv data length
* @retval none
*/
void usbd_ctrl_recv(usbd_core_type *udev, uint8_t *buffer, uint16_t len)
{
usb_ept_info *ept_info = &udev->ept_out[0];
ept_info->ept0_slen = len;
ept_info->rem0_len = len;
udev->ept0_sts = USB_EPT0_DATA_OUT;
usbd_ept_recv(udev, 0, buffer, len);
}
/**
* @brief usb control endpoint send in status
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_ctrl_send_status(usbd_core_type *udev)
{
udev->ept0_sts = USB_EPT0_STATUS_IN;
usbd_ept_send(udev, 0, 0, 0);
}
/**
* @brief usb control endpoint send out status
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_ctrl_recv_status(usbd_core_type *udev)
{
udev->ept0_sts = USB_EPT0_STATUS_OUT;
usbd_ept_recv(udev, 0, 0, 0);
}
/**
* @brief clear endpoint stall
* @param udev: to the structure of usbd_core_type
* @param ept_addr: endpoint number
* @retval none
*/
void usbd_clear_stall(usbd_core_type *udev, uint8_t ept_addr)
{
usb_ept_info *ept_info;
usb_reg_type *usbx = udev->usb_reg;
if(ept_addr & 0x80)
{
/* in endpoint */
ept_info = &udev->ept_in[ept_addr & 0x7F];
}
else
{
/* out endpoint */
ept_info = &udev->ept_out[ept_addr & 0x7F];
}
usb_ept_clear_stall(usbx, ept_info);
ept_info->stall = 0;
}
/**
* @brief usb set endpoint to stall status
* @param udev: to the structure of usbd_core_type
* @param ept_addr: endpoint number
* @retval none
*/
void usbd_set_stall(usbd_core_type *udev, uint8_t ept_addr)
{
usb_ept_info *ept_info;
usb_reg_type *usbx = udev->usb_reg;
if(ept_addr & 0x80)
{
/* in endpoint */
ept_info = &udev->ept_in[ept_addr & 0x7F];
}
else
{
/* out endpoint */
ept_info = &udev->ept_out[ept_addr & 0x7F];
}
usb_ept_stall(usbx, ept_info);
ept_info->stall = 1;
}
/**
* @brief un-support device request
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_ctrl_unsupport(usbd_core_type *udev)
{
/* return stall status */
usbd_set_stall(udev, 0x00);
usbd_set_stall(udev, 0x80);
}
/**
* @brief get endpoint receive data length
* @param udev: to the structure of usbd_core_type
* @param ept_addr: endpoint number
* @retval data receive len
*/
uint32_t usbd_get_recv_len(usbd_core_type *udev, uint8_t ept_addr)
{
usb_ept_info *ept = &udev->ept_out[ept_addr & 0x7F];
return ept->trans_len;
}
/**
* @brief usb open endpoint
* @param udev: to the structure of usbd_core_type
* @param ept_addr: endpoint number
* @param ept_type: endpoint type
* @param maxpacket: endpoint support max buffer size
* @retval none
*/
void usbd_ept_open(usbd_core_type *udev, uint8_t ept_addr, uint8_t ept_type, uint16_t maxpacket)
{
usb_reg_type *usbx = udev->usb_reg;
usb_ept_info *ept_info;
if((ept_addr & 0x80) == 0)
{
/* out endpoint info */
ept_info = &udev->ept_out[ept_addr & 0x7F];
ept_info->inout = EPT_DIR_OUT;
}
else
{
/* in endpoint info */
ept_info = &udev->ept_in[ept_addr & 0x7F];
ept_info->inout = EPT_DIR_IN;
}
/* set endpoint maxpacket and type */
ept_info->maxpacket = maxpacket;
ept_info->trans_type = ept_type;
/* open endpoint */
usb_ept_open(usbx, ept_info);
}
/**
* @brief usb close endpoint
* @param udev: to the structure of usbd_core_type
* @param ept_addr: endpoint number
* @retval none
*/
void usbd_ept_close(usbd_core_type *udev, uint8_t ept_addr)
{
usb_ept_info *ept_info;
if(ept_addr & 0x80)
{
/* in endpoint */
ept_info = &udev->ept_in[ept_addr & 0x7F];
}
else
{
/* out endpoint */
ept_info = &udev->ept_out[ept_addr & 0x7F];
}
/* close endpoint */
usb_ept_close(udev->usb_reg, ept_info);
}
/**
* @brief usb device connect to host
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_connect(usbd_core_type *udev)
{
usb_connect(udev->usb_reg);
}
/**
* @brief usb device disconnect to host
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_disconnect(usbd_core_type *udev)
{
usb_disconnect(udev->usb_reg);
}
/**
* @brief usb device set device address.
* @param udev: to the structure of usbd_core_type
* @param address: host assignment address
* @retval none
*/
void usbd_set_device_addr(usbd_core_type *udev, uint8_t address)
{
usb_set_address(udev->usb_reg, address);
}
/**
* @brief usb endpoint structure initialization
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usb_ept_default_init(usbd_core_type *udev)
{
uint8_t i_index = 0;
/* init in endpoint info structure */
for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++)
{
udev->ept_in[i_index].eptn = i_index;
udev->ept_in[i_index].ept_address = i_index;
udev->ept_in[i_index].inout = EPT_DIR_IN;
udev->ept_in[i_index].maxpacket = 0;
udev->ept_in[i_index].trans_buf = 0;
udev->ept_in[i_index].total_len = 0;
}
/* init out endpoint info structure */
for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++)
{
udev->ept_out[i_index].eptn = i_index;
udev->ept_out[i_index].ept_address = i_index;
udev->ept_out[i_index].inout = EPT_DIR_OUT;
udev->ept_out[i_index].maxpacket = 0;
udev->ept_out[i_index].trans_buf = 0;
udev->ept_out[i_index].total_len = 0;
}
}
/**
* @brief endpoint send data
* @param udev: to the structure of usbd_core_type
* @param ept_addr: endpoint number
* @param buffer: send data buffer
* @param len: send data length
* @retval none
*/
void usbd_ept_send(usbd_core_type *udev, uint8_t ept_addr, uint8_t *buffer, uint16_t len)
{
/* get endpoint info struct and register */
usb_reg_type *usbx = udev->usb_reg;
usb_ept_info *ept_info = &udev->ept_in[ept_addr & 0x7F];
otg_eptin_type *ept_in = USB_INEPT(usbx, ept_info->eptn);
otg_device_type *dev = OTG_DEVICE(usbx);
uint32_t pktcnt;
/* set send data buffer and length */
ept_info->trans_buf = buffer;
ept_info->total_len = len;
ept_info->trans_len = 0;
/* transfer data len is zero */
if(ept_info->total_len == 0)
{
ept_in->dieptsiz_bit.pktcnt = 1;
ept_in->dieptsiz_bit.xfersize = 0;
}
else
{
if((ept_addr & 0x7F) == 0) // endpoint 0
{
/* endpoint 0 */
if(ept_info->total_len > ept_info->maxpacket)
{
ept_info->total_len = ept_info->maxpacket;
}
/* set transfer size */
ept_in->dieptsiz_bit.xfersize = ept_info->total_len;
/* set packet count */
ept_in->dieptsiz_bit.pktcnt = 1;
ept_info->last_len = ept_info->total_len;
}
else
{
/* other endpoint */
/* packet count */
pktcnt = (ept_info->total_len + ept_info->maxpacket - 1) / ept_info->maxpacket;
/* set transfer size */
ept_in->dieptsiz_bit.xfersize = ept_info->total_len;
/* set packet count */
ept_in->dieptsiz_bit.pktcnt = pktcnt;
if(ept_info->trans_type == EPT_ISO_TYPE)
{
ept_in->dieptsiz_bit.mc = 1;
}
}
}
if(ept_info->trans_type != EPT_ISO_TYPE)
{
if(ept_info->total_len > 0)
{
/* set in endpoint tx fifo empty interrupt mask */
dev->diepempmsk |= 1 << ept_info->eptn;
}
}
if(ept_info->trans_type == EPT_ISO_TYPE)
{
if((dev->dsts_bit.soffn & 0x1) == 0)
{
ept_in->diepctl_bit.setd1pid = TRUE;
}
else
{
ept_in->diepctl_bit.setd0pid = TRUE;
}
}
/* clear endpoint nak */
ept_in->diepctl_bit.cnak = TRUE;
/* endpoint enable */
ept_in->diepctl_bit.eptena = TRUE;
if(ept_info->trans_type == EPT_ISO_TYPE)
{
/* write data to fifo */
usb_write_packet(usbx, ept_info->trans_buf, ept_info->eptn, ept_info->total_len);
}
}
/**
* @brief endpoint receive data
* @param udev: to the structure of usbd_core_type
* @param ept_addr: endpoint number
* @param buffer: receive data buffer
* @param len: receive data length
* @retval none
*/
void usbd_ept_recv(usbd_core_type *udev, uint8_t ept_addr, uint8_t *buffer, uint16_t len)
{
/* get endpoint info struct and register */
usb_reg_type *usbx = udev->usb_reg;
usb_ept_info *ept_info = &udev->ept_out[ept_addr & 0x7F];
otg_eptout_type *ept_out = USB_OUTEPT(usbx, ept_info->eptn);
otg_device_type *dev = OTG_DEVICE(usbx);
uint32_t pktcnt;
/* set receive data buffer and length */
ept_info->trans_buf = buffer;
ept_info->total_len = len;
ept_info->trans_len = 0;
if((ept_addr & 0x7F) == 0)
{
/* endpoint 0 */
ept_info->total_len = ept_info->maxpacket;
}
if(ept_info->total_len == 0 || ((ept_addr & 0x7F) == 0))
{
/* set transfer size */
ept_out->doeptsiz_bit.xfersize = ept_info->maxpacket;
/* set packet count */
ept_out->doeptsiz_bit.pktcnt = 1;
}
else
{
pktcnt = (ept_info->total_len + ept_info->maxpacket - 1) / ept_info->maxpacket;
/* set transfer size */
ept_out->doeptsiz_bit.xfersize = ept_info->maxpacket * pktcnt;
/* set packet count */
ept_out->doeptsiz_bit.pktcnt = pktcnt;
}
if(ept_info->trans_type == EPT_ISO_TYPE)
{
if((dev->dsts_bit.soffn & 0x01) == 0)
{
ept_out->doepctl_bit.setd1pid = TRUE;
}
else
{
ept_out->doepctl_bit.setd0pid = TRUE;
}
}
/* clear endpoint nak */
ept_out->doepctl_bit.cnak = TRUE;
/* endpoint enable */
ept_out->doepctl_bit.eptena = TRUE;
}
/**
* @brief get usb connect state
* @param udev: to the structure of usbd_core_type
* @retval usb connect state
*/
usbd_conn_state usbd_connect_state_get(usbd_core_type *udev)
{
return udev->conn_state;
}
/**
* @brief usb device remote wakeup
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_remote_wakeup(usbd_core_type *udev)
{
/* check device is in suspend mode */
if(usb_suspend_status_get(udev->usb_reg) == 1)
{
/* set connect state */
udev->conn_state = udev->old_conn_state;
/* open phy clock */
usb_open_phy_clk(udev->usb_reg);
/* set remote wakeup */
usb_remote_wkup_set(udev->usb_reg);
/* delay 10 ms */
usb_delay_ms(10);
/* clear remote wakup */
usb_remote_wkup_clear(udev->usb_reg);
}
}
/**
* @brief usb device enter suspend mode
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_enter_suspend(usbd_core_type *udev)
{
/* check device is in suspend mode */
if(usb_suspend_status_get(udev->usb_reg) == 1)
{
/* stop phy clk */
usb_stop_phy_clk(udev->usb_reg);
}
}
/**
* @brief usb device flush in endpoint fifo
* @param udev: to the structure of usbd_core_type
* @param ept_num: endpoint number
* @retval none
*/
void usbd_flush_tx_fifo(usbd_core_type *udev, uint8_t ept_num)
{
/* flush endpoint tx fifo */
usb_flush_tx_fifo(udev->usb_reg, ept_num & 0x1F);
}
/**
* @brief usb device endpoint fifo alloc
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_fifo_alloc(usbd_core_type *udev)
{
usb_reg_type *usbx = udev->usb_reg;
if(usbx == OTG1_GLOBAL)
{
/* set receive fifo size */
usb_set_rx_fifo(usbx, USBD_RX_SIZE);
/* set endpoint0 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT0, USBD_EP0_TX_SIZE);
/* set endpoint1 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT1, USBD_EP1_TX_SIZE);
/* set endpoint2 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT2, USBD_EP2_TX_SIZE);
/* set endpoint3 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT3, USBD_EP3_TX_SIZE);
if(USB_EPT_MAX_NUM == 8)
{
/* set endpoint4 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT4, USBD_EP4_TX_SIZE);
/* set endpoint5 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT5, USBD_EP5_TX_SIZE);
/* set endpoint6 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT6, USBD_EP6_TX_SIZE);
/* set endpoint7 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT7, USBD_EP7_TX_SIZE);
}
}
#ifdef OTG2_GLOBAL
if(usbx == OTG2_GLOBAL)
{
/* set receive fifo size */
usb_set_rx_fifo(usbx, USBD2_RX_SIZE);
/* set endpoint0 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT0, USBD2_EP0_TX_SIZE);
/* set endpoint1 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT1, USBD2_EP1_TX_SIZE);
/* set endpoint2 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT2, USBD2_EP2_TX_SIZE);
/* set endpoint3 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT3, USBD2_EP3_TX_SIZE);
if(USB_EPT_MAX_NUM == 8)
{
/* set endpoint4 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT4, USBD2_EP4_TX_SIZE);
/* set endpoint5 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT5, USBD2_EP5_TX_SIZE);
/* set endpoint6 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT6, USBD2_EP6_TX_SIZE);
/* set endpoint7 tx fifo size */
usb_set_tx_fifo(usbx, USB_EPT7, USBD2_EP7_TX_SIZE);
}
}
#endif
}
/**
* @brief usb device core initialization
* @param udev: to the structure of usbd_core_type
* @param usb_reg: usb otgfs peripheral global register
* this parameter can be one of the following values:
* OTG1_GLOBAL , OTG2_GLOBAL
* @param class_handler: usb class handler
* @param desc_handler: device config handler
* @param core_id: usb core id number
* @retval usb_sts_type
*/
usb_sts_type usbd_core_init(usbd_core_type *udev,
usb_reg_type *usb_reg,
usbd_class_handler *class_handler,
usbd_desc_handler *desc_handler,
uint8_t core_id)
{
UNUSED(core_id);
usb_reg_type *usbx;
otg_device_type *dev;
otg_eptin_type *ept_in;
otg_eptout_type *ept_out;
uint32_t i_index;
udev->usb_reg = usb_reg;
usbx = usb_reg;
dev = OTG_DEVICE(usbx);
/* set connect state */
udev->conn_state = USB_CONN_STATE_DEFAULT;
/* device class config */
udev->device_addr = 0;
udev->class_handler = class_handler;
udev->desc_handler = desc_handler;
/* set device disconnect */
usbd_disconnect(udev);
/* set endpoint to default status */
usb_ept_default_init(udev);
/* disable usb global interrupt */
usb_interrupt_disable(usbx);
/* init global register */
usb_global_init(usbx);
/* set device mode */
usb_global_set_mode(usbx, OTG_DEVICE_MODE);
/* open phy clock */
usb_open_phy_clk(udev->usb_reg);
/* set periodic frame interval */
dev->dcfg_bit.perfrint = DCFG_PERFRINT_80;
/* set device speed to full-speed */
dev->dcfg_bit.devspd = USB_DCFG_FULL_SPEED;
/* flush all tx fifo */
usb_flush_tx_fifo(usbx, 16);
/* flush share rx fifo */
usb_flush_rx_fifo(usbx);
/* clear all endpoint interrupt flag and mask */
dev->daint = 0xFFFFFFFF;
dev->daintmsk = 0;
dev->diepmsk = 0;
dev->doepmsk = 0;
for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++)
{
usbx->dieptxfn[i_index] = 0;
}
/* endpoint fifo alloc */
usbd_fifo_alloc(udev);
/* disable all in endpoint */
for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++)
{
ept_in = USB_INEPT(usbx, i_index);
if(ept_in->diepctl_bit.eptena)
{
ept_in->diepctl = 0;
ept_in->diepctl_bit.eptdis = TRUE;
ept_in->diepctl_bit.snak = TRUE;
}
else
{
ept_in->diepctl = 0;
}
ept_in->dieptsiz = 0;
ept_in->diepint = 0xFF;
}
/* disable all out endpoint */
for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++)
{
ept_out = USB_OUTEPT(usbx, i_index);
if(ept_out->doepctl_bit.eptena)
{
ept_out->doepctl = 0;
ept_out->doepctl_bit.eptdis = TRUE;
ept_out->doepctl_bit.snak = TRUE;
}
else
{
ept_out->doepctl = 0;
}
ept_out->doeptsiz = 0;
ept_out->doepint = 0xFF;
}
dev->diepmsk_bit.txfifoudrmsk = TRUE;
/* clear global interrupt and mask */
usbx->gintmsk = 0;
usbx->gintsts = 0xBFFFFFFF;
/* enable global interrupt mask */
usbx->gintmsk = USB_OTG_SOF_INT | USB_OTG_RXFLVL_INT |
USB_OTG_USBSUSP_INT | USB_OTG_USBRST_INT |
USB_OTG_ENUMDONE_INT | USB_OTG_IEPT_INT |
USB_OTG_OEPT_INT | USB_OTG_INCOMISOIN_INT |
USB_OTG_INCOMPIP_INCOMPISOOUT_INT | USB_OTG_WKUP_INT |
USB_OTG_OTGINT_INT;
/* usb connect */
usbd_connect(udev);
/* enable global interrupt */
usb_interrupt_enable(usbx);
return USB_OK;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View file

@ -1,185 +0,0 @@
/**
**************************************************************************
* @file usbd_core.h
* @brief usb device core header file
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_CORE_H
#define __USBD_CORE_H
#ifdef __cplusplus
extern "C" {
#endif
#include "usb_conf.h"
#include "usb_std.h"
/** @addtogroup AT32F435_437_middlewares_usbd_drivers
* @{
*/
/** @addtogroup USBD_drivers_core
* @{
*/
/** @defgroup USBD_core_exported_types
* @{
*/
#ifdef USE_OTG_DEVICE_MODE
/**
* @brief usb device event
*/
typedef enum
{
USBD_NOP_EVENT, /*!< usb device nop event */
USBD_RESET_EVENT, /*!< usb device reset event */
USBD_SUSPEND_EVENT, /*!< usb device suspend event */
USBD_WAKEUP_EVENT, /*!< usb device wakeup event */
USBD_DISCONNECT_EVNET, /*!< usb device disconnect event */
USBD_INISOINCOM_EVENT, /*!< usb device inisoincom event */
USBD_OUTISOINCOM_EVENT, /*!< usb device outisoincom event */
USBD_ERR_EVENT /*!< usb device error event */
}usbd_event_type;
/**
* @brief usb device descriptor struct
*/
typedef struct
{
uint16_t length; /*!< descriptor length */
uint8_t *descriptor; /*!< descriptor string */
}usbd_desc_t;
/**
* @brief usb device descriptor handler
*/
typedef struct
{
usbd_desc_t *(*get_device_descriptor)(void); /*!< get device descriptor callback */
usbd_desc_t *(*get_device_qualifier)(void); /*!< get device qualifier callback */
usbd_desc_t *(*get_device_configuration)(void); /*!< get device configuration callback */
usbd_desc_t *(*get_device_other_speed)(void); /*!< get device other speed callback */
usbd_desc_t *(*get_device_lang_id)(void); /*!< get device lang id callback */
usbd_desc_t *(*get_device_manufacturer_string)(void); /*!< get device manufacturer callback */
usbd_desc_t *(*get_device_product_string)(void); /*!< get device product callback */
usbd_desc_t *(*get_device_serial_string)(void); /*!< get device serial callback */
usbd_desc_t *(*get_device_interface_string)(void); /*!< get device interface string callback */
usbd_desc_t *(*get_device_config_string)(void); /*!< get device device config callback */
}usbd_desc_handler;
/**
* @brief usb device class handler
*/
typedef struct
{
usb_sts_type (*init_handler)(void *udev); /*!< usb class init handler */
usb_sts_type (*clear_handler)(void *udev); /*!< usb class clear handler */
usb_sts_type (*setup_handler)(void *udev, usb_setup_type *setup); /*!< usb class setup handler */
usb_sts_type (*ept0_tx_handler)(void *udev); /*!< usb class endpoint 0 tx complete handler */
usb_sts_type (*ept0_rx_handler)(void *udev); /*!< usb class endpoint 0 rx complete handler */
usb_sts_type (*in_handler)(void *udev, uint8_t ept_num); /*!< usb class in transfer complete handler */
usb_sts_type (*out_handler)(void *udev, uint8_t ept_num); /*!< usb class out transfer complete handler */
usb_sts_type (*sof_handler)(void *udev); /*!< usb class sof handler */
usb_sts_type (*event_handler)(void *udev, usbd_event_type event); /*!< usb class event handler */
void *pdata; /*!< usb class data pointer */
}usbd_class_handler;
/**
* @brief usb device core struct type
*/
typedef struct
{
usb_reg_type *usb_reg; /*!< usb register pointer */
usbd_class_handler *class_handler; /*!< usb device class handler pointer */
usbd_desc_handler *desc_handler; /*!< usb device descriptor handler pointer */
usb_ept_info ept_in[USB_EPT_MAX_NUM]; /*!< usb in endpoint infomation struct */
usb_ept_info ept_out[USB_EPT_MAX_NUM]; /*!< usb out endpoint infomation struct */
usb_setup_type setup; /*!< usb setup type struct */
uint8_t setup_buffer[12]; /*!< usb setup request buffer */
uint8_t ept0_sts; /*!< usb control endpoint 0 state */
uint8_t speed; /*!< usb speed */
uint16_t ept0_wlength; /*!< usb endpoint 0 transfer length */
usbd_conn_state conn_state; /*!< usb current connect state */
usbd_conn_state old_conn_state; /*!< usb save the previous connect state */
uint8_t device_addr; /*!< device address */
uint8_t remote_wakup; /*!< remote wakeup state */
uint8_t default_config; /*!< usb default config state */
uint8_t dev_config; /*!< usb device config state */
uint32_t config_status; /*!< usb configure status */
}usbd_core_type;
void usbd_core_in_handler(usbd_core_type *udev, uint8_t ept_num);
void usbd_core_out_handler(usbd_core_type *udev, uint8_t ept_num);
void usbd_core_setup_handler(usbd_core_type *udev, uint8_t ept_num);
void usbd_ctrl_unsupport(usbd_core_type *udev);
void usbd_ctrl_send(usbd_core_type *udev, uint8_t *buffer, uint16_t len);
void usbd_ctrl_recv(usbd_core_type *udev, uint8_t *buffer, uint16_t len);
void usbd_ctrl_send_status(usbd_core_type *udev);
void usbd_ctrl_recv_status(usbd_core_type *udev);
void usbd_set_stall(usbd_core_type *udev, uint8_t ept_addr);
void usbd_clear_stall(usbd_core_type *udev, uint8_t ept_addr);
void usbd_ept_open(usbd_core_type *udev, uint8_t ept_addr, uint8_t ept_type, uint16_t maxpacket);
void usbd_ept_close(usbd_core_type *udev, uint8_t ept_addr);
void usbd_ept_send(usbd_core_type *udev, uint8_t ept_num, uint8_t *buffer, uint16_t len);
void usbd_ept_recv(usbd_core_type *udev, uint8_t ept_num, uint8_t *buffer, uint16_t len);
void usbd_connect(usbd_core_type *udev);
void usbd_disconnect(usbd_core_type *udev);
void usbd_set_device_addr(usbd_core_type *udev, uint8_t address);
uint32_t usbd_get_recv_len(usbd_core_type *udev, uint8_t ept_addr);
void usb_ept_defaut_init(usbd_core_type *udev);
usbd_conn_state usbd_connect_state_get(usbd_core_type *udev);
void usbd_remote_wakeup(usbd_core_type *udev);
void usbd_enter_suspend(usbd_core_type *udev);
void usbd_flush_tx_fifo(usbd_core_type *udev, uint8_t ept_num);
void usbd_fifo_alloc(usbd_core_type *udev);
usb_sts_type usbd_core_init(usbd_core_type *udev,
usb_reg_type *usb_reg,
usbd_class_handler *class_handler,
usbd_desc_handler *desc_handler,
uint8_t core_id);
#endif
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif

View file

@ -1,539 +0,0 @@
/**
**************************************************************************
* @file usbd_int.c
* @brief usb interrupt request
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
#include "platform.h"
#include "usbd_int.h"
/** @addtogroup AT32F435_437_middlewares_usbd_drivers
* @{
*/
/** @defgroup USBD_drivers_interrupt
* @brief usb device interrupt
* @{
*/
/** @defgroup USBD_int_private_functions
* @{
*/
/**
* @brief usb device interrput request handler.
* @param otgdev: to the structure of otg_core_type
* @retval none
*/
void usbd_irq_handler(otg_core_type *otgdev)
{
otg_global_type *usbx = otgdev->usb_reg;
usbd_core_type *udev = &otgdev->dev;
uint32_t intsts = usb_global_get_all_interrupt(usbx);
/* check current device mode */
if(usbx->gintsts_bit.curmode == 0)
{
/* mode mismatch interrupt */
if(intsts & USB_OTG_MODEMIS_FLAG)
{
usb_global_clear_interrupt(usbx, USB_OTG_MODEMIS_FLAG);
}
/* in endpoint interrupt */
if(intsts & USB_OTG_IEPT_FLAG)
{
usbd_inept_handler(udev);
}
/* out endpoint interrupt */
if(intsts & USB_OTG_OEPT_FLAG)
{
usbd_outept_handler(udev);
}
/* usb reset interrupt */
if(intsts & USB_OTG_USBRST_FLAG)
{
usbd_reset_handler(udev);
usb_global_clear_interrupt(usbx, USB_OTG_USBRST_FLAG);
}
/* sof interrupt */
if(intsts & USB_OTG_SOF_FLAG)
{
usbd_sof_handler(udev);
usb_global_clear_interrupt(usbx, USB_OTG_SOF_FLAG);
}
/* enumeration done interrupt */
if(intsts & USB_OTG_ENUMDONE_FLAG)
{
usbd_enumdone_handler(udev);
usb_global_clear_interrupt(usbx, USB_OTG_ENUMDONE_FLAG);
}
/* rx non-empty interrupt, indicates that there is at least one
data packet pending to be read in rx fifo */
if(intsts & USB_OTG_RXFLVL_FLAG)
{
usbd_rxflvl_handler(udev);
}
/* incomplete isochronous in transfer interrupt */
if(intsts & USB_OTG_INCOMISOIN_FLAG)
{
usbd_incomisioin_handler(udev);
usb_global_clear_interrupt(usbx, USB_OTG_INCOMISOIN_FLAG);
}
#ifndef USB_VBUS_IGNORE
/* disconnect detected interrupt */
if(intsts & USB_OTG_OTGINT_FLAG)
{
uint32_t tmp = udev->usb_reg->gotgint;
if(udev->usb_reg->gotgint_bit.sesenddet)
usbd_discon_handler(udev);
udev->usb_reg->gotgint = tmp;
usb_global_clear_interrupt(usbx, USB_OTG_OTGINT_FLAG);
}
#endif
/* incomplete isochronous out transfer interrupt */
if(intsts & USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG)
{
usbd_incomisoout_handler(udev);
usb_global_clear_interrupt(usbx, USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG);
}
/* resume/remote wakeup interrupt */
if(intsts & USB_OTG_WKUP_FLAG)
{
usbd_wakeup_handler(udev);
usb_global_clear_interrupt(usbx, USB_OTG_WKUP_FLAG);
}
/* usb suspend interrupt */
if(intsts & USB_OTG_USBSUSP_FLAG)
{
usbd_suspend_handler(udev);
usb_global_clear_interrupt(usbx, USB_OTG_USBSUSP_FLAG);
}
}
}
/**
* @brief usb write tx fifo.
* @param udev: to the structure of usbd_core_type
* @param ept_num: endpoint number
* @retval none
*/
void usb_write_empty_txfifo(usbd_core_type *udev, uint32_t ept_num)
{
otg_global_type *usbx = udev->usb_reg;
usb_ept_info *ept_info = &udev->ept_in[ept_num];
uint32_t length = ept_info->total_len - ept_info->trans_len;
uint32_t wlen = 0;
if(length > ept_info->maxpacket)
{
length = ept_info->maxpacket;
}
wlen = (length + 3) / 4;
while((USB_INEPT(usbx, ept_num)->dtxfsts & USB_OTG_DTXFSTS_INEPTFSAV) > wlen &&
(ept_info->trans_len < ept_info->total_len) && (ept_info->total_len != 0))
{
length = ept_info->total_len - ept_info->trans_len;
if(length > ept_info->maxpacket)
{
length = ept_info->maxpacket;
}
wlen = (length + 3) / 4;
usb_write_packet(usbx, ept_info->trans_buf, ept_num, length);
ept_info->trans_buf += length;
ept_info->trans_len += length;
}
if(length <= 0)
{
OTG_DEVICE(usbx)->diepempmsk &= ~(0x1 << ept_num);
}
}
/**
* @brief usb in endpoint handler
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_inept_handler(usbd_core_type *udev)
{
otg_global_type *usbx = udev->usb_reg;
uint32_t ept_num = 0, ept_int;
uint32_t intsts;
/*get all endpoint interrut */
intsts = usb_get_all_in_interrupt(usbx);
while(intsts)
{
if(intsts & 0x1)
{
/* get endpoint interrupt flag */
ept_int = usb_ept_in_interrupt(usbx, ept_num);
/* transfer completed interrupt */
if(ept_int & USB_OTG_DIEPINT_XFERC_FLAG)
{
OTG_DEVICE(usbx)->diepempmsk &= ~(1 << ept_num);
usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_XFERC_FLAG);
usbd_core_in_handler(udev, ept_num);
}
/* timeout condition interrupt */
if(ept_int & USB_OTG_DIEPINT_TIMEOUT_FLAG)
{
usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_TIMEOUT_FLAG);
}
/* in token received when tx fifo is empty */
if(ept_int & USB_OTG_DIEPINT_INTKNTXFEMP_FLAG)
{
usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_INTKNTXFEMP_FLAG);
}
/* in endpoint nak effective */
if(ept_int & USB_OTG_DIEPINT_INEPTNAK_FLAG)
{
usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_INEPTNAK_FLAG);
}
/* endpoint disable interrupt */
if(ept_int & USB_OTG_DIEPINT_EPTDISD_FLAG)
{
usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_EPTDISD_FLAG);
}
/* transmit fifo empty interrupt */
if(ept_int & USB_OTG_DIEPINT_TXFEMP_FLAG)
{
usb_write_empty_txfifo(udev, ept_num);
}
}
ept_num ++;
intsts >>= 1;
}
}
/**
* @brief usb out endpoint handler
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_outept_handler(usbd_core_type *udev)
{
otg_global_type *usbx = udev->usb_reg;
uint32_t ept_num = 0, ept_int;
uint32_t intsts;
/* get all out endpoint interrupt */
intsts = usb_get_all_out_interrupt(usbx);
while(intsts)
{
if(intsts & 0x1)
{
/* get out endpoint interrupt */
ept_int = usb_ept_out_interrupt(usbx, ept_num);
/* transfer completed interrupt */
if(ept_int & USB_OTG_DOEPINT_XFERC_FLAG)
{
usb_ept_out_clear(usbx, ept_num , USB_OTG_DOEPINT_XFERC_FLAG);
usbd_core_out_handler(udev, ept_num);
}
/* setup phase done interrupt */
if(ept_int & USB_OTG_DOEPINT_SETUP_FLAG)
{
usb_ept_out_clear(usbx, ept_num , USB_OTG_DOEPINT_SETUP_FLAG);
usbd_core_setup_handler(udev, ept_num);
if(udev->device_addr != 0)
{
OTG_DEVICE(udev->usb_reg)->dcfg_bit.devaddr = udev->device_addr;
udev->device_addr = 0;
}
}
/* endpoint disable interrupt */
if(ept_int & USB_OTG_DOEPINT_OUTTEPD_FLAG)
{
usb_ept_out_clear(usbx, ept_num , USB_OTG_DOEPINT_OUTTEPD_FLAG);
}
}
ept_num ++;
intsts >>= 1;
}
}
/**
* @brief usb enumeration done handler
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_enumdone_handler(usbd_core_type *udev)
{
otg_global_type *usbx = udev->usb_reg;
usb_ept0_setup(usbx);
usbx->gusbcfg_bit.usbtrdtim = USB_TRDTIM_16;
/* open endpoint 0 out */
usbd_ept_open(udev, 0x00, EPT_CONTROL_TYPE, 0x40);
/* open endpoint 0 in */
usbd_ept_open(udev, 0x80, EPT_CONTROL_TYPE, 0x40);
/* usb connect state set to default */
udev->conn_state = USB_CONN_STATE_DEFAULT;
/* clear callback */
if(udev->class_handler->clear_handler != 0)
udev->class_handler->clear_handler(udev);
}
/**
* @brief usb rx non-empty handler
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_rxflvl_handler(usbd_core_type *udev)
{
otg_global_type *usbx = udev->usb_reg;
uint32_t stsp;
uint32_t count;
uint32_t pktsts;
usb_ept_info *ept_info;
/* disable rxflvl interrupt */
usb_global_interrupt_enable(usbx, USB_OTG_RXFLVL_INT, FALSE);
/* get rx status */
stsp = usbx->grxstsp;
/*get the byte count of receive */
count = (stsp & USB_OTG_GRXSTSP_BCNT) >> 4;
/* get packet status */
pktsts = (stsp &USB_OTG_GRXSTSP_PKTSTS) >> 17;
/* get endpoint infomation struct */
ept_info = &udev->ept_out[stsp & USB_OTG_GRXSTSP_EPTNUM];
/* received out data packet */
if(pktsts == USB_OUT_STS_DATA)
{
if(count != 0)
{
/* read packet to buffer */
usb_read_packet(usbx, ept_info->trans_buf, (stsp & USB_OTG_GRXSTSP_EPTNUM), count);
ept_info->trans_buf += count;
ept_info->trans_len += count;
}
}
/* setup data received */
else if ( pktsts == USB_SETUP_STS_DATA)
{
/* read packet to buffer */
usb_read_packet(usbx, udev->setup_buffer, (stsp & USB_OTG_GRXSTSP_EPTNUM), count);
ept_info->trans_len += count;
}
/* enable rxflvl interrupt */
usb_global_interrupt_enable(usbx, USB_OTG_RXFLVL_INT, TRUE);
}
/**
* @brief usb disconnect handler
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_discon_handler(usbd_core_type *udev)
{
/* disconnect callback handler */
if(udev->class_handler->event_handler != 0)
udev->class_handler->event_handler(udev, USBD_DISCONNECT_EVNET);
}
/**
* @brief usb incomplete out handler
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_incomisoout_handler(usbd_core_type *udev)
{
if(udev->class_handler->event_handler != 0)
udev->class_handler->event_handler(udev, USBD_OUTISOINCOM_EVENT);
}
/**
* @brief usb incomplete in handler
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_incomisioin_handler(usbd_core_type *udev)
{
if(udev->class_handler->event_handler != 0)
udev->class_handler->event_handler(udev, USBD_INISOINCOM_EVENT);
}
/**
* @brief usb device reset interrupt request handler.
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_reset_handler(usbd_core_type *udev)
{
otg_global_type *usbx = udev->usb_reg;
otg_device_type *dev = OTG_DEVICE(usbx);
uint32_t i_index = 0;
/* disable remote wakeup singal */
dev->dctl_bit.rwkupsig = FALSE;
/* endpoint fifo alloc */
usbd_fifo_alloc(udev);
/* flush all tx fifo */
usb_flush_tx_fifo(usbx, 0x10);
/* clear in and out endpoint interrupt flag */
for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++)
{
USB_INEPT(usbx, i_index)->diepint = 0xFF;
USB_OUTEPT(usbx, i_index)->doepint = 0xFF;
}
/* clear endpoint flag */
dev->daint = 0xFFFFFFFF;
/*clear endpoint interrupt mask */
dev->daintmsk = 0x10001;
/* enable out endpoint xfer, eptdis, setup interrupt mask */
dev->doepmsk_bit.xfercmsk = TRUE;
dev->doepmsk_bit.eptdismsk = TRUE;
dev->doepmsk_bit.setupmsk = TRUE;
/* enable in endpoint xfer, eptdis, timeout interrupt mask */
dev->diepmsk_bit.xfercmsk = TRUE;
dev->diepmsk_bit.eptdismsk = TRUE;
dev->diepmsk_bit.timeoutmsk = TRUE;
/* set device address to 0 */
usb_set_address(usbx, 0);
/* enable endpoint 0 */
usb_ept0_start(usbx);
/* usb connect state set to default */
udev->conn_state = USB_CONN_STATE_DEFAULT;
/* user define reset event */
if(udev->class_handler->event_handler)
udev->class_handler->event_handler(udev, USBD_RESET_EVENT);
}
/**
* @brief usb device sof interrupt request handler.
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_sof_handler(usbd_core_type *udev)
{
/* user sof handler in class define */
if(udev->class_handler->sof_handler)
udev->class_handler->sof_handler(udev);
}
/**
* @brief usb device suspend interrupt request handler.
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_suspend_handler(usbd_core_type *udev)
{
otg_global_type *usbx = udev->usb_reg;
if(OTG_DEVICE(usbx)->dsts_bit.suspsts)
{
/* save connect state */
udev->old_conn_state = udev->conn_state;
/* set current state to suspend */
udev->conn_state = USB_CONN_STATE_SUSPENDED;
/* enter suspend mode */
usbd_enter_suspend(udev);
/* user suspend handler */
if(udev->class_handler->event_handler != 0)
udev->class_handler->event_handler(udev, USBD_SUSPEND_EVENT);
}
}
/**
* @brief usb device wakup interrupt request handler.
* @param udev: to the structure of usbd_core_type
* @retval none
*/
void usbd_wakeup_handler(usbd_core_type *udev)
{
otg_global_type *usbx = udev->usb_reg;
/* clear remote wakeup bit */
OTG_DEVICE(usbx)->dctl_bit.rwkupsig = FALSE;
/* exit suspend mode */
usb_open_phy_clk(udev->usb_reg);
/* restore connect state */
udev->conn_state = udev->old_conn_state;
/* user suspend handler */
if(udev->class_handler->event_handler != 0)
udev->class_handler->event_handler(udev, USBD_WAKEUP_EVENT);
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View file

@ -1,80 +0,0 @@
/**
**************************************************************************
* @file usbd_int.h
* @brief usb interrupt header file
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_INT_H
#define __USBD_INT_H
#ifdef __cplusplus
extern "C" {
#endif
/** @addtogroup AT32F435_437_middlewares_usbd_drivers
* @{
*/
/** @addtogroup USBD_drivers_int
* @{
*/
/** @defgroup USBD_interrupt_exported_types
* @{
*/
/* includes ------------------------------------------------------------------*/
#include "usbd_core.h"
#include "usb_core.h"
void usbd_irq_handler(otg_core_type *udev);
void usbd_ept_handler(usbd_core_type *udev);
void usbd_reset_handler(usbd_core_type *udev);
void usbd_sof_handler(usbd_core_type *udev);
void usbd_suspend_handler(usbd_core_type *udev);
void usbd_wakeup_handler(usbd_core_type *udev);
void usbd_inept_handler(usbd_core_type *udev);
void usbd_outept_handler(usbd_core_type *udev);
void usbd_enumdone_handler(usbd_core_type *udev);
void usbd_rxflvl_handler(usbd_core_type *udev);
void usbd_incomisioin_handler(usbd_core_type *udev);
void usbd_discon_handler(usbd_core_type *udev);
void usbd_incomisoout_handler(usbd_core_type *udev);
void usb_write_empty_txfifo(usbd_core_type *udev, uint32_t ept_num);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif

View file

@ -1,535 +0,0 @@
/**
**************************************************************************
* @file usbd_sdr.c
* @brief usb standard device request
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
#include "platform.h"
#include "usbd_sdr.h"
/** @addtogroup AT32F435_437_middlewares_usbd_drivers
* @{
*/
/** @defgroup USBD_drivers_standard_request
* @brief usb device standard_request
* @{
*/
/** @defgroup USBD_sdr_private_functions
* @{
*/
static usb_sts_type usbd_get_descriptor(usbd_core_type *udev);
static usb_sts_type usbd_set_address(usbd_core_type *udev);
static usb_sts_type usbd_get_status(usbd_core_type *udev);
static usb_sts_type usbd_clear_feature(usbd_core_type *udev);
static usb_sts_type usbd_set_feature(usbd_core_type *udev);
static usb_sts_type usbd_get_configuration(usbd_core_type *udev);
static usb_sts_type usbd_set_configuration(usbd_core_type *udev);
/**
* @brief usb parse standard setup request
* @param setup: setup structure
* @param buf: setup buffer
* @retval none
*/
void usbd_setup_request_parse(usb_setup_type *setup, uint8_t *buf)
{
setup->bmRequestType = *(uint8_t *) buf;
setup->bRequest = *(uint8_t *) (buf + 1);
setup->wValue = SWAPBYTE(buf + 2);
setup->wIndex = SWAPBYTE(buf + 4);
setup->wLength = SWAPBYTE(buf + 6);
}
/**
* @brief get usb standard device description request
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
static usb_sts_type usbd_get_descriptor(usbd_core_type *udev)
{
usb_sts_type ret = USB_OK;
uint16_t len = 0;
usbd_desc_t *desc = NULL;
uint8_t desc_type = udev->setup.wValue >> 8;
switch(desc_type)
{
case USB_DESCIPTOR_TYPE_DEVICE:
desc = udev->desc_handler->get_device_descriptor();
break;
case USB_DESCIPTOR_TYPE_CONFIGURATION:
desc = udev->desc_handler->get_device_configuration();
break;
case USB_DESCIPTOR_TYPE_STRING:
{
uint8_t str_desc = (uint8_t)udev->setup.wValue;
switch(str_desc)
{
case USB_LANGID_STRING:
desc = udev->desc_handler->get_device_lang_id();
break;
case USB_MFC_STRING:
desc = udev->desc_handler->get_device_manufacturer_string();
break;
case USB_PRODUCT_STRING:
desc = udev->desc_handler->get_device_product_string();
break;
case USB_SERIAL_STRING:
desc = udev->desc_handler->get_device_serial_string();
break;
case USB_CONFIG_STRING:
desc = udev->desc_handler->get_device_config_string();
break;
case USB_INTERFACE_STRING:
desc = udev->desc_handler->get_device_interface_string();
break;
default:
udev->class_handler->setup_handler(udev, &udev->setup);
return ret;
}
break;
}
case USB_DESCIPTOR_TYPE_DEVICE_QUALIFIER:
usbd_ctrl_unsupport(udev);
break;
case USB_DESCIPTOR_TYPE_OTHER_SPEED:
usbd_ctrl_unsupport(udev);
return ret;
default:
usbd_ctrl_unsupport(udev);
return ret;
}
if(desc != NULL)
{
if((desc->length != 0) && (udev->setup.wLength != 0))
{
len = MIN(desc->length , udev->setup.wLength);
usbd_ctrl_send(udev, desc->descriptor, len);
}
}
return ret;
}
/**
* @brief this request sets the device address
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
static usb_sts_type usbd_set_address(usbd_core_type *udev)
{
usb_sts_type ret = USB_OK;
usb_setup_type *setup = &udev->setup;
uint8_t dev_addr;
/* if wIndex or wLength are non-zero, then the behavior of
the device is not specified
*/
if(setup->wIndex == 0 && setup->wLength == 0)
{
dev_addr = (uint8_t)(setup->wValue) & 0x7f;
/* device behavior when this request is received
while the device is in the configured state is not specified.*/
if(udev->conn_state == USB_CONN_STATE_CONFIGURED )
{
usbd_ctrl_unsupport(udev);
}
else
{
udev->device_addr = dev_addr;
if(dev_addr != 0)
{
udev->conn_state = USB_CONN_STATE_ADDRESSED;
}
else
{
udev->conn_state = USB_CONN_STATE_DEFAULT;
}
usbd_ctrl_send_status(udev);
}
}
else
{
usbd_ctrl_unsupport(udev);
}
return ret;
}
/**
* @brief get usb status request
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
static usb_sts_type usbd_get_status(usbd_core_type *udev)
{
usb_sts_type ret = USB_OK;
switch(udev->conn_state)
{
case USB_CONN_STATE_ADDRESSED:
case USB_CONN_STATE_CONFIGURED:
if(udev->remote_wakup)
{
udev->config_status |= USB_CONF_REMOTE_WAKEUP;
}
usbd_ctrl_send(udev, (uint8_t *)(&udev->config_status), 2);
break;
default:
usbd_ctrl_unsupport(udev);
break;
}
return ret;
}
/**
* @brief clear usb feature request
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
static usb_sts_type usbd_clear_feature(usbd_core_type *udev)
{
usb_sts_type ret = USB_OK;
usb_setup_type *setup = &udev->setup;
switch(udev->conn_state)
{
case USB_CONN_STATE_ADDRESSED:
case USB_CONN_STATE_CONFIGURED:
if(setup->wValue == USB_FEATURE_REMOTE_WAKEUP)
{
udev->remote_wakup = 0;
udev->config_status &= ~USB_CONF_REMOTE_WAKEUP;
udev->class_handler->setup_handler(udev, &udev->setup);
usbd_ctrl_send_status(udev);
}
break;
default:
usbd_ctrl_unsupport(udev);
break;
}
return ret;
}
/**
* @brief set usb feature request
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
static usb_sts_type usbd_set_feature(usbd_core_type *udev)
{
usb_sts_type ret = USB_OK;
usb_setup_type *setup = &udev->setup;
if(setup->wValue == USB_FEATURE_REMOTE_WAKEUP)
{
udev->remote_wakup = 1;
udev->class_handler->setup_handler(udev, &udev->setup);
usbd_ctrl_send_status(udev);
}
return ret;
}
/**
* @brief get usb configuration request
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
static usb_sts_type usbd_get_configuration(usbd_core_type *udev)
{
usb_sts_type ret = USB_OK;
usb_setup_type *setup = &udev->setup;
if(setup->wLength != 1)
{
usbd_ctrl_unsupport(udev);
}
else
{
switch(udev->conn_state)
{
case USB_CONN_STATE_ADDRESSED:
udev->default_config = 0;
usbd_ctrl_send(udev, (uint8_t *)(&udev->default_config), 1);
break;
case USB_CONN_STATE_CONFIGURED:
usbd_ctrl_send(udev, (uint8_t *)(&udev->dev_config), 1);
break;
default:
usbd_ctrl_unsupport(udev);
break;
}
}
return ret;
}
/**
* @brief sets the usb device configuration request
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
static usb_sts_type usbd_set_configuration(usbd_core_type *udev)
{
usb_sts_type ret = USB_OK;
static uint8_t config_value;
usb_setup_type *setup = &udev->setup;
config_value = (uint8_t)setup->wValue;
if(setup->wIndex == 0 && setup->wLength == 0)
{
switch(udev->conn_state)
{
case USB_CONN_STATE_ADDRESSED:
if(config_value)
{
udev->dev_config = config_value;
udev->conn_state = USB_CONN_STATE_CONFIGURED;
udev->class_handler->init_handler(udev);
usbd_ctrl_send_status(udev);
}
else
{
usbd_ctrl_send_status(udev);
}
break;
case USB_CONN_STATE_CONFIGURED:
if(config_value == 0)
{
udev->conn_state = USB_CONN_STATE_ADDRESSED;
udev->dev_config = config_value;
udev->class_handler->clear_handler(udev);
usbd_ctrl_send_status(udev);
}
else if(config_value == udev->dev_config)
{
udev->class_handler->clear_handler(udev);
udev->dev_config = config_value;
udev->class_handler->init_handler(udev);
usbd_ctrl_send_status(udev);
}
else
{
usbd_ctrl_send_status(udev);
}
break;
default:
usbd_ctrl_unsupport(udev);
break;
}
}
else
{
usbd_ctrl_unsupport(udev);
}
return ret;
}
/**
* @brief standard usb device requests
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
usb_sts_type usbd_device_request(usbd_core_type *udev)
{
usb_sts_type ret = USB_OK;
usb_setup_type *setup = &udev->setup;
if((setup->bmRequestType & USB_REQ_TYPE_RESERVED) != USB_REQ_TYPE_STANDARD)
{
udev->class_handler->setup_handler(udev, &udev->setup);
return ret;
}
switch(udev->setup.bRequest)
{
case USB_STD_REQ_GET_STATUS:
usbd_get_status(udev);
break;
case USB_STD_REQ_CLEAR_FEATURE:
usbd_clear_feature(udev);
break;
case USB_STD_REQ_SET_FEATURE:
usbd_set_feature(udev);
break;
case USB_STD_REQ_SET_ADDRESS:
usbd_set_address(udev);
break;
case USB_STD_REQ_GET_DESCRIPTOR:
usbd_get_descriptor(udev);
break;
case USB_STD_REQ_GET_CONFIGURATION:
usbd_get_configuration(udev);
break;
case USB_STD_REQ_SET_CONFIGURATION:
usbd_set_configuration(udev);
break;
default:
usbd_ctrl_unsupport(udev);
break;
}
return ret;
}
/**
* @brief standard usb interface requests
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
usb_sts_type usbd_interface_request(usbd_core_type *udev)
{
usb_sts_type ret = USB_OK;
usb_setup_type *setup = &udev->setup;
switch(udev->conn_state)
{
case USB_CONN_STATE_CONFIGURED:
udev->class_handler->setup_handler(udev, &udev->setup);
if(setup->wLength == 0)
{
usbd_ctrl_send_status(udev);
}
break;
default:
usbd_ctrl_unsupport(udev);
break;
}
return ret;
}
/**
* @brief standard usb endpoint requests
* @param udev: to the structure of usbd_core_type
* @retval status of usb_sts_type
*/
usb_sts_type usbd_endpoint_request(usbd_core_type *udev)
{
usb_sts_type ret = USB_OK;
usb_setup_type *setup = &udev->setup;
uint8_t ept_addr = LBYTE(setup->wIndex);
usb_ept_info *ept_info;
if((setup->bmRequestType & USB_REQ_TYPE_RESERVED) == USB_REQ_TYPE_CLASS)
{
udev->class_handler->setup_handler(udev, &udev->setup);
}
switch(setup->bRequest)
{
case USB_STD_REQ_GET_STATUS:
switch(udev->conn_state)
{
case USB_CONN_STATE_ADDRESSED:
if((ept_addr & 0x7F) != 0)
{
usbd_set_stall(udev, ept_addr);
}
break;
case USB_CONN_STATE_CONFIGURED:
{
if((ept_addr & 0x80) != 0)
{
ept_info = &udev->ept_in[ept_addr & 0x7F];
}
else
{
ept_info = &udev->ept_out[ept_addr & 0x7F];
}
if(ept_info->stall == 1)
{
ept_info->status = 0x0001;
}
else
{
ept_info->status = 0x0000;
}
usbd_ctrl_send(udev, (uint8_t *)(&ept_info->status), 2);
}
break;
default:
usbd_ctrl_unsupport(udev);
break;
}
break;
case USB_STD_REQ_CLEAR_FEATURE:
switch(udev->conn_state)
{
case USB_CONN_STATE_ADDRESSED:
if((ept_addr != 0x00) && (ept_addr != 0x80))
{
usbd_set_stall(udev, ept_addr);
}
break;
case USB_CONN_STATE_CONFIGURED:
if(setup->wValue == USB_FEATURE_EPT_HALT)
{
if((ept_addr & 0x7F) != 0x00 )
{
usbd_clear_stall(udev, ept_addr);
udev->class_handler->setup_handler(udev, &udev->setup);
}
usbd_ctrl_send_status(udev);
}
break;
default:
usbd_ctrl_unsupport(udev);
break;
}
break;
case USB_STD_REQ_SET_FEATURE:
switch(udev->conn_state)
{
case USB_CONN_STATE_ADDRESSED:
if((ept_addr != 0x00) && (ept_addr != 0x80))
{
usbd_set_stall(udev, ept_addr);
}
break;
case USB_CONN_STATE_CONFIGURED:
if(setup->wValue == USB_FEATURE_EPT_HALT)
{
if((ept_addr != 0x00) && (ept_addr != 0x80))
{
usbd_set_stall(udev, ept_addr);
}
}
udev->class_handler->setup_handler(udev, &udev->setup);
usbd_ctrl_send_status(udev);
break;
default:
usbd_ctrl_unsupport(udev);
break;
}
break;
default:
usbd_ctrl_unsupport(udev);
break;
}
return ret;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View file

@ -1,71 +0,0 @@
/**
**************************************************************************
* @file usb_sdr.h
* @brief usb header file
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_SDR_H
#define __USB_SDR_H
#ifdef __cplusplus
extern "C" {
#endif
/* includes ------------------------------------------------------------------*/
#include "usb_conf.h"
#include "usb_core.h"
/** @addtogroup AT32F435_437_middlewares_usbd_drivers
* @{
*/
/** @addtogroup USBD_drivers_standard_request
* @{
*/
/** @defgroup USBD_sdr_exported_functions
* @{
*/
void usbd_setup_request_parse(usb_setup_type *setup, uint8_t *buf);
usb_sts_type usbd_device_request(usbd_core_type *udev);
usb_sts_type usbd_interface_request(usbd_core_type *udev);
usb_sts_type usbd_endpoint_request(usbd_core_type *udev);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif

File diff suppressed because it is too large Load diff

View file

@ -1,373 +0,0 @@
/**
**************************************************************************
* @file usbh_core.h
* @brief usb host core header file
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBH_CORE_H
#define __USBH_CORE_H
#ifdef __cplusplus
extern "C" {
#endif
#include "usb_conf.h"
#include "usb_std.h"
/** @addtogroup AT32F435_437_middlewares_usbh_drivers
* @{
*/
/** @addtogroup USBH_drivers_core
* @{
*/
/** @defgroup USBH_core_exported_types
* @{
*/
#ifdef USE_OTG_HOST_MODE
/**
* @brief usb channel flag
*/
typedef enum
{
HCH_IDLE, /*!< usb host channel idle */
HCH_XFRC, /*!< usb host channel transfer completed */
HCH_HALTED, /*!< usb host channel halted */
HCH_NAK, /*!< usb host channel nak */
HCH_NYET, /*!< usb host channel nyet */
HCH_STALL, /*!< usb host channel stall */
HCH_XACTERR, /*!< usb host channel transaction error */
HCH_BBLERR, /*!< usb host channel babble error */
HCH_DATATGLERR /*!< usb host channel data toggle error */
} hch_sts_type;
/**
* @brief usb channel state
*/
typedef enum
{
URB_IDLE = 0, /*!< usb request idle state */
URB_DONE, /*!< usb request done state */
URB_NOTREADY, /*!< usb request not ready state */
URB_NYET, /*!< usb request nyet stat e*/
URB_ERROR, /*!< usb request error state */
URB_STALL /*!< usb request stall state */
} urb_sts_type;
/**
* @brief usb control channel flag
*/
typedef enum
{
CTRL_START = 0, /*!< usb control request start */
CTRL_XFERC, /*!< usb control request completed */
CTRL_HALTED, /*!< usb control request halted */
CTRL_NAK, /*!< usb control request nak */
CTRL_STALL, /*!< usb control request stall */
CTRL_XACTERR, /*!< usb control request transaction error */
CTRL_BBLERR, /*!< usb control request babble error */
CTRL_DATATGLERR, /*!< usb control request data toggle error */
CTRL_FAIL /*!< usb control request failed */
} ctrl_sts_type;
/**
* @brief usb host control state machine
*/
typedef enum
{
CONTROL_IDLE, /*!< usb control state idle */
CONTROL_SETUP, /*!< usb control state setup */
CONTROL_SETUP_WAIT, /*!< usb control state setup wait */
CONTROL_DATA_IN, /*!< usb control state data in */
CONTROL_DATA_IN_WAIT, /*!< usb control state data in wait */
CONTROL_DATA_OUT, /*!< usb control state data out */
CONTROL_DATA_OUT_WAIT, /*!< usb control state data out wait */
CONTROL_STATUS_IN, /*!< usb control state status in */
CONTROL_STATUS_IN_WAIT, /*!< usb control state status in wait */
CONTROL_STATUS_OUT, /*!< usb control state out */
CONTROL_STATUS_OUT_WAIT, /*!< usb control state out wait */
CONTROL_ERROR, /*!< usb control state error */
CONTROL_STALL, /*!< usb control state stall */
CONTROL_COMPLETE /*!< usb control state complete */
} ctrl_ept0_sts_type;
/**
* @brief usb host enumration state machine
*/
typedef enum
{
ENUM_IDLE, /*!< usb host enumration state idle */
ENUM_GET_MIN_DESC, /*!< usb host enumration state get descriptor 8 byte*/
ENUM_GET_FULL_DESC, /*!< usb host enumration state get descriptor 18 byte*/
ENUM_SET_ADDR, /*!< usb host enumration state set address */
ENUM_GET_CFG, /*!< usb host enumration state get configuration */
ENUM_GET_FULL_CFG, /*!< usb host enumration state get full configuration */
ENUM_GET_MFC_STRING, /*!< usb host enumration state get manufacturer string */
ENUM_GET_PRODUCT_STRING, /*!< usb host enumration state get product string */
ENUM_GET_SERIALNUM_STRING, /*!< usb host enumration state get serial number string */
ENUM_SET_CONFIG, /*!< usb host enumration state set config */
ENUM_COMPLETE, /*!< usb host enumration state complete */
} usbh_enum_sts_type;
/**
* @brief usb host global state machine
*/
typedef enum
{
USBH_IDLE, /*!< usb host global state idle */
USBH_PORT_EN, /*!< usb host global state port enable */
USBH_ATTACHED, /*!< usb host global state attached */
USBH_DISCONNECT, /*!< usb host global state disconnect */
USBH_DEV_SPEED, /*!< usb host global state device speed */
USBH_ENUMERATION, /*!< usb host global state enumeration */
USBH_CLASS_REQUEST, /*!< usb host global state class request */
USBH_CLASS, /*!< usb host global state class */
USBH_CTRL_XFER, /*!< usb host global state control transfer */
USBH_USER_HANDLER, /*!< usb host global state user handler */
USBH_SUSPEND, /*!< usb host global state suspend */
USBH_SUSPENDED, /*!< usb host have in suspend mode */
USBH_WAKEUP, /*!< usb host global state wakeup */
USBH_UNSUPPORT, /*!< usb host global unsupport device */
USBH_ERROR_STATE, /*!< usb host global state error */
} usbh_gstate_type;
/**
* @brief usb host transfer state
*/
typedef enum
{
CMD_IDLE, /*!< usb host transfer state idle */
CMD_SEND, /*!< usb host transfer state send */
CMD_WAIT /*!< usb host transfer state wait */
} cmd_sts_type;
/**
* @brief usb host channel malloc state
*/
#define HCH_OK 0x0000 /*!< usb channel malloc state ok */
#define HCH_USED 0x8000 /*!< usb channel had used */
#define HCH_ERROR 0xFFFF /*!< usb channel error */
#define HCH_USED_MASK 0x7FFF /*!< usb channel use mask */
/**
* @brief channel pid
*/
#define HCH_PID_DATA0 0 /*!< usb channel pid data 0 */
#define HCH_PID_DATA2 1 /*!< usb channel pid data 2 */
#define HCH_PID_DATA1 2 /*!< usb channel pid data 1 */
#define HCH_PID_SETUP 3 /*!< usb channel pid setup */
/**
* @brief channel data transfer direction
*/
#define USB_REQUEST_DIR_MASK 0x80 /*!< usb request direction mask */
#define USB_DIR_H2D USB_REQ_DIR_HTD /*!< usb request direction host to device */
#define USB_DIR_D2H USB_REQ_DIR_DTH /*!< usb request direction device to host */
/**
* @brief request timeout
*/
#define DATA_STAGE_TIMEOUT 5000 /*!< usb data stage timeout */
#define NODATA_STAGE_TIMEOUT 50 /*!< usb no-data stage timeout */
/**
* @brief max interface and endpoint
*/
#define USBH_MAX_ERROR_COUNT 2 /*!< usb support maximum error */
#define USBH_MAX_INTERFACE 5 /*!< usb support maximum interface */
#define USBH_MAX_ENDPOINT 5 /*!< usb support maximum endpoint */
/**
* @brief interface descriptor
*/
typedef struct
{
usb_interface_desc_type interface; /*!< usb device interface descriptor structure */
usb_endpoint_desc_type endpoint[USBH_MAX_ENDPOINT]; /*!< usb device endpoint descriptor structure array */
} usb_itf_desc_type;
/**
* @brief configure descriptor
*/
typedef struct
{
usb_configuration_desc_type cfg; /*!< usb device configuration descriptor structure */
usb_itf_desc_type interface[USBH_MAX_INTERFACE]; /*!< usb device interface descriptor structure array*/
} usb_cfg_desc_type;
/**
* @brief device descriptor
*/
typedef struct
{
uint8_t address; /*!< usb device address */
uint8_t speed; /*!< usb device speed */
usb_device_desc_type dev_desc; /*!< usb device descriptor */
usb_cfg_desc_type cfg_desc; /*!< usb device configuration */
} usbh_dev_desc_type;
/**
* @brief usb host control struct type
*/
typedef struct
{
uint8_t hch_in; /*!< in channel number */
uint8_t hch_out; /*!< out channel number */
uint8_t ept0_size; /*!< endpoint 0 size */
uint8_t *buffer; /*!< endpoint 0 transfer buffer */
usb_setup_type setup; /*!< control setup type */
uint16_t len; /*!< transfer length */
uint8_t err_cnt; /*!< error counter */
uint32_t timer; /*!< transfer timer */
ctrl_sts_type sts; /*!< control transfer status */
ctrl_ept0_sts_type state; /*!< endpoint 0 state */
} usbh_ctrl_type;
/**
* @brief host class handler type
*/
typedef struct
{
usb_sts_type (*init_handler)(void *uhost); /*!< usb host class init handler */
usb_sts_type (*reset_handler)(void *uhost); /*!< usb host class reset handler */
usb_sts_type (*request_handler)(void *uhost); /*!< usb host class request handler */
usb_sts_type (*process_handler)(void *uhost); /*!< usb host class process handler */
void *pdata; /*!< usb host class data */
} usbh_class_handler_type;
/**
* @brief host user handler type
*/
typedef struct
{
usb_sts_type (*user_init)(void); /*!< usb host user init handler */
usb_sts_type (*user_reset)(void); /*!< usb host user reset handler */
usb_sts_type (*user_attached)(void); /*!< usb host user attached handler */
usb_sts_type (*user_disconnect)(void); /*!< usb host user disconnect handler */
usb_sts_type (*user_speed)(uint8_t speed); /*!< usb host user speed handler */
usb_sts_type (*user_mfc_string)(void *); /*!< usb host user manufacturer string handler */
usb_sts_type (*user_product_string)(void *); /*!< usb host user product string handler */
usb_sts_type (*user_serial_string)(void *); /*!< usb host user serial handler */
usb_sts_type (*user_enumeration_done)(void); /*!< usb host user enumeration done handler */
usb_sts_type (*user_application)(void); /*!< usb host user application handler */
usb_sts_type (*user_active_vbus)(void *uhost, confirm_state state); /*!< usb host user active vbus */
usb_sts_type (*user_not_support)(void); /*!< usb host user not support handler */
} usbh_user_handler_type;
/**
* @brief host host core handler type
*/
typedef struct
{
usb_reg_type *usb_reg; /*!< usb register pointer */
uint8_t global_state; /*!< usb host global state machine */
uint8_t enum_state; /*!< usb host enumeration state machine */
uint8_t req_state; /*!< usb host request state machine */
usbh_dev_desc_type dev; /*!< usb device descriptor */
usbh_ctrl_type ctrl; /*!< usb host control transfer struct */
usbh_class_handler_type *class_handler; /*!< usb host class handler pointer */
usbh_user_handler_type *user_handler; /*!< usb host user handler pointer */
usb_hch_type hch[USB_HOST_CHANNEL_NUM]; /*!< usb host channel array */
uint8_t rx_buffer[USB_MAX_DATA_LENGTH]; /*!< usb host rx buffer */
uint32_t conn_sts; /*!< connect status */
uint32_t port_enable; /*!< port enable status */
uint32_t timer; /*!< sof timer */
uint32_t err_cnt[USB_HOST_CHANNEL_NUM]; /*!< error counter */
uint32_t xfer_cnt[USB_HOST_CHANNEL_NUM]; /*!< xfer counter */
hch_sts_type hch_state[USB_HOST_CHANNEL_NUM];/*!< channel state */
urb_sts_type urb_state[USB_HOST_CHANNEL_NUM];/*!< usb request state */
uint16_t channel[USB_HOST_CHANNEL_NUM]; /*!< channel array */
} usbh_core_type;
void usbh_free_channel(usbh_core_type *uhost, uint8_t index);
uint16_t usbh_get_free_channel(usbh_core_type *uhost);
usb_sts_type usbh_set_toggle(usbh_core_type *uhost, uint8_t hc_num, uint8_t toggle);
usb_sts_type usbh_in_out_request(usbh_core_type *uhost, uint8_t hc_num);
usb_sts_type usbh_interrupt_recv(usbh_core_type *uhost, uint8_t hc_num,
uint8_t *buffer, uint16_t length);
usb_sts_type usbh_interrupt_send(usbh_core_type *uhost, uint8_t hc_num,
uint8_t *buffer, uint16_t length);
usb_sts_type usbh_bulk_recv(usbh_core_type *uhost, uint8_t hc_num,
uint8_t *buffer, uint16_t length);
usb_sts_type usbh_bulk_send(usbh_core_type *uhost, uint8_t hc_num,
uint8_t *buffer, uint16_t length);
usb_sts_type usbh_isoc_send(usbh_core_type *uhost, uint8_t hc_num,
uint8_t *buffer, uint16_t length);
usb_sts_type usbh_isoc_recv(usbh_core_type *uhost, uint8_t hc_num,
uint8_t *buffer, uint16_t length);
usb_sts_type usbh_cfg_default_init(usbh_core_type *uhost);
void usbh_enter_suspend(usbh_core_type *uhost);
void usbh_resume(usbh_core_type *uhost);
uint16_t usbh_alloc_channel(usbh_core_type *uhost, uint8_t ept_addr);
urb_sts_type usbh_get_urb_status(usbh_core_type *uhost, uint8_t ch_num);
usb_sts_type usbh_ctrl_result_check(usbh_core_type *uhost,
ctrl_ept0_sts_type next_ctrl_state,
uint8_t next_enum_state);
uint8_t usbh_alloc_address(void);
void usbh_reset_port(usbh_core_type *uhost);
usb_sts_type usbh_loop_handler(usbh_core_type *uhost);
void usbh_ch_disable(usbh_core_type *uhost, uint8_t chn);
void usbh_hc_open(usbh_core_type *uhost,
uint8_t chn,
uint8_t ept_num,
uint8_t dev_address,
uint8_t type,
uint16_t maxpacket,
uint8_t speed);
void usbh_active_vbus(usbh_core_type *uhost, confirm_state state);
usb_sts_type usbh_core_init(usbh_core_type *uhost,
usb_reg_type *usb_reg,
usbh_class_handler_type *class_handler,
usbh_user_handler_type *user_handler,
uint8_t core_id);
#endif
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif

View file

@ -1,988 +0,0 @@
/**
**************************************************************************
* @file usbh_ctrl.c
* @brief usb host control request
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
#include "platform.h"
#include "usbh_ctrl.h"
#include "usbh_core.h"
#include "usb_std.h"
/** @addtogroup AT32F435_437_middlewares_usbh_drivers
* @{
*/
/** @defgroup USBH_drivers_control
* @brief usb host drivers control
* @{
*/
/** @defgroup USBH_ctrl_private_functions
* @{
*/
/* control timeout 5s */
#define CTRL_TIMEOUT 5000
/**
* @brief usb host control send setup packet
* @param uhost: to the structure of usbh_core_type
* @param buffer: usb control setup send buffer
* @param hc_num: channel number
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_send_setup(usbh_core_type *uhost, uint8_t *buffer, uint8_t hc_num)
{
uhost->hch[hc_num].dir = 0;
uhost->hch[hc_num].data_pid = HCH_PID_SETUP;
uhost->hch[hc_num].trans_buf = buffer;
uhost->hch[hc_num].trans_len = 8; /*setup */
return usbh_in_out_request(uhost, hc_num);
}
/**
* @brief usb host control receive data from device
* @param uhost: to the structure of usbh_core_type
* @param buffer: usb control receive data buffer
* @param length: usb control receive data length
* @param hc_num: channel number
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_recv_data(usbh_core_type *uhost, uint8_t *buffer,
uint16_t length, uint16_t hc_num)
{
uhost->hch[hc_num].dir = 1;
uhost->hch[hc_num].data_pid = HCH_PID_DATA1;
uhost->hch[hc_num].trans_buf = buffer;
uhost->hch[hc_num].trans_len = length;
return usbh_in_out_request(uhost, hc_num);
}
/**
* @brief usb host control send data packet
* @param uhost: to the structure of usbh_core_type
* @param buffer: usb control send data buffer
* @param length: usb control send data length
* @param hc_num: channel number
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_send_data(usbh_core_type *uhost, uint8_t *buffer,
uint16_t length, uint16_t hc_num)
{
uhost->hch[hc_num].dir = 0;
uhost->hch[hc_num].trans_buf = buffer;
uhost->hch[hc_num].trans_len = length;
if(length == 0)
{
uhost->hch[uhost->ctrl.hch_out].toggle_out = 1;
}
if(uhost->hch[uhost->ctrl.hch_out].toggle_out == 0)
{
uhost->hch[hc_num].data_pid = HCH_PID_DATA0;
}
else
{
uhost->hch[hc_num].data_pid = HCH_PID_DATA1;
}
return usbh_in_out_request(uhost, hc_num);
}
/**
* @brief usb host control setup request handler
* @param uhost: to the structure of usbh_core_type
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_setup_handler(usbh_core_type *uhost)
{
usbh_ctrl_send_setup(uhost, (uint8_t *)(&uhost->ctrl.setup),
uhost->ctrl.hch_out);
uhost->ctrl.state = CONTROL_SETUP_WAIT;
return USB_OK;
}
/**
* @brief usb host control setup request wait handler
* @param uhost: to the structure of usbh_core_type
* @param timeout: pointer of wait timeout
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_setup_wait_handler(usbh_core_type *uhost, uint32_t *timeout)
{
urb_sts_type urb_state;
usb_sts_type status = USB_WAIT;
uint8_t dir;
urb_state = uhost->urb_state[uhost->ctrl.hch_out];
if(urb_state == URB_DONE)
{
dir = uhost->ctrl.setup.bmRequestType & USB_REQUEST_DIR_MASK;
if(uhost->ctrl.setup.wLength != 0)
{
*timeout = DATA_STAGE_TIMEOUT;
if(dir == USB_DIR_D2H) //in
{
uhost->ctrl.state = CONTROL_DATA_IN;
}
else //out
{
uhost->ctrl.state = CONTROL_DATA_OUT;
}
}
else
{
*timeout = NODATA_STAGE_TIMEOUT;
if(dir == USB_DIR_D2H) //no data, send status
{
uhost->ctrl.state = CONTROL_STATUS_OUT;
}
else //out
{
uhost->ctrl.state = CONTROL_STATUS_IN;
}
}
status = USB_OK;
}
else if(urb_state == URB_ERROR || urb_state == URB_NOTREADY)
{
uhost->ctrl.state = CONTROL_ERROR;
uhost->ctrl.sts = CTRL_XACTERR;
status = USB_ERROR;
}
else
{
/* wait nak timeout 5s*/
if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT)
{
uhost->ctrl.state = CONTROL_ERROR;
uhost->ctrl.sts = CTRL_XACTERR;
status = USB_ERROR;
}
}
return status;
}
/**
* @brief usb host control data in request handler
* @param uhost: to the structure of usbh_core_type
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_data_in_handler(usbh_core_type *uhost)
{
usb_sts_type status = USB_OK;
usbh_ctrl_recv_data(uhost, uhost->ctrl.buffer,
uhost->ctrl.len,
uhost->ctrl.hch_in);
uhost->ctrl.state = CONTROL_DATA_IN_WAIT;
return status;
}
/**
* @brief usb host control data in wait handler
* @param uhost: to the structure of usbh_core_type
* @param timeout: wait timeout
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_data_in_wait_handler(usbh_core_type *uhost, uint32_t timeout)
{
UNUSED(timeout);
usb_sts_type status = USB_OK;
urb_sts_type urb_state;
urb_state = uhost->urb_state[uhost->ctrl.hch_in];
if(urb_state == URB_DONE)
{
uhost->ctrl.state = CONTROL_STATUS_OUT;
}
else if(urb_state == URB_STALL)
{
uhost->ctrl.state = CONTROL_STALL;
}
else if(urb_state == URB_ERROR)
{
uhost->ctrl.state = CONTROL_ERROR;
}
else
{
/* wait nak timeout 5s*/
if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT)
{
uhost->ctrl.state = CONTROL_ERROR;
uhost->ctrl.sts = CTRL_XACTERR;
status = USB_ERROR;
}
}
return status;
}
/**
* @brief usb host control data out request handler
* @param uhost: to the structure of usbh_core_type
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_data_out_handler(usbh_core_type *uhost)
{
usb_sts_type status = USB_OK;
uhost->hch[uhost->ctrl.hch_out].toggle_out = 1;
usbh_ctrl_send_data(uhost, uhost->ctrl.buffer,
uhost->ctrl.len,
uhost->ctrl.hch_out);
uhost->ctrl.state = CONTROL_DATA_OUT_WAIT;
return status;
}
/**
* @brief usb host control data out wait handler
* @param uhost: to the structure of usbh_core_type
* @param timeout: wait timeout
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_data_out_wait_handler(usbh_core_type *uhost, uint32_t timeout)
{
UNUSED(timeout);
usb_sts_type status = USB_OK;
urb_sts_type urb_state;
urb_state = uhost->urb_state[uhost->ctrl.hch_out];
if(urb_state == URB_DONE)
{
uhost->ctrl.state = CONTROL_STATUS_IN;
}
else if(urb_state == URB_STALL)
{
uhost->ctrl.state = CONTROL_STALL;
}
else if(urb_state == URB_ERROR)
{
uhost->ctrl.state = CONTROL_ERROR;
}
else if(urb_state == URB_NOTREADY)
{
uhost->ctrl.state = CONTROL_DATA_OUT;
}
else
{
/* wait nak timeout 5s*/
if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT)
{
uhost->ctrl.state = CONTROL_ERROR;
uhost->ctrl.sts = CTRL_XACTERR;
status = USB_ERROR;
}
}
return status;
}
/**
* @brief usb host control status data in handler
* @param uhost: to the structure of usbh_core_type
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_status_in_handler(usbh_core_type *uhost)
{
usb_sts_type status = USB_OK;
usbh_ctrl_recv_data(uhost, 0, 0,
uhost->ctrl.hch_in);
uhost->ctrl.state = CONTROL_STATUS_IN_WAIT;
return status;
}
/**
* @brief usb host control status data in wait handler
* @param uhost: to the structure of usbh_core_type
* @param timeout: wait timeout
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_status_in_wait_handler(usbh_core_type *uhost, uint32_t timeout)
{
UNUSED(timeout);
usb_sts_type status = USB_OK;
urb_sts_type urb_state;
urb_state = uhost->urb_state[uhost->ctrl.hch_in];
if(urb_state == URB_DONE)
{
uhost->ctrl.state = CONTROL_COMPLETE;
}
else if(urb_state == URB_STALL)
{
uhost->ctrl.state = CONTROL_STALL;
status = USB_NOT_SUPPORT;
}
else if(urb_state == URB_ERROR)
{
uhost->ctrl.state = CONTROL_ERROR;
}
else
{
/* wait nak timeout 5s*/
if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT)
{
uhost->ctrl.state = CONTROL_ERROR;
uhost->ctrl.sts = CTRL_XACTERR;
status = USB_ERROR;
}
}
return status;
}
/**
* @brief usb host control status data out wait handler
* @param uhost: to the structure of usbh_core_type
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_status_out_handler(usbh_core_type *uhost)
{
usb_sts_type status = USB_OK;
uhost->hch[uhost->ctrl.hch_out].toggle_out ^= 1;
usbh_ctrl_send_data(uhost, 0, 0, uhost->ctrl.hch_out);
uhost->ctrl.state = CONTROL_STATUS_OUT_WAIT;
return status;
}
/**
* @brief usb host control status data out wait handler
* @param uhost: to the structure of usbh_core_type
* @param timeout: wait timeout
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_status_out_wait_handler(usbh_core_type *uhost, uint32_t timeout)
{
UNUSED(timeout);
usb_sts_type status = USB_OK;
urb_sts_type urb_state;
urb_state = uhost->urb_state[uhost->ctrl.hch_out];
if(urb_state == URB_DONE)
{
uhost->ctrl.state = CONTROL_COMPLETE;
}
else if(urb_state == URB_STALL)
{
uhost->ctrl.state = CONTROL_STALL;
}
else if(urb_state == URB_ERROR)
{
uhost->ctrl.state = CONTROL_ERROR;
}
else if(urb_state == URB_NOTREADY)
{
uhost->ctrl.state = CONTROL_STATUS_OUT;
}
else
{
/* wait nak timeout 5s*/
if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT)
{
uhost->ctrl.state = CONTROL_ERROR;
uhost->ctrl.sts = CTRL_XACTERR;
status = USB_ERROR;
}
}
return status;
}
/**
* @brief usb host control error handler
* @param uhost: to the structure of usbh_core_type
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_error_handler(usbh_core_type *uhost)
{
usb_sts_type status = USB_WAIT;
if(++ uhost->ctrl.err_cnt <= USBH_MAX_ERROR_COUNT)
{
uhost->ctrl.state = CONTROL_SETUP;
}
else
{
uhost->ctrl.sts = CTRL_FAIL;
uhost->global_state = USBH_ERROR_STATE;
uhost->ctrl.err_cnt = 0;
//USBH_DEBUG("control error: **** Device No Response ****");
status = USB_ERROR;
}
return status;
}
/**
* @brief usb host control stall handler
* @param uhost: to the structure of usbh_core_type
* @retval usb_sts_type
*/
usb_sts_type usbh_ctrl_stall_handler(usbh_core_type *uhost)
{
UNUSED(uhost);
return USB_NOT_SUPPORT;
}
/**
* @brief usb host control complete handler
* @param uhost: to the structure of usbh_core_type
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_complete_handler(usbh_core_type *uhost)
{
UNUSED(uhost);
return USB_OK;
}
/**
* @brief usb host control transfer loop function
* @param uhost: to the structure of usbh_core_type
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_transfer_loop(usbh_core_type *uhost)
{
usb_sts_type status = USB_WAIT;
static uint32_t timeout = 0;
uhost->ctrl.sts = CTRL_START;
switch(uhost->ctrl.state)
{
case CONTROL_SETUP:
usbh_ctrl_setup_handler(uhost);
uhost->ctrl.timer = uhost->timer;
break;
case CONTROL_SETUP_WAIT:
usbh_ctrl_setup_wait_handler(uhost, &timeout);
break;
case CONTROL_DATA_IN:
usbh_ctrl_data_in_handler(uhost);
uhost->ctrl.timer = uhost->timer;
break;
case CONTROL_DATA_IN_WAIT:
usbh_ctrl_data_in_wait_handler(uhost, timeout);
break;
case CONTROL_DATA_OUT:
usbh_ctrl_data_out_handler(uhost);
uhost->ctrl.timer = uhost->timer;
break;
case CONTROL_DATA_OUT_WAIT:
usbh_ctrl_data_out_wait_handler(uhost, timeout);
break;
case CONTROL_STATUS_IN:
usbh_ctrl_status_in_handler(uhost);
uhost->ctrl.timer = uhost->timer;
break;
case CONTROL_STATUS_IN_WAIT:
usbh_ctrl_status_in_wait_handler(uhost, timeout);
break;
case CONTROL_STATUS_OUT:
usbh_ctrl_status_out_handler(uhost);
uhost->ctrl.timer = uhost->timer;
break;
case CONTROL_STATUS_OUT_WAIT:
usbh_ctrl_status_out_wait_handler(uhost, timeout);
break;
case CONTROL_STALL:
status = usbh_ctrl_stall_handler(uhost);
break;
case CONTROL_ERROR:
status = usbh_ctrl_error_handler(uhost);
break;
case CONTROL_COMPLETE:
status = usbh_ctrl_complete_handler(uhost);
break;
default:
break;
}
return status;
}
/**
* @brief usb host control request
* @param uhost: to the structure of usbh_core_type
* @param buffer: usb request buffer
* @param length: usb request length
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_ctrl_request(usbh_core_type *uhost, uint8_t *buffer, uint16_t length)
{
usb_sts_type status = USB_OK;
if(uhost->req_state == CMD_SEND)
{
uhost->req_state = CMD_WAIT;
uhost->ctrl.buffer = buffer;
uhost->ctrl.len = length;
uhost->ctrl.state = CONTROL_SETUP;
}
return status;
}
/**
* @brief usb host get device descriptor
* @param uhost: to the structure of usbh_core_type
* @param length: get descriptor request length
* @param req_type: usb request type
* @param wvalue: usb wvalue
* @param buffer: request buffer
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_get_descriptor(usbh_core_type *uhost, uint16_t length,
uint8_t req_type, uint16_t wvalue,
uint8_t *buffer)
{
usb_sts_type status;
uhost->ctrl.setup.bmRequestType = USB_DIR_D2H | req_type;
uhost->ctrl.setup.bRequest = USB_STD_REQ_GET_DESCRIPTOR;
uhost->ctrl.setup.wValue = wvalue;
uhost->ctrl.setup.wLength = length;
if((wvalue & 0xFF00) == ((USB_DESCIPTOR_TYPE_STRING << 8) & 0xFF00))
{
uhost->ctrl.setup.wIndex = 0x0409;
}
else
{
uhost->ctrl.setup.wIndex = 0;
}
status = usbh_ctrl_request(uhost, buffer, length);
return status;
}
/**
* @brief usb host parse device descriptor
* @param uhost: to the structure of usbh_core_type
* @param buffer: usb device descriptor buffer
* @param length: usb device descriptor length
* @retval status: usb_sts_type status
*/
void usbh_parse_dev_desc(usbh_core_type *uhost, uint8_t *buffer, uint16_t length)
{
usbh_dev_desc_type *desc = &(uhost->dev);
desc->dev_desc.bLength = *(uint8_t *)(buffer + 0);
desc->dev_desc.bDescriptorType = *(uint8_t *)(buffer + 1);
desc->dev_desc.bcdUSB = SWAPBYTE(buffer + 2);
desc->dev_desc.bDeviceClass = *(uint8_t *)(buffer + 4);
desc->dev_desc.bDeviceSubClass = *(uint8_t *)(buffer + 5);
desc->dev_desc.bDeviceProtocol = *(uint8_t *)(buffer + 6);
desc->dev_desc.bMaxPacketSize0 = *(uint8_t *)(buffer + 7);
if(length > 8)
{
desc->dev_desc.idVendor = SWAPBYTE(buffer + 8);
desc->dev_desc.idProduct = SWAPBYTE(buffer + 10);
desc->dev_desc.bcdDevice = SWAPBYTE(buffer + 12);
desc->dev_desc.iManufacturer = *(uint8_t *)(buffer + 14);
desc->dev_desc.iProduct = *(uint8_t *)(buffer + 15);
desc->dev_desc.iSerialNumber = *(uint8_t *)(buffer + 16);
desc->dev_desc.bNumConfigurations = *(uint8_t *)(buffer + 17);
}
}
/**
* @brief usb host get next header
* @param buffer: usb data buffer
* @param index_len: pointer of index len
* @retval status: usb_sts_type status
*/
usb_header_desc_type *usbh_get_next_header(uint8_t *buf, uint16_t *index_len)
{
*index_len += ((usb_header_desc_type *)buf)->bLength;
return (usb_header_desc_type *)
((uint8_t *)buf + ((usb_header_desc_type *)buf)->bLength);
}
/**
* @brief usb host parse interface descriptor
* @param intf: usb interface description type
* @param buf: interface description data buffer
* @retval none
*/
void usbh_parse_interface_desc(usb_interface_desc_type *intf, uint8_t *buf)
{
intf->bLength = *(uint8_t *)buf;
intf->bDescriptorType = *(uint8_t *)(buf + 1);
intf->bInterfaceNumber = *(uint8_t *)(buf + 2);
intf->bAlternateSetting = *(uint8_t *)(buf + 3);
intf->bNumEndpoints = *(uint8_t *)(buf + 4);
intf->bInterfaceClass = *(uint8_t *)(buf + 5);
intf->bInterfaceSubClass = *(uint8_t *)(buf + 6);
intf->bInterfaceProtocol = *(uint8_t *)(buf + 7);
intf->iInterface = *(uint8_t *)(buf + 8);
}
/**
* @brief usb host parse endpoint descriptor
* @param ept_desc: endpoint type
* @param buf: endpoint description data buffer
* @retval none
*/
void usbh_parse_endpoint_desc(usb_endpoint_desc_type *ept_desc, uint8_t *buf)
{
ept_desc->bLength = *(uint8_t *)(buf + 0);
ept_desc->bDescriptorType = *(uint8_t *)(buf + 1);
ept_desc->bEndpointAddress = *(uint8_t *)(buf + 2);
ept_desc->bmAttributes = *(uint8_t *)(buf + 3);
ept_desc->wMaxPacketSize = SWAPBYTE(buf + 4);
ept_desc->bInterval = *(uint8_t *)(buf + 6);
}
/**
* @brief usb host parse configure descriptor
* @param uhost: to the structure of usbh_core_type
* @param buffer: configure buffer
* @param length: configure length
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_parse_configure_desc(usbh_core_type *uhost,
uint8_t *buffer, uint16_t length)
{
usb_cfg_desc_type *cfg_desc = &(uhost->dev.cfg_desc);
usb_interface_desc_type *intf_desc;
usb_endpoint_desc_type *ept_desc;
usb_header_desc_type *desc;
uint16_t index_len;
uint8_t index_intf = 0;
uint8_t index_ept = 0;
desc = (usb_header_desc_type *)buffer;
cfg_desc->cfg.bLength = *(uint8_t *)buffer;
cfg_desc->cfg.bDescriptorType = *(uint8_t *)(buffer + 1);
cfg_desc->cfg.wTotalLength = SWAPBYTE(buffer + 2);
cfg_desc->cfg.bNumInterfaces = *(uint8_t *)(buffer + 4);
cfg_desc->cfg.bConfigurationValue = *(uint8_t *)(buffer + 5);
cfg_desc->cfg.iConfiguration = *(uint8_t *)(buffer + 6);
cfg_desc->cfg.bmAttributes = *(uint8_t *)(buffer + 7);
cfg_desc->cfg.bMaxPower = *(uint8_t *)(buffer + 8);
if(length > USB_DEVICE_CFG_DESC_LEN)
{
index_len = USB_DEVICE_CFG_DESC_LEN;
while((index_intf < USBH_MAX_INTERFACE) && index_len < cfg_desc->cfg.wTotalLength)
{
desc = usbh_get_next_header((uint8_t *)desc, &index_len);
if(desc->bDescriptorType == USB_DESCIPTOR_TYPE_INTERFACE)
{
index_ept = 0;
intf_desc = &cfg_desc->interface[index_intf].interface;
usbh_parse_interface_desc(intf_desc, (uint8_t *)desc);
while(index_ept < intf_desc->bNumEndpoints && index_len < cfg_desc->cfg.wTotalLength)
{
desc = usbh_get_next_header((uint8_t *)desc, &index_len);
if(desc->bDescriptorType == USB_DESCIPTOR_TYPE_ENDPOINT)
{
ept_desc = &(cfg_desc->interface[index_intf].endpoint[index_ept]);
usbh_parse_endpoint_desc(ept_desc, (uint8_t *)desc);
index_ept ++;
}
}
index_intf ++;
}
}
}
return USB_OK;
}
/**
* @brief usb host find interface
* @param uhost: to the structure of usbh_core_type
* @param class_code: class code
* @param sub_class: subclass code
* @param protocol: prtocol code
* @retval idx: interface index
*/
uint8_t usbh_find_interface(usbh_core_type *uhost, uint8_t class_code, uint8_t sub_class, uint8_t protocol)
{
uint8_t idx = 0;
usb_itf_desc_type *usbitf;
for(idx = 0; idx < uhost->dev.cfg_desc.cfg.bNumInterfaces; idx ++)
{
usbitf = &uhost->dev.cfg_desc.interface[idx];
if(((usbitf->interface.bInterfaceClass == class_code) || (class_code == 0xFF)) &&
((usbitf->interface.bInterfaceSubClass == sub_class) || (sub_class == 0xFF)) &&
((usbitf->interface.bInterfaceProtocol == protocol) || (protocol == 0xFF))
)
{
return idx;
}
}
return 0xFF;
}
/**
* @brief usbh parse string descriptor
* @param src: string source pointer
* @param dest: string destination pointer
* @param length: string length
* @retval none
*/
void usbh_parse_string_desc(uint8_t *src, uint8_t *dest, uint16_t length)
{
uint16_t len;
uint16_t i_index;
if(src[1] == USB_DESCIPTOR_TYPE_STRING)
{
len = ((src[0] - 2) <= length ? (src[0] - 2) : length);
src += 2;
for(i_index = 0; i_index < len; i_index += 2)
{
*dest = src[i_index];
dest ++;
}
*dest = 0;
}
}
/**
* @brief usb host get device descriptor
* @param uhost: to the structure of usbh_core_type
* @param length: get device descriptor length
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_get_device_descriptor(usbh_core_type *uhost, uint16_t length)
{
usb_sts_type status = USB_WAIT;
uint8_t bm_req;
uint16_t wvalue;
bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD;
wvalue = (USB_DESCIPTOR_TYPE_DEVICE << 8) & 0xFF00;
status = usbh_get_descriptor(uhost, length, bm_req,
wvalue, uhost->rx_buffer);
return status;
}
/**
* @brief usb host get configure descriptor
* @param uhost: to the structure of usbh_core_type
* @param length: get device configure length
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_get_configure_descriptor(usbh_core_type *uhost, uint16_t length)
{
usb_sts_type status = USB_WAIT;
uint8_t bm_req;
uint16_t wvalue;
bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD;
wvalue = (USB_DESCIPTOR_TYPE_CONFIGURATION << 8) & 0xFF00;
status = usbh_get_descriptor(uhost, length, bm_req,
wvalue, uhost->rx_buffer);
return status;
}
/**
* @brief usb host get string descriptor
* @param uhost: to the structure of usbh_core_type
* @param string_id: string id
* @param buffer: receive data buffer
* @param length: get device string length
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_get_sting_descriptor(usbh_core_type *uhost, uint8_t string_id,
uint8_t *buffer, uint16_t length)
{
UNUSED(buffer);
usb_sts_type status = USB_WAIT;
uint8_t bm_req;
uint16_t wvalue;
bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD;
wvalue = (USB_DESCIPTOR_TYPE_STRING << 8) | string_id;
status = usbh_get_descriptor(uhost, length, bm_req,
wvalue, uhost->rx_buffer);
return status;
}
/**
* @brief usb host set configurtion
* @param uhost: to the structure of usbh_core_type
* @param config: usb configuration
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_set_configuration(usbh_core_type *uhost, uint16_t config)
{
usb_sts_type status = USB_WAIT;
uint8_t bm_req;
bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD;
uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req;
uhost->ctrl.setup.bRequest = USB_STD_REQ_SET_CONFIGURATION;
uhost->ctrl.setup.wValue = config;
uhost->ctrl.setup.wLength = 0;
uhost->ctrl.setup.wIndex = 0;
status = usbh_ctrl_request(uhost, 0, 0);
return status;
}
/**
* @brief usb host set device address
* @param uhost: to the structure of usbh_core_type
* @param address: device address
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_set_address(usbh_core_type *uhost, uint8_t address)
{
usb_sts_type status = USB_WAIT;
uint8_t bm_req;
bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD;
uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req;
uhost->ctrl.setup.bRequest = USB_STD_REQ_SET_ADDRESS;
uhost->ctrl.setup.wValue = (uint16_t)address;
uhost->ctrl.setup.wLength = 0;
uhost->ctrl.setup.wIndex = 0;
status = usbh_ctrl_request(uhost, 0, 0);
return status;
}
/**
* @brief usb host set interface
* @param uhost: to the structure of usbh_core_type
* @param ept_num: endpoint number
* @param altsetting: alter setting
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_set_interface(usbh_core_type *uhost, uint8_t ept_num, uint8_t altsetting)
{
usb_sts_type status = USB_WAIT;
uint8_t bm_req;
bm_req = USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_STANDARD;
uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req;
uhost->ctrl.setup.bRequest = USB_STD_REQ_SET_INTERFACE;
uhost->ctrl.setup.wValue = (uint16_t)altsetting;
uhost->ctrl.setup.wLength = 0;
uhost->ctrl.setup.wIndex = ept_num;
status = usbh_ctrl_request(uhost, 0, 0);
return status;
}
/**
* @brief usb host set feature
* @param uhost: to the structure of usbh_core_type
* @param feature: feature number
* @param index: index number
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_set_feature(usbh_core_type *uhost, uint8_t feature, uint16_t index)
{
usb_sts_type status = USB_WAIT;
uint8_t bm_req;
bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD;
uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req;
uhost->ctrl.setup.bRequest = USB_STD_REQ_SET_FEATURE;
uhost->ctrl.setup.wValue = (uint16_t)feature;
uhost->ctrl.setup.wLength = 0;
uhost->ctrl.setup.wIndex = index;
status = usbh_ctrl_request(uhost, 0, 0);
return status;
}
/**
* @brief usb host clear device feature
* @param uhost: to the structure of usbh_core_type
* @param feature: feature number
* @param index: index number
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_clear_dev_feature(usbh_core_type *uhost, uint8_t feature, uint16_t index)
{
usb_sts_type status = USB_WAIT;
uint8_t bm_req;
bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD;
uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req;
uhost->ctrl.setup.bRequest = USB_STD_REQ_CLEAR_FEATURE;
uhost->ctrl.setup.wValue = (uint16_t)feature;
uhost->ctrl.setup.wLength = 0;
uhost->ctrl.setup.wIndex = index;
status = usbh_ctrl_request(uhost, 0, 0);
return status;
}
/**
* @brief usb host clear endpoint feature
* @param uhost: to the structure of usbh_core_type
* @param ept_num: endpoint number
* @param hc_num: host channel number
* @retval status: usb_sts_type status
*/
usb_sts_type usbh_clear_ept_feature(usbh_core_type *uhost, uint8_t ept_num, uint8_t hc_num)
{
UNUSED(hc_num);
usb_sts_type status = USB_WAIT;
uint8_t bm_req;
if(uhost->ctrl.state == CONTROL_IDLE )
{
bm_req = USB_REQ_RECIPIENT_ENDPOINT | USB_REQ_TYPE_STANDARD;
uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req;
uhost->ctrl.setup.bRequest = USB_STD_REQ_CLEAR_FEATURE;
uhost->ctrl.setup.wValue = USB_FEATURE_EPT_HALT;
uhost->ctrl.setup.wLength = 0;
uhost->ctrl.setup.wIndex = ept_num;
usbh_ctrl_request(uhost, 0, 0);
}
if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK)
{
status = USB_OK;
}
return status;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View file

@ -1,107 +0,0 @@
/**
**************************************************************************
* @file usbh_ctrl.h
* @brief usb header file
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBH_CTRL_H
#define __USBH_CTRL_H
#ifdef __cplusplus
extern "C" {
#endif
/* includes ------------------------------------------------------------------*/
#include "usb_conf.h"
#include "usbh_core.h"
/** @addtogroup AT32F435_437_middlewares_usbh_drivers
* @{
*/
/** @addtogroup USBH_drivers_control
* @{
*/
/** @defgroup USBH_ctrl_exported_types
* @{
*/
usb_sts_type usbh_ctrl_send_setup(usbh_core_type *uhost, uint8_t *buffer, uint8_t hc_num);
usb_sts_type usbh_ctrl_recv_data(usbh_core_type *uhost, uint8_t *buffer,
uint16_t length, uint16_t hc_num);
usb_sts_type usbh_ctrl_send_data(usbh_core_type *uhost, uint8_t *buffer,
uint16_t length, uint16_t hc_num);
usb_sts_type usbh_ctrl_setup_handler(usbh_core_type *uhost);
usb_sts_type usbh_ctrl_setup_wait_handler(usbh_core_type *uhost, uint32_t *timeout);
usb_sts_type usbh_ctrl_data_in_handler(usbh_core_type *uhost);
usb_sts_type usbh_ctrl_data_in_wait_handler(usbh_core_type *uhost, uint32_t timeout);
usb_sts_type usbh_ctrl_data_out_handler(usbh_core_type *uhost);
usb_sts_type usbh_ctrl_data_out_wait_handler(usbh_core_type *uhost, uint32_t timeout);
usb_sts_type usbh_ctrl_status_in_handler(usbh_core_type *uhost);
usb_sts_type usbh_ctrl_status_in_wait_handler(usbh_core_type *uhost, uint32_t timeout);
usb_sts_type usbh_ctrl_status_out_handler(usbh_core_type *uhost);
usb_sts_type usbh_ctrl_status_out_wait_handler(usbh_core_type *uhost, uint32_t timeout);
usb_sts_type usbh_ctrl_error_handler(usbh_core_type *uhost);
usb_sts_type usbh_ctrl_stall_handler(usbh_core_type *uhost);
usb_sts_type usbh_ctrl_complete_handler(usbh_core_type *uhost);
usb_sts_type usbh_ctrl_transfer_loop(usbh_core_type *uhost);
usb_sts_type usbh_ctrl_request(usbh_core_type *uhost, uint8_t *buffer, uint16_t length);
usb_sts_type usbh_get_descriptor(usbh_core_type *uhost, uint16_t length,
uint8_t req_type, uint16_t wvalue,
uint8_t *buffer);
void usbh_parse_dev_desc(usbh_core_type *uhost, uint8_t *buffer, uint16_t length);
usb_header_desc_type *usbh_get_next_header(uint8_t *buf, uint16_t *index_len);
void usbh_parse_interface_desc(usb_interface_desc_type *intf, uint8_t *buf);
void usbh_parse_endpoint_desc(usb_endpoint_desc_type *ept_desc, uint8_t *buf);
usb_sts_type usbh_parse_configure_desc(usbh_core_type *uhost,
uint8_t *buffer, uint16_t length);
uint8_t usbh_find_interface(usbh_core_type *uhost, uint8_t class_code, uint8_t sub_class, uint8_t protocol);
void usbh_parse_string_desc(uint8_t *src, uint8_t *dest, uint16_t length);
usb_sts_type usbh_get_device_descriptor(usbh_core_type *uhost, uint16_t length);
usb_sts_type usbh_get_configure_descriptor(usbh_core_type *uhost, uint16_t length);
usb_sts_type usbh_get_sting_descriptor(usbh_core_type *uhost, uint8_t string_id,
uint8_t *buffer, uint16_t length);
usb_sts_type usbh_set_configuration(usbh_core_type *uhost, uint16_t config);
usb_sts_type usbh_set_address(usbh_core_type *uhost, uint8_t address);
usb_sts_type usbh_set_interface(usbh_core_type *uhost, uint8_t ept_num, uint8_t altsetting);
usb_sts_type usbh_set_feature(usbh_core_type *uhost, uint8_t feature, uint16_t index);
usb_sts_type usbh_clear_dev_feature(usbh_core_type *uhost, uint8_t feature, uint16_t index);
usb_sts_type usbh_clear_ept_feature(usbh_core_type *uhost, uint8_t ept_num, uint8_t hc_num);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif

View file

@ -1,530 +0,0 @@
/**
**************************************************************************
* @file usbh_int.c
* @brief usb host interrupt request
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
#include "platform.h"
#include "usbh_int.h"
/** @addtogroup AT32F435_437_middlewares_usbh_drivers
* @{
*/
/** @defgroup USBH_drivers_interrupt
* @brief usb host interrupt
* @{
*/
/** @defgroup USBH_int_private_functions
* @{
*/
/**
* @brief usb host interrupt handler
* @param otgdev: to the structure of otg_core_type
* @retval none
*/
void usbh_irq_handler(otg_core_type *otgdev)
{
otg_global_type *usbx = otgdev->usb_reg;
usbh_core_type *uhost = &otgdev->host;
uint32_t intsts = usb_global_get_all_interrupt(usbx);
if(usbx->gintsts_bit.curmode == 1)
{
if(intsts & USB_OTG_HCH_FLAG)
{
usbh_hch_handler(uhost);
usb_global_clear_interrupt(usbx, USB_OTG_HCH_FLAG);
}
if(intsts & USB_OTG_SOF_FLAG)
{
usbh_sof_handler(uhost);
usb_global_clear_interrupt(usbx, USB_OTG_SOF_FLAG);
}
if(intsts & USB_OTG_MODEMIS_FLAG)
{
usb_global_clear_interrupt(usbx, USB_OTG_MODEMIS_FLAG);
}
if(intsts & USB_OTG_WKUP_FLAG)
{
usbh_wakeup_handler(uhost);
usb_global_clear_interrupt(usbx, USB_OTG_WKUP_FLAG);
}
while(usbx->gintsts & USB_OTG_RXFLVL_FLAG)
{
usbh_rx_qlvl_handler(uhost);
usb_global_clear_interrupt(usbx, USB_OTG_RXFLVL_FLAG);
}
if(intsts & USB_OTG_DISCON_FLAG)
{
usbh_disconnect_handler(uhost);
usb_global_clear_interrupt(usbx, USB_OTG_DISCON_FLAG);
}
if(intsts & USB_OTG_PRT_FLAG)
{
usbh_port_handler(uhost);
}
if(intsts & USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG)
{
usb_global_clear_interrupt(usbx, USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG);
}
if(intsts & USB_OTG_INCOMISOIN_FLAG)
{
usb_global_clear_interrupt(usbx, USB_OTG_INCOMISOIN_FLAG);
}
if(intsts & USB_OTG_PTXFEMP_FLAG)
{
usb_global_clear_interrupt(usbx, USB_OTG_PTXFEMP_FLAG);
}
if(intsts & USB_OTG_ISOOUTDROP_FLAG)
{
usb_global_clear_interrupt(usbx, USB_OTG_INCOMISOIN_FLAG);
}
}
}
/**
* @brief usb host wakeup handler
* @param uhost: to the structure of usbh_core_type
* @retval none
*/
void usbh_wakeup_handler(usbh_core_type *uhost)
{
uhost->global_state = USBH_WAKEUP;
}
/**
* @brief usb host sof handler
* @param uhost: to the structure of usbh_core_type
* @retval none
*/
void usbh_sof_handler(usbh_core_type *uhost)
{
uhost->timer ++;
}
/**
* @brief usb host disconnect handler
* @param uhost: to the structure of usbh_core_type
* @retval none
*/
void usbh_disconnect_handler(usbh_core_type *uhost)
{
otg_global_type *usbx = uhost->usb_reg;
uint8_t i_index;
usb_host_disable(usbx);
uhost->conn_sts = 0;
uhost->global_state = USBH_DISCONNECT;
for(i_index = 0; i_index < USB_HOST_CHANNEL_NUM; i_index ++)
{
usbh_free_channel(uhost, i_index);
}
usbh_fsls_clksel(usbx, USB_HCFG_CLK_48M);
}
/**
* @brief usb host in transfer request handler
* @param uhost: to the structure of usbh_core_type
* @param chn: channel number
* @retval none
*/
void usbh_hch_in_handler(usbh_core_type *uhost, uint8_t chn)
{
otg_global_type *usbx = uhost->usb_reg;
otg_hchannel_type *usb_chh = USB_CHL(usbx, chn);
uint32_t hcint_value = usb_chh->hcint & usb_chh->hcintmsk;
if( hcint_value & USB_OTG_HC_ACK_FLAG)
{
usb_chh->hcint = USB_OTG_HC_ACK_FLAG;
}
else if(hcint_value & USB_OTG_HC_STALL_FLAG)
{
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
usb_chh->hcint = USB_OTG_HC_NAK_FLAG | USB_OTG_HC_STALL_FLAG;
uhost->hch[chn].state = HCH_STALL;
usb_hch_halt(usbx, chn);
}
else if(hcint_value & USB_OTG_HC_DTGLERR_FLAG)
{
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
usb_hch_halt(usbx, chn);
usb_chh->hcint = USB_OTG_HC_DTGLERR_FLAG | USB_OTG_HC_NAK_FLAG;
uhost->hch[chn].state = HCH_DATATGLERR;
}
else if(hcint_value & USB_OTG_HC_FRMOVRRUN_FLAG)
{
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
usb_hch_halt(usbx, chn);
usb_chh->hcint = USB_OTG_HC_FRMOVRRUN_FLAG;
}
else if(hcint_value & USB_OTG_HC_XFERC_FLAG)
{
uhost->hch[chn].state = HCH_XFRC;
usb_chh->hcint = USB_OTG_HC_XFERC_FLAG;
if(usb_chh->hcchar_bit.eptype == EPT_BULK_TYPE || usb_chh->hcchar_bit.eptype == EPT_CONTROL_TYPE)
{
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
usb_hch_halt(usbx, chn);
usb_chh->hcint = USB_OTG_HC_NAK_FLAG;
}
else if(usb_chh->hcchar_bit.eptype == EPT_INT_TYPE)
{
usb_chh->hcchar_bit.oddfrm = TRUE;
uhost->urb_state[chn] = URB_DONE;
}
else if(usb_chh->hcchar_bit.eptype == EPT_ISO_TYPE)
{
uhost->urb_state[chn] = URB_DONE;
}
uhost->hch[chn].toggle_in ^= 1;
}
else if(hcint_value & USB_OTG_HC_CHHLTD_FLAG)
{
usb_chh->hcintmsk_bit.chhltdmsk = FALSE;
if(uhost->hch[chn].state == HCH_XFRC )
{
uhost->urb_state[chn] = URB_DONE;
}
else if(uhost->hch[chn].state == HCH_STALL)
{
uhost->urb_state[chn] = URB_STALL;
}
else if(uhost->hch[chn].state == HCH_XACTERR ||
uhost->hch[chn].state == HCH_DATATGLERR)
{
uhost->err_cnt[chn] ++;
if(uhost->err_cnt[chn] > 3)
{
uhost->urb_state[chn] = URB_ERROR;
uhost->err_cnt[chn] = 0;
}
else
{
uhost->urb_state[chn] = URB_NOTREADY;
}
usb_chh->hcchar_bit.chdis = FALSE;
usb_chh->hcchar_bit.chena = TRUE;
}
else if(uhost->hch[chn].state == HCH_NAK)
{
usb_chh->hcchar_bit.chdis = FALSE;
usb_chh->hcchar_bit.chena = TRUE;
uhost->urb_state[chn] = URB_NOTREADY;
}
usb_chh->hcint = USB_OTG_HC_CHHLTD_FLAG;
}
else if(hcint_value & USB_OTG_HC_XACTERR_FLAG)
{
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
uhost->hch[chn].state = HCH_XACTERR;
usb_hch_halt(usbx, chn);
uhost->err_cnt[chn] ++;
usb_chh->hcint = USB_OTG_HC_XACTERR_FLAG;
}
else if(hcint_value & USB_OTG_HC_NAK_FLAG)
{
if(usb_chh->hcchar_bit.eptype == EPT_INT_TYPE)
{
uhost->err_cnt[chn] = 0;
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
usb_hch_halt(usbx, chn);
}
else if(usb_chh->hcchar_bit.eptype == EPT_BULK_TYPE ||
usb_chh->hcchar_bit.eptype == EPT_CONTROL_TYPE)
{
uhost->err_cnt[chn] = 0;
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
usb_hch_halt(usbx, chn);
}
uhost->hch[chn].state = HCH_NAK;
usb_chh->hcint = USB_OTG_HC_NAK_FLAG;
}
else if(hcint_value & USB_OTG_HC_BBLERR_FLAG)
{
usb_chh->hcint = USB_OTG_HC_BBLERR_FLAG;
}
}
/**
* @brief usb host out transfer request handler
* @param uhost: to the structure of usbh_core_type
* @param chn: channel number
* @retval none
*/
void usbh_hch_out_handler(usbh_core_type *uhost, uint8_t chn)
{
otg_global_type *usbx = uhost->usb_reg;
otg_hchannel_type *usb_chh = USB_CHL(usbx, chn);
uint32_t hcint_value = usb_chh->hcint & usb_chh->hcintmsk;
if( hcint_value & USB_OTG_HC_ACK_FLAG)
{
usb_chh->hcint = USB_OTG_HC_ACK_FLAG;
}
else if( hcint_value & USB_OTG_HC_FRMOVRRUN_FLAG)
{
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
usb_hch_halt(usbx, chn);
usb_chh->hcint = USB_OTG_HC_FRMOVRRUN_FLAG;
}
else if( hcint_value & USB_OTG_HC_XFERC_FLAG)
{
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
usb_hch_halt(usbx, chn);
uhost->hch[chn].state = HCH_XFRC;
usb_chh->hcint = USB_OTG_HC_XFERC_FLAG;
}
else if( hcint_value & USB_OTG_HC_STALL_FLAG)
{
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
usb_chh->hcint = USB_OTG_HC_STALL_FLAG;
uhost->hch[chn].state = HCH_STALL;
usb_hch_halt(usbx, chn);
}
else if( hcint_value & USB_OTG_HC_DTGLERR_FLAG)
{
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
usb_hch_halt(usbx, chn);
usb_chh->hcint = USB_OTG_HC_DTGLERR_FLAG | USB_OTG_HC_NAK_FLAG;
uhost->hch[chn].state = HCH_DATATGLERR;
}
else if( hcint_value & USB_OTG_HC_CHHLTD_FLAG)
{
usb_chh->hcintmsk_bit.chhltdmsk = FALSE;
if(uhost->hch[chn].state == HCH_XFRC)
{
uhost->urb_state[chn] = URB_DONE;
if(uhost->hch[chn].ept_type == EPT_BULK_TYPE ||
uhost->hch[chn].ept_type == EPT_INT_TYPE)
{
uhost->hch[chn].toggle_out ^= 1;
}
}
else if(uhost->hch[chn].state == HCH_NAK)
{
uhost->urb_state[chn] = URB_NOTREADY;
}
else if(uhost->hch[chn].state == HCH_STALL)
{
uhost->hch[chn].urb_sts = URB_STALL;
}
else if(uhost->hch[chn].state == HCH_XACTERR ||
uhost->hch[chn].state == HCH_DATATGLERR)
{
uhost->err_cnt[chn] ++;
if(uhost->err_cnt[chn] > 3)
{
uhost->urb_state[chn] = URB_ERROR;
uhost->err_cnt[chn] = 0;
}
else
{
uhost->urb_state[chn] = URB_NOTREADY;
}
usb_chh->hcchar_bit.chdis = FALSE;
usb_chh->hcchar_bit.chena = TRUE;
}
usb_chh->hcint = USB_OTG_HC_CHHLTD_FLAG;
}
else if( hcint_value & USB_OTG_HC_XACTERR_FLAG)
{
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
uhost->err_cnt[chn] ++;
uhost->hch[chn].state = HCH_XACTERR;
usb_hch_halt(usbx, chn);
usb_chh->hcint = USB_OTG_HC_XACTERR_FLAG | USB_OTG_HC_NAK_FLAG;
}
else if( hcint_value & USB_OTG_HC_NAK_FLAG)
{
usb_chh->hcintmsk_bit.chhltdmsk = TRUE;
uhost->err_cnt[chn] = 0;
usb_hch_halt(usbx, chn);
uhost->hch[chn].state = HCH_NAK;
usb_chh->hcint = USB_OTG_HC_NAK_FLAG;
}
}
/**
* @brief usb host channel request handler
* @param uhost: to the structure of usbh_core_type
* @retval none
*/
void usbh_hch_handler(usbh_core_type *uhost)
{
otg_global_type *usbx = uhost->usb_reg;
otg_host_type *usb_host = OTG_HOST(usbx);
uint32_t intsts, i_index;
intsts = usb_host->haint & 0xFFFF;
for(i_index = 0; i_index < 16; i_index ++)
{
if(intsts & (1 << i_index))
{
if(USB_CHL(usbx, i_index)->hcchar_bit.eptdir)
{
//hc in
usbh_hch_in_handler(uhost, i_index);
}
else
{
//hc out
usbh_hch_out_handler(uhost, i_index);
}
}
}
}
/**
* @brief usb host rx buffer not empty request handler
* @param uhost: to the structure of usbh_core_type
* @retval none
*/
void usbh_rx_qlvl_handler(usbh_core_type *uhost)
{
uint8_t chn;
uint32_t pktsts;
uint32_t pktcnt;
uint32_t tmp;
otg_hchannel_type *ch;
otg_global_type *usbx = uhost->usb_reg;
usbx->gintmsk_bit.rxflvlmsk = 0;
tmp = usbx->grxstsp;
chn = tmp & 0xF;
pktsts = (tmp >> 17) & 0xF;
pktcnt = (tmp >> 4) & 0x7FF;
ch = USB_CHL(usbx, chn);
switch(pktsts)
{
case PKTSTS_IN_DATA_PACKET_RECV:
if(pktcnt > 0 && (uhost->hch[chn].trans_buf) != 0)
{
usb_read_packet(usbx, uhost->hch[chn].trans_buf, chn, pktcnt);
uhost->hch[chn].trans_buf += pktcnt;
uhost->hch[chn].trans_count += pktcnt;
if(ch->hctsiz_bit.pktcnt > 0)
{
ch->hcchar_bit.chdis = FALSE;
ch->hcchar_bit.chena = TRUE;
uhost->hch[chn].toggle_in ^= 1;
}
}
break;
case PKTSTS_IN_TRANSFER_COMPLETE:
break;
case PKTSTS_DATA_BIT_ERROR:
break;
case PKTSTS_CHANNEL_STOP:
break;
default:
break;
}
usbx->gintmsk_bit.rxflvlmsk = 1;
}
/**
* @brief usb host port request handler
* @param uhost: to the structure of usbh_core_type
* @retval none
*/
void usbh_port_handler(usbh_core_type *uhost)
{
otg_global_type *usbx = uhost->usb_reg;
otg_host_type *usb_host = OTG_HOST(usbx);
uint32_t prt = 0, prt_0;
prt = usb_host->hprt;
prt_0 = prt;
prt_0 &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG |
USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET);
if(prt & USB_OTG_HPRT_PRTCONDET)
{
if(prt & USB_OTG_HPRT_PRTCONSTS)
{
/* connect callback */
uhost->conn_sts = 1;
}
prt_0 |= USB_OTG_HPRT_PRTCONDET;
}
if(prt & USB_OTG_HPRT_PRTENCHNG)
{
prt_0 |= USB_OTG_HPRT_PRTENCHNG;
if(prt & USB_OTG_HPRT_PRTENA)
{
if((prt & USB_OTG_HPRT_PRTSPD) == (USB_PRTSPD_LOW_SPEED << 17))
{
usbh_fsls_clksel(usbx, USB_HCFG_CLK_6M);
}
else
{
usbh_fsls_clksel(usbx, USB_HCFG_CLK_48M);
}
/* connect callback */
uhost->port_enable = 1;
}
else
{
/* clean up hprt */
uhost->port_enable = 0;
}
}
if(prt & USB_OTG_HPRT_PRTOVRCACT)
{
prt_0 |= USB_OTG_HPRT_PRTOVRCACT;
}
usb_host->hprt = prt_0;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View file

@ -1,75 +0,0 @@
/**
**************************************************************************
* @file usbh_int.h
* @brief usb header file
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBH_INT_H
#define __USBH_INT_H
#ifdef __cplusplus
extern "C" {
#endif
/** @addtogroup AT32F435_437_middlewares_usbh_drivers
* @{
*/
/** @addtogroup USBH_drivers_int
* @{
*/
/** @defgroup USBH_interrupt_exported_types
* @{
*/
/* includes ------------------------------------------------------------------*/
#include "usbh_core.h"
#include "usb_core.h"
void usbh_irq_handler(otg_core_type *hdev);
void usbh_hch_handler(usbh_core_type *uhost);
void usbh_port_handler(usbh_core_type *uhost);
void usbh_disconnect_handler(usbh_core_type *uhost);
void usbh_hch_in_handler(usbh_core_type *uhost, uint8_t chn);
void usbh_hch_out_handler(usbh_core_type *uhost, uint8_t chn);
void usbh_rx_qlvl_handler(usbh_core_type *uhost);
void usbh_wakeup_handler(usbh_core_type *uhost);
void usbh_sof_handler(usbh_core_type *uhost);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif

View file

@ -4,9 +4,10 @@ MCU_FLASH_SIZE := 4032
DEVICE_FLAGS = -DAT32F435ZMT7
TARGET_MCU_FAMILY := AT32F4
STDPERIPH_DIR = $(ROOT)/lib/main/AT32F43x/drivers
STDPERIPH_SRC = \
$(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) \
AT_LIB_DIR = $(ROOT)/lib/main/AT32F43x
STDPERIPH_DIR = $(AT_LIB_DIR)/drivers
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
EXCLUDES = at32f435_437_dvp.c \
at32f435_437_can.c \
@ -16,18 +17,21 @@ EXCLUDES = at32f435_437_dvp.c \
STARTUP_SRC = at32/startup_at32f435_437.s
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
VPATH := $(VPATH):$(ROOT)/lib/main/AT32F43x/cmsis/cm4/core_support:$(STDPERIPH_DIR)/inc:$(SRC_DIR)/startup/at32
VPATH := $(VPATH):$(AT_LIB_DIR)/cmsis/cm4/core_support:$(STDPERIPH_DIR)/inc:$(SRC_DIR)/startup/at32:$(STDPERIPH_DIR)/src
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(SRC_DIR)/startup/at32 \
$(STDPERIPH_DIR)/inc \
$(ROOT)/lib/main/AT32F43x/cmsis/cm4/core_support \
$(ROOT)/lib/main/AT32F43x/cmsis/cm4 \
$(ROOT)/lib/main/AT32F43x/middlewares/i2c_application_library
$(AT_LIB_DIR)/cmsis/cm4/core_support \
$(AT_LIB_DIR)/cmsis/cm4 \
$(AT_LIB_DIR)/middlewares/i2c_application_library \
$(AT_LIB_DIR)/middlewares/usb_drivers/inc \
$(AT_LIB_DIR)/middlewares/usbd_class/cdc
DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
TARGET_SRC := $(ROOT)/lib/main/AT32F43x/middlewares/i2c_application_library/i2c_application.c
TARGET_SRC := \
$(AT_LIB_DIR)/middlewares/i2c_application_library/i2c_application.c
LD_SCRIPT = $(LINKER_DIR)/at32_flash_f43xM.ld
@ -38,10 +42,11 @@ MCU_COMMON_SRC = \
$(addprefix startup/at32/,$(notdir $(wildcard $(SRC_DIR)/startup/at32/*.c))) \
$(addprefix drivers/at32/,$(notdir $(wildcard $(SRC_DIR)/drivers/at32/*.c))) \
drivers/bus_i2c_timing.c
MCU_EXCLUDES =
VCP_SRC = \
$(addprefix drivers/at32/usb/,$(notdir $(wildcard $(SRC_DIR)/drivers/at32/usb/*.c))) \
drivers/usb_io.c
$(addprefix $(AT_LIB_DIR)/middlewares/usbd_class/cdc/,$(notdir $(wildcard $(AT_LIB_DIR)/middlewares/usbd_class/cdc/*.c))) \
$(addprefix $(AT_LIB_DIR)/middlewares/usb_drivers/src/,$(notdir $(wildcard $(AT_LIB_DIR)/middlewares/usb_drivers/src/*.c))) \
drivers/usb_io.c