solve gcc build err

This commit is contained in:
tyustli 2019-12-26 14:10:06 +08:00
parent 8d0ca47526
commit 00fa2e2d78
22 changed files with 15002 additions and 3 deletions

View File

@ -123,6 +123,27 @@ menu "Onboard Peripheral Drivers"
config BSP_USING_SDRAM
bool "Enable SDRAM"
default n
menuconfig BSP_USING_USB_HOST
bool "Enable USB Host"
select RT_USING_USB_HOST
default n
if BSP_USING_USB_HOST
menuconfig RT_USBH_MSTORAGE
bool "Enable Udisk Drivers"
default n
if RT_USBH_MSTORAGE
config UDISK_MOUNTPOINT
string "Udisk mount dir"
default "/"
endif
endif
config BSP_USING_USB_DEVICE
bool "Enable USB Device"
select RT_USING_USB_DEVICE
default n
endmenu
endmenu

View File

@ -1,8 +1,10 @@
from building import *
cwd = GetCurrentDir()
src = []
cwd = []
CPPDEFINES = []
cwd = GetCurrentDir()
if GetDepend('BSP_USING_GPIO'):
src += ['drv_gpio.c']
@ -43,8 +45,24 @@ if GetDepend('BSP_USING_LCD'):
if GetDepend('BSP_USING_ETH'):
src += ['drv_eth.c']
if GetDepend('BSP_USING_USB_DEVICE'):
src += ['drv_usbd.c']
src += Glob('usb/device/*.c')
if GetDepend('BSP_USING_USB_DEVICE'):
src += Glob('usb/phy/*.c')
CPPDEFINES += ['ENDIANNESS']
if GetDepend('BSP_USING_USB_HOST'):
src += ['drv_usbh.c']
src += Glob('usb/host/*.c')
if GetDepend('BSP_USING_USB_HOST'):
src += Glob('usb/phy/*.c')
CPPDEFINES += ['ENDIANNESS']
path = [cwd,cwd + '/config']
group = DefineGroup('Drivers', src, depend = [''], CPPPATH = path)
group = DefineGroup('Drivers', src, depend = [''], CPPPATH = path, CPPDEFINES=CPPDEFINES)
Return('group')

View File

@ -0,0 +1,338 @@
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2017-12-04 ZYH first implementation
*/
#include <usb/include/usb_device_config.h>
#include <usb/include/usb.h>
#include <rtthread.h>
#include <usb/phy/usb_phy.h>
#include <usb/device/usb_device.h>
#include <usb/device/usb_device_dci.h>
#include <rtdevice.h>
/* USB PHY condfiguration */
#define BOARD_USB_PHY_D_CAL (0x0CU)
#define BOARD_USB_PHY_TXCAL45DP (0x06U)
#define BOARD_USB_PHY_TXCAL45DM (0x06U)
static usb_device_handle ehci0_handle;
static struct udcd _fsl_udc_0;
static usb_status_t usb_device_callback(usb_device_handle handle, uint32_t callbackEvent, void *eventParam);
static usb_status_t usb_device_endpoint_callback(usb_device_handle handle, usb_device_endpoint_callback_message_struct_t *message, void *callbackParam);
static void USB_DeviceIsrEnable(uint8_t controllerId)
{
uint8_t irqNumber;
#if defined(USB_DEVICE_CONFIG_EHCI) && (USB_DEVICE_CONFIG_EHCI > 0U)
uint8_t usbDeviceEhciIrq[] = USBHS_IRQS;
irqNumber = usbDeviceEhciIrq[controllerId - kUSB_ControllerEhci0];
#endif
/* Install isr, set priority, and enable IRQ. */
#if defined(__GIC_PRIO_BITS)
GIC_SetPriority((IRQn_Type)irqNumber, 3);
#else
NVIC_SetPriority((IRQn_Type)irqNumber, 3);
#endif
EnableIRQ((IRQn_Type)irqNumber);
}
/*!
* @brief Initializes USB specific setting that was not set by the Clocks tool.
*/
static void USB_DeviceClockInit(uint8_t controllerId)
{
#if defined(USB_DEVICE_CONFIG_EHCI) && (USB_DEVICE_CONFIG_EHCI > 0U)
usb_phy_config_struct_t phyConfig = {
BOARD_USB_PHY_D_CAL, BOARD_USB_PHY_TXCAL45DP, BOARD_USB_PHY_TXCAL45DM,
};
#endif
#if defined(USB_DEVICE_CONFIG_EHCI) && (USB_DEVICE_CONFIG_EHCI > 0U)
if (controllerId == kUSB_ControllerEhci0)
{
CLOCK_EnableUsbhs0PhyPllClock(kCLOCK_Usbphy480M, 480000000U);
CLOCK_EnableUsbhs0Clock(kCLOCK_Usb480M, 480000000U);
}
else
{
CLOCK_EnableUsbhs1PhyPllClock(kCLOCK_Usbphy480M, 480000000U);
CLOCK_EnableUsbhs1Clock(kCLOCK_Usb480M, 480000000U);
}
USB_EhciPhyInit(controllerId, 0, &phyConfig);
#endif
}
static struct ep_id _ehci0_ep_pool[] =
{
{0x0, USB_EP_ATTR_CONTROL, USB_DIR_INOUT, 64, ID_ASSIGNED },
{0x1, USB_EP_ATTR_BULK, USB_DIR_IN, 64, ID_UNASSIGNED},
{0x1, USB_EP_ATTR_BULK, USB_DIR_OUT, 64, ID_UNASSIGNED},
{0x2, USB_EP_ATTR_INT, USB_DIR_IN, 64, ID_UNASSIGNED},
{0x2, USB_EP_ATTR_INT, USB_DIR_OUT, 64, ID_UNASSIGNED},
{0x3, USB_EP_ATTR_BULK, USB_DIR_IN, 64, ID_UNASSIGNED},
{0x3, USB_EP_ATTR_BULK, USB_DIR_OUT, 64, ID_UNASSIGNED},
{0x4, USB_EP_ATTR_INT, USB_DIR_IN, 64, ID_UNASSIGNED},
{0x4, USB_EP_ATTR_INT, USB_DIR_OUT, 64, ID_UNASSIGNED},
{0x5, USB_EP_ATTR_BULK, USB_DIR_IN, 64, ID_UNASSIGNED},
{0x5, USB_EP_ATTR_BULK, USB_DIR_OUT, 64, ID_UNASSIGNED},
{0x6, USB_EP_ATTR_INT, USB_DIR_IN, 64, ID_UNASSIGNED},
{0x6, USB_EP_ATTR_INT, USB_DIR_OUT, 64, ID_UNASSIGNED},
{0x7, USB_EP_ATTR_BULK, USB_DIR_IN, 64, ID_UNASSIGNED},
{0x7, USB_EP_ATTR_BULK, USB_DIR_OUT, 64, ID_UNASSIGNED},
{0xFF, USB_EP_ATTR_TYPE_MASK, USB_DIR_MASK, 0, ID_ASSIGNED },
};
/*!
* @brief USB Interrupt service routine.
*
* This function serves as the USB interrupt service routine.
*
* @return None.
*/
void USB_OTG1_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
USB_DeviceEhciIsrFunction(ehci0_handle);
/* leave interrupt */
rt_interrupt_leave();
}
static rt_err_t _ehci0_ep_set_stall(rt_uint8_t address)
{
USB_DeviceStallEndpoint(ehci0_handle, address);
return RT_EOK;
}
static rt_err_t _ehci0_ep_clear_stall(rt_uint8_t address)
{
USB_DeviceUnstallEndpoint(ehci0_handle, address);
return RT_EOK;
}
static rt_err_t _ehci0_set_address(rt_uint8_t address)
{
USB_DeviceSetStatus(ehci0_handle, kUSB_DeviceStatusAddress, &address);
return RT_EOK;
}
static rt_err_t _ehci0_set_config(rt_uint8_t address)
{
return RT_EOK;
}
static rt_err_t _ehci0_ep_enable(uep_t ep)
{
usb_device_endpoint_init_struct_t ep_init;
usb_device_endpoint_callback_struct_t ep_callback;
rt_uint32_t param = ep->ep_desc->bEndpointAddress;
RT_ASSERT(ep != RT_NULL);
RT_ASSERT(ep->ep_desc != RT_NULL);
ep_init.maxPacketSize = ep->ep_desc->wMaxPacketSize;
ep_init.endpointAddress = ep->ep_desc->bEndpointAddress;
ep_init.transferType = ep->ep_desc->bmAttributes;
ep_init.zlt = 0;
ep_callback.callbackFn = usb_device_endpoint_callback;
ep_callback.callbackParam = (void *)param;
ep_callback.isBusy = 0;
USB_DeviceInitEndpoint(ehci0_handle, &ep_init, &ep_callback);
return RT_EOK;
}
static rt_err_t _ehci0_ep_disable(uep_t ep)
{
RT_ASSERT(ep != RT_NULL);
RT_ASSERT(ep->ep_desc != RT_NULL);
USB_DeviceDeinitEndpoint(ehci0_handle, ep->ep_desc->bEndpointAddress);
return RT_EOK;
}
static rt_size_t _ehci0_ep_read(rt_uint8_t address, void *buffer)
{
rt_size_t size = 0;
RT_ASSERT(buffer != RT_NULL);
return size;
}
static rt_size_t _ehci0_ep_read_prepare(rt_uint8_t address, void *buffer, rt_size_t size)
{
USB_DeviceRecvRequest(ehci0_handle, address, buffer, size);
return size;
}
static rt_size_t _ehci0_ep_write(rt_uint8_t address, void *buffer, rt_size_t size)
{
USB_DeviceSendRequest(ehci0_handle, address, buffer, size);
return size;
}
static rt_err_t _ehci0_ep0_send_status(void)
{
_ehci0_ep_write(0x00, NULL, 0);
return RT_EOK;
}
static rt_err_t _ehci0_suspend(void)
{
return RT_EOK;
}
static rt_err_t _ehci0_wakeup(void)
{
return RT_EOK;
}
const static struct udcd_ops _ehci0_udc_ops =
{
_ehci0_set_address,
_ehci0_set_config,
_ehci0_ep_set_stall,
_ehci0_ep_clear_stall,
_ehci0_ep_enable,
_ehci0_ep_disable,
_ehci0_ep_read_prepare,
_ehci0_ep_read,
_ehci0_ep_write,
_ehci0_ep0_send_status,
_ehci0_suspend,
_ehci0_wakeup,
};
static rt_err_t drv_ehci0_usbd_init(rt_device_t device)
{
usb_status_t result;
USB_DeviceClockInit(kUSB_ControllerEhci0);
result = USB_DeviceInit(kUSB_ControllerEhci0, usb_device_callback, &ehci0_handle);
RT_ASSERT(ehci0_handle);
if(result == kStatus_USB_Success)
{
USB_DeviceIsrEnable(kUSB_ControllerEhci0);
USB_DeviceRun(ehci0_handle);
}
else
{
rt_kprintf("USB_DeviceInit ehci0 error\r\n");
return RT_ERROR;
}
return RT_EOK;
}
static int rt_usbd_init(void)
{
rt_memset((void *)&_fsl_udc_0, 0, sizeof(struct udcd));
_fsl_udc_0.parent.type = RT_Device_Class_USBDevice;
_fsl_udc_0.parent.init = drv_ehci0_usbd_init;
_fsl_udc_0.ops = &_ehci0_udc_ops;
/* Register endpoint infomation */
_fsl_udc_0.ep_pool = _ehci0_ep_pool;
_fsl_udc_0.ep0.id = &_ehci0_ep_pool[0];
_fsl_udc_0.device_is_hs = RT_FALSE;
rt_device_register((rt_device_t)&_fsl_udc_0, "usbd", 0);
rt_usb_device_init();
return 0;
}
INIT_DEVICE_EXPORT(rt_usbd_init);
static usb_status_t usb_device_endpoint_callback(usb_device_handle handle, usb_device_endpoint_callback_message_struct_t *message, void *callbackParam)
{
rt_uint32_t ep_addr = (rt_uint32_t)callbackParam;
usb_device_struct_t *deviceHandle = (usb_device_struct_t *)handle;
udcd_t udcd = RT_NULL;
uint8_t state;
if(deviceHandle->controllerId == kUSB_ControllerEhci0)
udcd = &_fsl_udc_0;
if(message->isSetup)
{
rt_usbd_ep0_setup_handler(udcd, (struct urequest*)message->buffer);
}
else if(ep_addr == 0x00)
{
USB_DeviceGetStatus(handle, kUSB_DeviceStatusDeviceState, &state);
if(state == kUSB_DeviceStateAddressing)
{
if (kStatus_USB_Success == USB_DeviceSetStatus(handle, kUSB_DeviceStatusAddress, NULL))
{
state = kUSB_DeviceStateAddress;
USB_DeviceSetStatus(handle, kUSB_DeviceStatusDeviceState, &state);
}
}
rt_usbd_ep0_out_handler(udcd, message->length);
}
else if(ep_addr == 0x80)
{
USB_DeviceGetStatus(handle, kUSB_DeviceStatusDeviceState, &state);
if(state == kUSB_DeviceStateAddressing)
{
if (kStatus_USB_Success == USB_DeviceSetStatus(handle, kUSB_DeviceStatusAddress, NULL))
{
state = kUSB_DeviceStateAddress;
USB_DeviceSetStatus(handle, kUSB_DeviceStatusDeviceState, &state);
}
}
rt_usbd_ep0_in_handler(udcd);
}
else if(ep_addr & 0x80)
{
rt_usbd_ep_in_handler(udcd, ep_addr, message->length);
}
else
{
rt_usbd_ep_out_handler(udcd, ep_addr, message->length);
}
return kStatus_USB_Success;
}
static usb_status_t usb_device_callback(usb_device_handle handle, uint32_t callbackEvent, void *eventParam)
{
usb_status_t error = kStatus_USB_Error;
usb_device_struct_t *deviceHandle = (usb_device_struct_t *)handle;
usb_device_endpoint_init_struct_t ep0_init =
{
0x40,
0x00,
USB_EP_ATTR_CONTROL,
0
};
usb_device_endpoint_callback_struct_t ep0_callback =
{
usb_device_endpoint_callback,
0,
0
};
udcd_t udcd = RT_NULL;
if(deviceHandle->controllerId == kUSB_ControllerEhci0)
udcd = &_fsl_udc_0;
switch (callbackEvent)
{
case kUSB_DeviceEventBusReset:
ep0_init.endpointAddress = 0x00;
ep0_callback.callbackParam = (void *)0x00;
USB_DeviceInitEndpoint(deviceHandle, &ep0_init, &ep0_callback);
ep0_init.endpointAddress = 0x80;
ep0_callback.callbackParam = (void *)0x80;
USB_DeviceInitEndpoint(deviceHandle, &ep0_init, &ep0_callback);
rt_usbd_reset_handler(udcd);
break;
case kUSB_DeviceEventAttach:
rt_usbd_connect_handler(udcd);
break;
case kUSB_DeviceEventDetach:
rt_usbd_disconnect_handler(udcd);
break;
}
return error;
}
/********************* end of file ************************/

View File

@ -0,0 +1,644 @@
/*
* Copyright (c) 2015 - 2016, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __FSL_USB_DEVICE_H__
#define __FSL_USB_DEVICE_H__
/*!
* @addtogroup usb_device_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief Defines Get/Set status Types */
typedef enum _usb_device_status
{
kUSB_DeviceStatusTestMode = 1U, /*!< Test mode */
kUSB_DeviceStatusSpeed, /*!< Current speed */
kUSB_DeviceStatusOtg, /*!< OTG status */
kUSB_DeviceStatusDevice, /*!< Device status */
kUSB_DeviceStatusEndpoint, /*!< Endpoint state usb_device_endpoint_status_t */
kUSB_DeviceStatusDeviceState, /*!< Device state */
kUSB_DeviceStatusAddress, /*!< Device address */
kUSB_DeviceStatusSynchFrame, /*!< Current frame */
kUSB_DeviceStatusBus, /*!< Bus status */
kUSB_DeviceStatusBusSuspend, /*!< Bus suspend */
kUSB_DeviceStatusBusSleep, /*!< Bus suspend */
kUSB_DeviceStatusBusResume, /*!< Bus resume */
kUSB_DeviceStatusRemoteWakeup, /*!< Remote wakeup state */
kUSB_DeviceStatusBusSleepResume, /*!< Bus resume */
} usb_device_status_t;
/*! @brief Defines USB 2.0 device state */
typedef enum _usb_device_state
{
kUSB_DeviceStateConfigured = 0U, /*!< Device state, Configured*/
kUSB_DeviceStateAddress, /*!< Device state, Address*/
kUSB_DeviceStateDefault, /*!< Device state, Default*/
kUSB_DeviceStateAddressing, /*!< Device state, Address setting*/
kUSB_DeviceStateTestMode, /*!< Device state, Test mode*/
} usb_device_state_t;
#if (defined(USB_DEVICE_CHARGER_DETECT_ENABLE) && (USB_DEVICE_CHARGER_DETECT_ENABLE > 0U))
typedef enum _usb_dcd_detection_sequence_status
{
kUSB_DcdDetectionNotEnabled = 0x0U,
kUSB_DcdDataPinDetectionCompleted = 0x01U,
kUSB_DcdChargingPortDetectionCompleted = 0x02U,
kUSB_DcdChargerTypeDetectionCompleted = 0x03U,
} usb_dcd_detection_sequence_status_t;
typedef enum _usb_dcd_detection_sequence_results
{
kUSB_DcdDetectionNoResults = 0x0U,
kUSB_DcdDetectionStandardHost = 0x01U,
kUSB_DcdDetectionChargingPort = 0x02U,
kUSB_DcdDetectionDedicatedCharger = 0x03U,
} usb_dcd_detection_sequence_results_t;
#endif
/*! @brief Defines endpoint state */
typedef enum _usb_endpoint_status
{
kUSB_DeviceEndpointStateIdle = 0U, /*!< Endpoint state, idle*/
kUSB_DeviceEndpointStateStalled, /*!< Endpoint state, stalled*/
} usb_device_endpoint_status_t;
/*! @brief Control endpoint index */
#define USB_CONTROL_ENDPOINT (0U)
/*! @brief Control endpoint maxPacketSize */
#define USB_CONTROL_MAX_PACKET_SIZE (64U)
#if (USB_DEVICE_CONFIG_EHCI && (USB_CONTROL_MAX_PACKET_SIZE != (64U)))
#error For high speed, USB_CONTROL_MAX_PACKET_SIZE must be 64!!!
#endif
/*! @brief The setup packet size of USB control transfer. */
#define USB_SETUP_PACKET_SIZE (8U)
/*! @brief USB endpoint mask */
#define USB_ENDPOINT_NUMBER_MASK (0x0FU)
/*! @brief Default invalid value or the endpoint callback length of cancelled transfer */
#define USB_UNINITIALIZED_VAL_32 (0xFFFFFFFFU)
/*! @brief Available common EVENT types in device callback */
typedef enum _usb_device_event
{
kUSB_DeviceEventBusReset = 1U, /*!< USB bus reset signal detected */
kUSB_DeviceEventSuspend, /*!< USB bus suspend signal detected */
kUSB_DeviceEventResume, /*!< USB bus resume signal detected. The resume signal is driven by itself or a host */
kUSB_DeviceEventSleeped, /*!< USB bus LPM suspend signal detected */
kUSB_DeviceEventLPMResume, /*!< USB bus LPM resume signal detected. The resume signal is driven by itself or a host
*/
kUSB_DeviceEventError, /*!< An error is happened in the bus. */
kUSB_DeviceEventDetach, /*!< USB device is disconnected from a host. */
kUSB_DeviceEventAttach, /*!< USB device is connected to a host. */
kUSB_DeviceEventSetConfiguration, /*!< Set configuration. */
kUSB_DeviceEventSetInterface, /*!< Set interface. */
kUSB_DeviceEventGetDeviceDescriptor, /*!< Get device descriptor. */
kUSB_DeviceEventGetConfigurationDescriptor, /*!< Get configuration descriptor. */
kUSB_DeviceEventGetStringDescriptor, /*!< Get string descriptor. */
kUSB_DeviceEventGetHidDescriptor, /*!< Get HID descriptor. */
kUSB_DeviceEventGetHidReportDescriptor, /*!< Get HID report descriptor. */
kUSB_DeviceEventGetHidPhysicalDescriptor, /*!< Get HID physical descriptor. */
kUSB_DeviceEventGetBOSDescriptor, /*!< Get configuration descriptor. */
kUSB_DeviceEventGetDeviceQualifierDescriptor, /*!< Get device qualifier descriptor. */
kUSB_DeviceEventVendorRequest, /*!< Vendor request. */
kUSB_DeviceEventSetRemoteWakeup, /*!< Enable or disable remote wakeup function. */
kUSB_DeviceEventGetConfiguration, /*!< Get current configuration index */
kUSB_DeviceEventGetInterface, /*!< Get current interface alternate setting value */
kUSB_DeviceEventSetBHNPEnable,
#if (defined(USB_DEVICE_CHARGER_DETECT_ENABLE) && (USB_DEVICE_CHARGER_DETECT_ENABLE > 0U))
kUSB_DeviceEventDcdTimeOut, /*!< Dcd detect result is timeout */
kUSB_DeviceEventDcdUnknownType, /*!< Dcd detect result is unknown type */
kUSB_DeviceEventSDPDetected, /*!< The SDP facility is detected */
kUSB_DeviceEventChargingPortDetected, /*!< The charging port is detected */
kUSB_DeviceEventChargingHostDetected, /*!< The CDP facility is detected */
kUSB_DeviceEventDedicatedChargerDetected, /*!< The DCP facility is detected */
#endif
} usb_device_event_t;
/*! @brief Endpoint callback message structure */
typedef struct _usb_device_endpoint_callback_message_struct
{
uint8_t *buffer; /*!< Transferred buffer */
uint32_t length; /*!< Transferred data length */
uint8_t isSetup; /*!< Is in a setup phase */
} usb_device_endpoint_callback_message_struct_t;
/*!
* @brief Endpoint callback function typedef.
*
* This callback function is used to notify the upper layer what the transfer result is.
* This callback pointer is passed when a specified endpoint is initialized by calling API #USB_DeviceInitEndpoint.
*
* @param handle The device handle. It equals to the value returned from #USB_DeviceInit.
* @param message The result of a transfer, which includes transfer buffer, transfer length, and whether is in a
* setup phase.
* phase for control pipe.
* @param callbackParam The parameter for this callback. It is same with
* usb_device_endpoint_callback_struct_t::callbackParam.
*
* @return A USB error code or kStatus_USB_Success.
*/
typedef usb_status_t (*usb_device_endpoint_callback_t)(usb_device_handle handle,
usb_device_endpoint_callback_message_struct_t *message,
void *callbackParam);
/*!
* @brief Device callback function typedef.
*
* This callback function is used to notify the upper layer that the device status has changed.
* This callback pointer is passed by calling API #USB_DeviceInit.
*
* @param handle The device handle. It equals the value returned from #USB_DeviceInit.
* @param callbackEvent The callback event type. See enumeration #usb_device_event_t.
* @param eventParam The event parameter for this callback. The parameter type is determined by the callback event.
*
* @return A USB error code or kStatus_USB_Success.
*/
typedef usb_status_t (*usb_device_callback_t)(usb_device_handle handle, uint32_t callbackEvent, void *eventParam);
/*! @brief Endpoint callback structure */
typedef struct _usb_device_endpoint_callback_struct
{
usb_device_endpoint_callback_t callbackFn; /*!< Endpoint callback function*/
void *callbackParam; /*!< Parameter for callback function*/
uint8_t isBusy;
} usb_device_endpoint_callback_struct_t;
/*! @brief Endpoint initialization structure */
typedef struct _usb_device_endpoint_init_struct
{
uint16_t maxPacketSize; /*!< Endpoint maximum packet size */
uint8_t endpointAddress; /*!< Endpoint address*/
uint8_t transferType; /*!< Endpoint transfer type*/
uint8_t zlt; /*!< ZLT flag*/
} usb_device_endpoint_init_struct_t;
/*! @brief Endpoint status structure */
typedef struct _usb_device_endpoint_status_struct
{
uint8_t endpointAddress; /*!< Endpoint address */
uint16_t endpointStatus; /*!< Endpoint status : idle or stalled */
} usb_device_endpoint_status_struct_t;
#if (defined(USB_DEVICE_CHARGER_DETECT_ENABLE) && (USB_DEVICE_CHARGER_DETECT_ENABLE > 0U))
/*! @brief USB DCD charge timing specification structure */
typedef struct _usb_device_dcd_charging_time
{
uint16_t dcdSeqInitTime; /*!< The dcd sequence init time */
uint16_t dcdDbncTime; /*!< The debounce time period on DP signal */
uint16_t dcdDpSrcOnTime; /*!< The time period comparator enabled */
uint16_t dcdTimeWaitAfterPrD; /*!< The time period between primary and secondary detection */
uint8_t dcdTimeDMSrcOn; /*!< The amount of time that the modules enable the Vdm_src */
} usb_device_dcd_charging_time_t;
#endif
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus*/
/*!
* @name USB device APIs
* @{
*/
/*******************************************************************************
* API
******************************************************************************/
/*!
* @brief Initializes the USB device stack.
*
* This function initializes the USB device module specified by the controllerId.
*
* @param[in] controllerId The controller ID of the USB IP. See the enumeration #usb_controller_index_t.
* @param[in] deviceCallback Function pointer of the device callback.
* @param[out] handle It is an out parameter used to return the pointer of the device handle to the caller.
*
* @retval kStatus_USB_Success The device is initialized successfully.
* @retval kStatus_USB_InvalidHandle The handle is a NULL pointer.
* @retval kStatus_USB_Busy Cannot allocate a device handle.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller according to the controller id.
* @retval kStatus_USB_InvalidControllerInterface The controller driver interfaces is invalid. There is an empty
* interface entity.
* @retval kStatus_USB_Error The macro USB_DEVICE_CONFIG_ENDPOINTS is more than the IP's endpoint number.
* Or, the device has been initialized.
* Or, the mutex or message queue is created failed.
*/
extern usb_status_t USB_DeviceInit(uint8_t controllerId,
usb_device_callback_t deviceCallback,
usb_device_handle *handle);
/*!
* @brief Enables the device functionality.
*
* The function enables the device functionality, so that the device can be recognized by the host when the device
* detects that it has been connected to a host.
*
* @param[in] handle The device handle got from #USB_DeviceInit.
*
* @retval kStatus_USB_Success The device is run successfully.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller.
* @retval kStatus_USB_InvalidHandle The device handle is a NULL pointer. Or the controller handle is invalid.
*
*/
extern usb_status_t USB_DeviceRun(usb_device_handle handle);
/*!
* @brief Disables the device functionality.
*
* The function disables the device functionality. After this function called, even if the device is detached to the
* host,
* it can't work.
*
* @param[in] handle The device handle received from #USB_DeviceInit.
*
* @retval kStatus_USB_Success The device is stopped successfully.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller.
* @retval kStatus_USB_InvalidHandle The device handle is a NULL pointer or the controller handle is invalid.
*/
extern usb_status_t USB_DeviceStop(usb_device_handle handle);
/*!
* @brief De-initializes the device controller.
*
* The function de-initializes the device controller specified by the handle.
*
* @param[in] handle The device handle got from #USB_DeviceInit.
*
* @retval kStatus_USB_Success The device is stopped successfully.
* @retval kStatus_USB_InvalidHandle The device handle is a NULL pointer or the controller handle is invalid.
*/
extern usb_status_t USB_DeviceDeinit(usb_device_handle handle);
/*!
* @brief Sends data through a specified endpoint.
*
* The function is used to send data through a specified endpoint.
*
* @param[in] handle The device handle got from #USB_DeviceInit.
* @param[in] endpointAddress Endpoint index.
* @param[in] buffer The memory address to hold the data need to be sent. The function is not reentrant.
* @param[in] length The data length need to be sent.
*
* @retval kStatus_USB_Success The send request is sent successfully.
* @retval kStatus_USB_InvalidHandle The handle is a NULL pointer. Or the controller handle is invalid.
* @retval kStatus_USB_Busy Cannot allocate DTDS for current transfer in EHCI driver.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller.
* @retval kStatus_USB_Error The device is doing reset.
*
* @note The return value indicates whether the sending request is successful or not. The transfer done is notified by
* the
* corresponding callback function.
* Currently, only one transfer request can be supported for one specific endpoint.
* If there is a specific requirement to support multiple transfer requests for one specific endpoint, the application
* should implement a queue on the application level.
* The subsequent transfer can begin only when the previous transfer is done (get notification through the endpoint
* callback).
*/
extern usb_status_t USB_DeviceSendRequest(usb_device_handle handle,
uint8_t endpointAddress,
uint8_t *buffer,
uint32_t length);
/*!
* @brief Receives data through a specified endpoint.
*
* The function is used to receive data through a specified endpoint. The function is not reentrant.
*
* @param[in] handle The device handle got from #USB_DeviceInit.
* @param[in] endpointAddress Endpoint index.
* @param[in] buffer The memory address to save the received data.
* @param[in] length The data length want to be received.
*
* @retval kStatus_USB_Success The receive request is sent successfully.
* @retval kStatus_USB_InvalidHandle The handle is a NULL pointer. Or the controller handle is invalid.
* @retval kStatus_USB_Busy Cannot allocate DTDS for current transfer in EHCI driver.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller.
* @retval kStatus_USB_Error The device is doing reset.
*
* @note The return value indicates whether the receiving request is successful or not. The transfer done is notified by
* the
* corresponding callback function.
* Currently, only one transfer request can be supported for one specific endpoint.
* If there is a specific requirement to support multiple transfer requests for one specific endpoint, the application
* should implement a queue on the application level.
* The subsequent transfer can begin only when the previous transfer is done (get notification through the endpoint
* callback).
*/
extern usb_status_t USB_DeviceRecvRequest(usb_device_handle handle,
uint8_t endpointAddress,
uint8_t *buffer,
uint32_t length);
/*!
* @brief Cancels the pending transfer in a specified endpoint.
*
* The function is used to cancel the pending transfer in a specified endpoint.
*
* @param[in] handle The device handle got from #USB_DeviceInit.
* @param[in] endpointAddress Endpoint address, bit7 is the direction of endpoint, 1U - IN, and 0U - OUT.
*
* @retval kStatus_USB_Success The transfer is cancelled.
* @retval kStatus_USB_InvalidHandle The handle is a NULL pointer or the controller handle is invalid.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller.
*/
extern usb_status_t USB_DeviceCancel(usb_device_handle handle, uint8_t endpointAddress);
/*!
* @brief Initializes a specified endpoint.
*
* The function is used to initialize a specified endpoint. The corresponding endpoint callback is also initialized.
*
* @param[in] handle The device handle received from #USB_DeviceInit.
* @param[in] epInit Endpoint initialization structure. See the structure usb_device_endpoint_init_struct_t.
* @param[in] epCallback Endpoint callback structure. See the structure
* usb_device_endpoint_callback_struct_t.
*
* @retval kStatus_USB_Success The endpoint is initialized successfully.
* @retval kStatus_USB_InvalidHandle The handle is a NULL pointer. Or the controller handle is invalid.
* @retval kStatus_USB_InvalidParameter The epInit or epCallback is NULL pointer. Or the endpoint number is
* more than USB_DEVICE_CONFIG_ENDPOINTS.
* @retval kStatus_USB_Busy The endpoint is busy in EHCI driver.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller.
*/
extern usb_status_t USB_DeviceInitEndpoint(usb_device_handle handle,
usb_device_endpoint_init_struct_t *epInit,
usb_device_endpoint_callback_struct_t *epCallback);
/*!
* @brief Deinitializes a specified endpoint.
*
* The function is used to deinitializes a specified endpoint.
*
* @param[in] handle The device handle got from #USB_DeviceInit.
* @param[in] endpointAddress Endpoint address, bit7 is the direction of endpoint, 1U - IN, and 0U - OUT.
*
* @retval kStatus_USB_Success The endpoint is de-initialized successfully.
* @retval kStatus_USB_InvalidHandle The handle is a NULL pointer. Or the controller handle is invalid.
* @retval kStatus_USB_InvalidParameter The endpoint number is more than USB_DEVICE_CONFIG_ENDPOINTS.
* @retval kStatus_USB_Busy The endpoint is busy in EHCI driver.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller.
*/
extern usb_status_t USB_DeviceDeinitEndpoint(usb_device_handle handle, uint8_t endpointAddress);
/*!
* @brief Stalls a specified endpoint.
*
* The function is used to stall a specified endpoint.
*
* @param[in] handle The device handle received from #USB_DeviceInit.
* @param[in] endpointAddress Endpoint address, bit7 is the direction of endpoint, 1U - IN, and 0U - OUT.
*
* @retval kStatus_USB_Success The endpoint is stalled successfully.
* @retval kStatus_USB_InvalidHandle The handle is a NULL pointer. Or the controller handle is invalid.
* @retval kStatus_USB_InvalidParameter The endpoint number is more than USB_DEVICE_CONFIG_ENDPOINTS.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller.
*/
extern usb_status_t USB_DeviceStallEndpoint(usb_device_handle handle, uint8_t endpointAddress);
/*!
* @brief Unstalls a specified endpoint.
*
* The function is used to unstall a specified endpoint.
*
* @param[in] handle The device handle received from #USB_DeviceInit.
* @param[in] endpointAddress Endpoint address, bit7 is the direction of endpoint, 1U - IN, and 0U - OUT.
*
* @retval kStatus_USB_Success The endpoint is unstalled successfully.
* @retval kStatus_USB_InvalidHandle The handle is a NULL pointer. Or the controller handle is invalid.
* @retval kStatus_USB_InvalidParameter The endpoint number is more than USB_DEVICE_CONFIG_ENDPOINTS.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller.
*/
extern usb_status_t USB_DeviceUnstallEndpoint(usb_device_handle handle, uint8_t endpointAddress);
/*!
* @brief Gets the status of the selected item.
*
* The function is used to get the status of the selected item.
*
* @param[in] handle The device handle got from #USB_DeviceInit.
* @param[in] type The selected item. See the structure #usb_device_status_t.
* @param[out] param The parameter type is determined by the selected item.
*
* @retval kStatus_USB_Success Get status successfully.
* @retval kStatus_USB_InvalidHandle The handle is a NULL pointer. Or the controller handle is invalid.
* @retval kStatus_USB_InvalidParameter The parameter is NULL pointer.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller.
* @retval kStatus_USB_Error Unsupported type.
*/
extern usb_status_t USB_DeviceGetStatus(usb_device_handle handle, usb_device_status_t type, void *param);
/*!
* @brief Sets the status of the selected item.
*
* The function is used to set the status of the selected item.
*
* @param[in] handle The device handle got from #USB_DeviceInit.
* @param[in] type The selected item. See the structure #usb_device_status_t.
* @param[in] param The parameter type is determined by the selected item.
*
* @retval kStatus_USB_Success Set status successfully.
* @retval kStatus_USB_InvalidHandle The handle is a NULL pointer. Or the controller handle is invalid.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller.
* @retval kStatus_USB_Error Unsupported type or the parameter is NULL pointer.
*/
extern usb_status_t USB_DeviceSetStatus(usb_device_handle handle, usb_device_status_t type, void *param);
#if (defined(USB_DEVICE_CHARGER_DETECT_ENABLE) && (USB_DEVICE_CHARGER_DETECT_ENABLE > 0U))
/*!
* @brief Initializes the device dcd module.
*
* The function initializes the device dcd module.
*
* @param[in] handle The device handle got from #USB_DeviceInit.
* @param[in] time_param The time parameter used to config the dcd timing registers.
*
* @retval kStatus_USB_Success The device is run successfully.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller.
* @retval kStatus_USB_InvalidHandle The device handle is a NULL pointer. Or the controller handle is invalid.
*
*/
extern usb_status_t USB_DeviceDcdInitModule(usb_device_handle handle, void *time_param);
/*!
* @brief De-initializes the device dcd module.
*
* The function de-initializes the device dcd module specified by the handle.
*
* @param[in] handle The device handle got from #USB_DeviceInit.
*
* @retval kStatus_USB_Success The device is stopped successfully.
* @retval kStatus_USB_InvalidHandle The device handle is a NULL pointer or the controller handle is invalid.
*/
extern usb_status_t USB_DeviceDcdDeinitModule(usb_device_handle handle);
#endif
/*!
* @brief Device task function.
*
* The function is used to handle the controller message.
* This function should not be called in the application directly.
*
* @param[in] deviceHandle The device handle got from #USB_DeviceInit.
*/
extern void USB_DeviceTaskFunction(void *deviceHandle);
#if ((defined(USB_DEVICE_CONFIG_KHCI)) && (USB_DEVICE_CONFIG_KHCI > 0U))
/*!
* @brief Device KHCI task function.
*
* The function is used to handle the KHCI controller message.
* In the bare metal environment, this function should be called periodically in the main function.
* In the RTOS environment, this function should be used as a function entry to create a task.
*
* @param[in] deviceHandle The device handle got from #USB_DeviceInit.
*/
#define USB_DeviceKhciTaskFunction(deviceHandle) USB_DeviceTaskFunction(deviceHandle)
#endif
#if ((defined(USB_DEVICE_CONFIG_EHCI)) && (USB_DEVICE_CONFIG_EHCI > 0U))
/*!
* @brief Device EHCI task function.
*
* The function is used to handle the EHCI controller message.
* In the bare metal environment, this function should be called periodically in the main function.
* In the RTOS environment, this function should be used as a function entry to create a task.
*
* @param[in] deviceHandle The device handle got from #USB_DeviceInit.
*/
#define USB_DeviceEhciTaskFunction(deviceHandle) USB_DeviceTaskFunction(deviceHandle)
#if (defined(USB_DEVICE_CHARGER_DETECT_ENABLE) && (USB_DEVICE_CHARGER_DETECT_ENABLE > 0U))
/*!
* @brief Device EHCI DCD ISR function.
*
* The function is the EHCI DCD interrupt service routine.
*
* @param[in] deviceHandle The device handle got from #USB_DeviceInit.
*/
extern void USB_DeviceDcdHSIsrFunction(void *deviceHandle);
#endif
#endif
#if (((defined(USB_DEVICE_CONFIG_LPCIP3511FS)) && (USB_DEVICE_CONFIG_LPCIP3511FS > 0U)) || \
((defined(USB_DEVICE_CONFIG_LPCIP3511HS)) && (USB_DEVICE_CONFIG_LPCIP3511HS > 0U)))
/*!
* @brief Device LPC ip3511 controller task function.
*
* The function is used to handle the LPC ip3511 controller message.
* In the bare metal environment, this function should be called periodically in the main function.
* In the RTOS environment, this function should be used as a function entry to create a task.
*
* @param[in] deviceHandle The device handle got from #USB_DeviceInit.
*/
#define USB_DeviceLpcIp3511TaskFunction(deviceHandle) USB_DeviceTaskFunction(deviceHandle)
#endif
#if ((defined(USB_DEVICE_CONFIG_KHCI)) && (USB_DEVICE_CONFIG_KHCI > 0U))
/*!
* @brief Device KHCI ISR function.
*
* The function is the KHCI interrupt service routine.
*
* @param[in] deviceHandle The device handle got from #USB_DeviceInit.
*/
extern void USB_DeviceKhciIsrFunction(void *deviceHandle);
#if (defined(USB_DEVICE_CHARGER_DETECT_ENABLE) && (USB_DEVICE_CHARGER_DETECT_ENABLE > 0U))
/*!
* @brief Device KHCI DCD ISR function.
*
* The function is the KHCI DCD interrupt service routine.
*
* @param[in] deviceHandle The device handle got from #USB_DeviceInit.
*/
extern void USB_DeviceDcdIsrFunction(void *deviceHandle);
#endif
#endif
#if ((defined(USB_DEVICE_CONFIG_EHCI)) && (USB_DEVICE_CONFIG_EHCI > 0U))
/*!
* @brief Device EHCI ISR function.
*
* The function is the EHCI interrupt service routine.
*
* @param[in] deviceHandle The device handle got from #USB_DeviceInit.
*/
extern void USB_DeviceEhciIsrFunction(void *deviceHandle);
#endif
#if (((defined(USB_DEVICE_CONFIG_LPCIP3511FS)) && (USB_DEVICE_CONFIG_LPCIP3511FS > 0U)) || \
((defined(USB_DEVICE_CONFIG_LPCIP3511HS)) && (USB_DEVICE_CONFIG_LPCIP3511HS > 0U)))
/*!
* @brief Device LPC USB ISR function.
*
* The function is the LPC USB interrupt service routine.
*
* @param[in] deviceHandle The device handle got from #USB_DeviceInit.
*/
extern void USB_DeviceLpcIp3511IsrFunction(void *deviceHandle);
#endif
/*!
* @brief Gets the device stack version function.
*
* The function is used to get the device stack version.
*
* @param[out] version The version structure pointer to keep the device stack version.
*
*/
extern void USB_DeviceGetVersion(uint32_t *version);
#if ((defined(USB_DEVICE_CONFIG_REMOTE_WAKEUP)) && (USB_DEVICE_CONFIG_REMOTE_WAKEUP > 0U))
/*!
* @brief Update the hardware tick.
*
* The function is used to update the hardware tick.
*
* @param[in] handle The device handle got from #USB_DeviceInit.
* @param[in] tick Current hardware tick(uint is ms).
*
*/
extern usb_status_t USB_DeviceUpdateHwTick(usb_device_handle handle, uint64_t tick);
#endif
/*! @}*/
#if defined(__cplusplus)
}
#endif /* __cplusplus*/
/*! @}*/
#endif /* __USB_DEVICE_H__ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,177 @@
/*
* Copyright (c) 2015 - 2016, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __USB_DEVICE_DCI_H__
#define __USB_DEVICE_DCI_H__
/*!
* @addtogroup usb_device_controller_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief Macro to define controller handle */
#define usb_device_controller_handle usb_device_handle
/*! @brief Available notify types for device notification */
typedef enum _usb_device_notification
{
kUSB_DeviceNotifyBusReset = 0x10U, /*!< Reset signal detected */
kUSB_DeviceNotifySuspend, /*!< Suspend signal detected */
kUSB_DeviceNotifyResume, /*!< Resume signal detected */
kUSB_DeviceNotifyLPMSleep, /*!< LPM signal detected */
kUSB_DeviceNotifyLPMResume, /*!< Resume signal detected */
kUSB_DeviceNotifyError, /*!< Errors happened in bus */
kUSB_DeviceNotifyDetach, /*!< Device disconnected from a host */
kUSB_DeviceNotifyAttach, /*!< Device connected to a host */
#if (defined(USB_DEVICE_CHARGER_DETECT_ENABLE) && (USB_DEVICE_CHARGER_DETECT_ENABLE > 0U))
kUSB_DeviceNotifyDcdTimeOut, /*!< Device charger detection timeout */
kUSB_DeviceNotifyDcdUnknownPortType, /*!< Device charger detection unknown port type */
kUSB_DeviceNotifySDPDetected, /*!< The SDP facility is detected */
kUSB_DeviceNotifyChargingPortDetected, /*!< The charging port is detected */
kUSB_DeviceNotifyChargingHostDetected, /*!< The CDP facility is detected */
kUSB_DeviceNotifyDedicatedChargerDetected, /*!< The DCP facility is detected */
#endif
} usb_device_notification_t;
/*! @brief Device notification message structure */
typedef struct _usb_device_callback_message_struct
{
uint8_t *buffer; /*!< Transferred buffer */
uint32_t length; /*!< Transferred data length */
uint8_t code; /*!< Notification code */
uint8_t isSetup; /*!< Is in a setup phase */
} usb_device_callback_message_struct_t;
/*! @brief Control type for controller */
typedef enum _usb_device_control_type
{
kUSB_DeviceControlRun = 0U, /*!< Enable the device functionality */
kUSB_DeviceControlStop, /*!< Disable the device functionality */
kUSB_DeviceControlEndpointInit, /*!< Initialize a specified endpoint */
kUSB_DeviceControlEndpointDeinit, /*!< De-initialize a specified endpoint */
kUSB_DeviceControlEndpointStall, /*!< Stall a specified endpoint */
kUSB_DeviceControlEndpointUnstall, /*!< Unstall a specified endpoint */
kUSB_DeviceControlGetDeviceStatus, /*!< Get device status */
kUSB_DeviceControlGetEndpointStatus, /*!< Get endpoint status */
kUSB_DeviceControlSetDeviceAddress, /*!< Set device address */
kUSB_DeviceControlGetSynchFrame, /*!< Get current frame */
kUSB_DeviceControlResume, /*!< Drive controller to generate a resume signal in USB bus */
kUSB_DeviceControlSleepResume, /*!< Drive controller to generate a LPM resume signal in USB bus */
kUSB_DeviceControlSuspend, /*!< Drive controller to enetr into suspend mode */
kUSB_DeviceControlSleep, /*!< Drive controller to enetr into sleep mode */
kUSB_DeviceControlSetDefaultStatus, /*!< Set controller to default status */
kUSB_DeviceControlGetSpeed, /*!< Get current speed */
kUSB_DeviceControlGetOtgStatus, /*!< Get OTG status */
kUSB_DeviceControlSetOtgStatus, /*!< Set OTG status */
kUSB_DeviceControlSetTestMode, /*!< Drive xCHI into test mode */
kUSB_DeviceControlGetRemoteWakeUp, /*!< Get flag of LPM Remote Wake-up Enabled by USB host. */
#if (defined(USB_DEVICE_CHARGER_DETECT_ENABLE) && (USB_DEVICE_CHARGER_DETECT_ENABLE > 0U))
kUSB_DeviceControlDcdInitModule,
kUSB_DeviceControlDcdDeinitModule,
#endif
} usb_device_control_type_t;
/*! @brief USB device controller initialization function typedef */
typedef usb_status_t (*usb_device_controller_init_t)(uint8_t controllerId,
usb_device_handle handle,
usb_device_controller_handle *controllerHandle);
/*! @brief USB device controller de-initialization function typedef */
typedef usb_status_t (*usb_device_controller_deinit_t)(usb_device_controller_handle controllerHandle);
/*! @brief USB device controller send data function typedef */
typedef usb_status_t (*usb_device_controller_send_t)(usb_device_controller_handle controllerHandle,
uint8_t endpointAddress,
uint8_t *buffer,
uint32_t length);
/*! @brief USB device controller receive data function typedef */
typedef usb_status_t (*usb_device_controller_recv_t)(usb_device_controller_handle controllerHandle,
uint8_t endpointAddress,
uint8_t *buffer,
uint32_t length);
/*! @brief USB device controller cancel transfer function in a specified endpoint typedef */
typedef usb_status_t (*usb_device_controller_cancel_t)(usb_device_controller_handle controllerHandle,
uint8_t endpointAddress);
/*! @brief USB device controller control function typedef */
typedef usb_status_t (*usb_device_controller_control_t)(usb_device_controller_handle controllerHandle,
usb_device_control_type_t command,
void *param);
/*! @brief USB device controller interface structure */
typedef struct _usb_device_controller_interface_struct
{
usb_device_controller_init_t deviceInit; /*!< Controller initialization */
usb_device_controller_deinit_t deviceDeinit; /*!< Controller de-initialization */
usb_device_controller_send_t deviceSend; /*!< Controller send data */
usb_device_controller_recv_t deviceRecv; /*!< Controller receive data */
usb_device_controller_cancel_t deviceCancel; /*!< Controller cancel transfer */
usb_device_controller_control_t deviceControl; /*!< Controller control */
} usb_device_controller_interface_struct_t;
/*! @brief USB device status structure */
typedef struct _usb_device_struct
{
#if ((defined(USB_DEVICE_CONFIG_REMOTE_WAKEUP)) && (USB_DEVICE_CONFIG_REMOTE_WAKEUP > 0U))
volatile uint64_t hwTick; /*!< Current hw tick(ms)*/
#endif
usb_device_controller_handle controllerHandle; /*!< Controller handle */
const usb_device_controller_interface_struct_t *controllerInterface; /*!< Controller interface handle */
#if USB_DEVICE_CONFIG_USE_TASK
usb_osa_msgq_handle notificationQueue; /*!< Message queue */
#endif
usb_device_callback_t deviceCallback; /*!< Device callback function pointer */
usb_device_endpoint_callback_struct_t
epCallback[USB_DEVICE_CONFIG_ENDPOINTS << 1U]; /*!< Endpoint callback function structure */
uint8_t deviceAddress; /*!< Current device address */
uint8_t controllerId; /*!< Controller ID */
uint8_t state; /*!< Current device state */
#if ((defined(USB_DEVICE_CONFIG_REMOTE_WAKEUP)) && (USB_DEVICE_CONFIG_REMOTE_WAKEUP > 0U))
uint8_t remotewakeup; /*!< Remote wakeup is enabled or not */
#endif
uint8_t isResetting; /*!< Is doing device reset or not */
#if (defined(USB_DEVICE_CONFIG_USE_TASK) && (USB_DEVICE_CONFIG_USE_TASK > 0U))
uint8_t epCallbackDirectly; /*!< Whether call ep callback directly when the task is enabled */
#endif
} usb_device_struct_t;
/*******************************************************************************
* API
******************************************************************************/
/*! @}*/
#endif /* __USB_DEVICE_DCI_H__ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,219 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __USB_DEVICE_EHCI_H__
#define __USB_DEVICE_EHCI_H__
#include <usb/include/usb_ehci.h>
/*!
* @addtogroup usb_device_controller_ehci_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief The maximum value of ISO type maximum packet size for HS in USB specification 2.0 */
#define USB_DEVICE_MAX_HS_ISO_MAX_PACKET_SIZE (1024U)
/*! @brief The maximum value of interrupt type maximum packet size for HS in USB specification 2.0 */
#define USB_DEVICE_MAX_HS_INTERUPT_MAX_PACKET_SIZE (1024U)
/*! @brief The maximum value of bulk type maximum packet size for HS in USB specification 2.0 */
#define USB_DEVICE_MAX_HS_BULK_MAX_PACKET_SIZE (512U)
/*! @brief The maximum value of control type maximum packet size for HS in USB specification 2.0 */
#define USB_DEVICE_MAX_HS_CONTROL_MAX_PACKET_SIZE (64U)
/*! @brief EHCI state structure */
typedef struct _usb_device_ehci_state_struct
{
usb_device_struct_t *deviceHandle; /*!< Device handle used to identify the device object is belonged to */
USBHS_Type *registerBase; /*!< The base address of the register */
#if (defined(USB_DEVICE_CONFIG_LOW_POWER_MODE) && (USB_DEVICE_CONFIG_LOW_POWER_MODE > 0U))
USBPHY_Type *registerPhyBase; /*!< The base address of the PHY register */
#if (defined(FSL_FEATURE_SOC_USBNC_COUNT) && (FSL_FEATURE_SOC_USBNC_COUNT > 0U))
USBNC_Type *registerNcBase; /*!< The base address of the USBNC register */
#endif
#endif
usb_device_ehci_qh_struct_t *qh; /*!< The QH structure base address */
usb_device_ehci_dtd_struct_t *dtd; /*!< The DTD structure base address */
usb_device_ehci_dtd_struct_t *dtdFree; /*!< The idle DTD list head */
usb_device_ehci_dtd_struct_t
*dtdHard[USB_DEVICE_CONFIG_ENDPOINTS * 2]; /*!< The transferring DTD list head for each endpoint */
usb_device_ehci_dtd_struct_t
*dtdTail[USB_DEVICE_CONFIG_ENDPOINTS * 2]; /*!< The transferring DTD list tail for each endpoint */
int8_t dtdCount; /*!< The idle DTD node count */
uint8_t endpointCount; /*!< The endpoint number of EHCI */
uint8_t isResetting; /*!< Whether a PORT reset is occurring or not */
uint8_t controllerId; /*!< Controller ID */
uint8_t speed; /*!< Current speed of EHCI */
uint8_t isSuspending; /*!< Is suspending of the PORT */
} usb_device_ehci_state_struct_t;
#if (defined(USB_DEVICE_CHARGER_DETECT_ENABLE) && (USB_DEVICE_CHARGER_DETECT_ENABLE > 0U)) && \
(defined(FSL_FEATURE_SOC_USBHSDCD_COUNT) && (FSL_FEATURE_SOC_USBHSDCD_COUNT > 0U))
typedef struct _usb_device_dcd_state_struct
{
usb_device_struct_t *deviceHandle; /*!< Device handle used to identify the device object belongs to */
USBHSDCD_Type *dcdRegisterBase; /*!< The base address of the dcd module */
uint8_t controllerId; /*!< Controller ID */
} usb_device_dcd_state_struct_t;
#endif
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name USB device EHCI functions
* @{
*/
/*******************************************************************************
* API
******************************************************************************/
/*!
* @brief Initializes the USB device EHCI instance.
*
* This function initializes the USB device EHCI module specified by the controllerId.
*
* @param[in] controllerId The controller ID of the USB IP. See the enumeration type usb_controller_index_t.
* @param[in] handle Pointer of the device handle used to identify the device object is belonged to.
* @param[out] ehciHandle An out parameter used to return the pointer of the device EHCI handle to the caller.
*
* @return A USB error code or kStatus_USB_Success.
*/
usb_status_t USB_DeviceEhciInit(uint8_t controllerId,
usb_device_handle handle,
usb_device_controller_handle *ehciHandle);
/*!
* @brief Deinitializes the USB device EHCI instance.
*
* This function deinitializes the USB device EHCI module.
*
* @param[in] ehciHandle Pointer of the device EHCI handle.
*
* @return A USB error code or kStatus_USB_Success.
*/
usb_status_t USB_DeviceEhciDeinit(usb_device_controller_handle ehciHandle);
/*!
* @brief Sends data through a specified endpoint.
*
* This function sends data through a specified endpoint.
*
* @param[in] ehciHandle Pointer of the device EHCI handle.
* @param[in] endpointAddress Endpoint index.
* @param[in] buffer The memory address to hold the data need to be sent.
* @param[in] length The data length to be sent.
*
* @return A USB error code or kStatus_USB_Success.
*
* @note The return value means whether the sending request is successful or not. The transfer completion is indicated
* by the
* corresponding callback function.
* Currently, only one transfer request can be supported for a specific endpoint.
* If there is a specific requirement to support multiple transfer requests for a specific endpoint, the application
* should implement a queue in the application level.
* The subsequent transfer can begin only when the previous transfer is done (a notification is received through the
* endpoint
* callback).
*/
usb_status_t USB_DeviceEhciSend(usb_device_controller_handle ehciHandle,
uint8_t endpointAddress,
uint8_t *buffer,
uint32_t length);
/*!
* @brief Receive data through a specified endpoint.
*
* This function Receives data through a specified endpoint.
*
* @param[in] ehciHandle Pointer of the device EHCI handle.
* @param[in] endpointAddress Endpoint index.
* @param[in] buffer The memory address to save the received data.
* @param[in] length The data length want to be received.
*
* @return A USB error code or kStatus_USB_Success.
*
* @note The return value just means if the receiving request is successful or not; the transfer done is notified by the
* corresponding callback function.
* Currently, only one transfer request can be supported for one specific endpoint.
* If there is a specific requirement to support multiple transfer requests for one specific endpoint, the application
* should implement a queue in the application level.
* The subsequent transfer could begin only when the previous transfer is done (get notification through the endpoint
* callback).
*/
usb_status_t USB_DeviceEhciRecv(usb_device_controller_handle ehciHandle,
uint8_t endpointAddress,
uint8_t *buffer,
uint32_t length);
/*!
* @brief Cancels the pending transfer in a specified endpoint.
*
* The function is used to cancel the pending transfer in a specified endpoint.
*
* @param[in] ehciHandle Pointer of the device EHCI handle.
* @param[in] ep Endpoint address, bit7 is the direction of endpoint, 1U - IN, 0U - OUT.
*
* @return A USB error code or kStatus_USB_Success.
*/
usb_status_t USB_DeviceEhciCancel(usb_device_controller_handle ehciHandle, uint8_t ep);
/*!
* @brief Controls the status of the selected item.
*
* The function is used to control the status of the selected item.
*
* @param[in] ehciHandle Pointer of the device EHCI handle.
* @param[in] type The selected item. See enumeration type usb_device_control_type_t.
* @param[in,out] param The parameter type is determined by the selected item.
*
* @return A USB error code or kStatus_USB_Success.
*/
usb_status_t USB_DeviceEhciControl(usb_device_controller_handle ehciHandle,
usb_device_control_type_t type,
void *param);
/*! @} */
#if defined(__cplusplus)
}
#endif
/*! @} */
#endif /* __USB_DEVICE_EHCI_H__ */

View File

@ -0,0 +1,726 @@
/*
* Copyright (c) 2015 - 2016, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _USB_HOST_H_
#define _USB_HOST_H_
#include <usb/include/usb.h>
#include <usb/include/usb_misc.h>
#include <usb/include/usb_spec.h>
/*******************************************************************************
* Definitions
******************************************************************************/
struct _usb_host_transfer; /* for cross reference */
/*!
* @addtogroup usb_host_drv
* @{
*/
/*! @brief USB host class handle type define */
typedef void *usb_host_class_handle;
/*! @brief USB host controller handle type define */
typedef void *usb_host_controller_handle;
/*! @brief USB host configuration handle type define */
typedef void *usb_host_configuration_handle;
/*! @brief USB host interface handle type define */
typedef void *usb_host_interface_handle;
/*! @brief USB host pipe handle type define */
typedef void *usb_host_pipe_handle;
/*! @brief Event codes for device attach/detach */
typedef enum _usb_host_event
{
kUSB_HostEventAttach = 1U, /*!< Device is attached */
kUSB_HostEventDetach, /*!< Device is detached */
kUSB_HostEventEnumerationDone, /*!< Device's enumeration is done and the device is supported */
kUSB_HostEventNotSupported, /*!< Device's enumeration is done and the device is not supported */
#if ((defined(USB_HOST_CONFIG_LOW_POWER_MODE)) && (USB_HOST_CONFIG_LOW_POWER_MODE > 0U))
kUSB_HostEventNotSuspended, /*!< Suspend failed */
kUSB_HostEventSuspended, /*!< Suspend successful */
kUSB_HostEventNotResumed, /*!< Resume failed */
kUSB_HostEventDetectResume, /*!< Detect resume signal */
kUSB_HostEventResumed, /*!< Resume successful */
kUSB_HostEventL1Sleeped, /*!< L1 Sleep successful,state transition was successful (ACK) */
kUSB_HostEventL1SleepNYET, /*!< Device was unable to enter the L1 state at this time (NYET) */
kUSB_HostEventL1SleepNotSupport, /*!< Device does not support the L1 state (STALL) */
kUSB_HostEventL1SleepError, /*!< Device failed to respond or an error occurred */
kUSB_HostEventL1NotResumed, /*!< Resume failed */
kUSB_HostEventL1DetectResume, /*!< Detect resume signal */
kUSB_HostEventL1Resumed, /*!< Resume successful */
#endif
} usb_host_event_t;
/*! @brief USB host device information code */
typedef enum _usb_host_dev_info
{
kUSB_HostGetDeviceAddress = 1U, /*!< Device's address */
kUSB_HostGetDeviceHubNumber, /*!< Device's first hub address */
kUSB_HostGetDevicePortNumber, /*!< Device's first hub port number */
kUSB_HostGetDeviceSpeed, /*!< Device's speed */
kUSB_HostGetDeviceHSHubNumber, /*!< Device's first high-speed hub address */
kUSB_HostGetDeviceHSHubPort, /*!< Device's first high-speed hub number */
kUSB_HostGetDeviceLevel, /*!< Device's hub level */
kUSB_HostGetHostHandle, /*!< Device's host handle */
kUSB_HostGetDeviceControlPipe, /*!< Device's control pipe handle */
kUSB_HostGetDevicePID, /*!< Device's PID */
kUSB_HostGetDeviceVID, /*!< Device's VID */
kUSB_HostGetHubThinkTime, /*!< Device's hub total think time */
kUSB_HostGetDeviceConfigIndex, /*!< Device's running zero-based config index */
kUSB_HostGetConfigurationDes, /*!< Device's configuration descriptor pointer */
kUSB_HostGetConfigurationLength, /*!< Device's configuration descriptor pointer */
} usb_host_dev_info_t;
/*!
* @brief Host callback function typedef.
*
* This callback function is used to notify application device attach/detach event.
* This callback pointer is passed when initializing the host.
*
* @param deviceHandle The device handle, which indicates the attached device.
* @param configurationHandle The configuration handle contains the attached device's configuration information.
* @param event_code The callback event code; See the enumeration host_event_t.
*
* @return A USB error code or kStatus_USB_Success.
* @retval kStatus_USB_Success Application handles the attached device successfully.
* @retval kStatus_USB_NotSupported Application don't support the attached device.
* @retval kStatus_USB_Error Application handles the attached device falsely.
*/
typedef usb_status_t (*host_callback_t)(usb_device_handle deviceHandle,
usb_host_configuration_handle configurationHandle,
uint32_t eventCode);
/*!
* @brief Transfer callback function typedef.
*
* This callback function is used to notify the upper layer the result of the transfer.
* This callback pointer is passed when calling the send/receive APIs.
*
* @param param The parameter pointer, which is passed when calling the send/receive APIs.
* @param data The data buffer pointer.
* @param data_len The result data length.
* @param status A USB error code or kStatus_USB_Success.
*/
typedef void (*transfer_callback_t)(void *param, uint8_t *data, uint32_t dataLen, usb_status_t status);
/*!
* @brief Host stack inner transfer callback function typedef.
*
* This callback function is used to notify the upper layer the result of a transfer.
* This callback pointer is passed when initializing the structure usb_host_transfer_t.
*
* @param param The parameter pointer, which is passed when calling the send/receive APIs.
* @param transfer The transfer information; See the structure usb_host_transfer_t.
* @param status A USB error code or kStatus_USB_Success.
*/
typedef void (*host_inner_transfer_callback_t)(void *param, struct _usb_host_transfer *transfer, usb_status_t status);
/*! @brief USB host endpoint information structure */
typedef struct _usb_host_ep
{
usb_descriptor_endpoint_t *epDesc; /*!< Endpoint descriptor pointer*/
uint8_t *epExtension; /*!< Endpoint extended descriptor pointer*/
uint16_t epExtensionLength; /*!< Extended descriptor length*/
} usb_host_ep_t;
/*! @brief USB host interface information structure */
typedef struct _usb_host_interface
{
usb_host_ep_t epList[USB_HOST_CONFIG_INTERFACE_MAX_EP]; /*!< Endpoint array*/
usb_descriptor_interface_t *interfaceDesc; /*!< Interface descriptor pointer*/
uint8_t *interfaceExtension; /*!< Interface extended descriptor pointer*/
uint16_t interfaceExtensionLength; /*!< Extended descriptor length*/
uint8_t interfaceIndex; /*!< The interface index*/
uint8_t alternateSettingNumber; /*!< The interface alternate setting value*/
uint8_t epCount; /*!< Interface's endpoint number*/
} usb_host_interface_t;
/*! @brief USB host configuration information structure */
typedef struct _usb_host_configuration
{
usb_host_interface_t interfaceList[USB_HOST_CONFIG_CONFIGURATION_MAX_INTERFACE]; /*!< Interface array*/
usb_descriptor_configuration_t *configurationDesc; /*!< Configuration descriptor pointer*/
uint8_t *configurationExtension; /*!< Configuration extended descriptor pointer*/
uint16_t configurationExtensionLength; /*!< Extended descriptor length*/
uint8_t interfaceCount; /*!< The configuration's interface number*/
} usb_host_configuration_t;
/*! @brief USB host pipe common structure */
typedef struct _usb_host_pipe
{
struct _usb_host_pipe *next; /*!< Link the idle pipes*/
usb_device_handle deviceHandle; /*!< This pipe's device's handle*/
uint16_t currentCount; /*!< For KHCI transfer*/
uint16_t nakCount; /*!< Maximum NAK count*/
uint16_t maxPacketSize; /*!< Maximum packet size*/
uint16_t interval; /*!< FS/LS: frame unit; HS: micro-frame unit*/
uint8_t open; /*!< 0 - closed, 1 - open*/
uint8_t nextdata01; /*!< Data toggle*/
uint8_t endpointAddress; /*!< Endpoint address*/
uint8_t direction; /*!< Pipe direction*/
uint8_t pipeType; /*!< Pipe type, for example USB_ENDPOINT_BULK*/
uint8_t numberPerUframe; /*!< Transaction number per micro-frame*/
} usb_host_pipe_t;
/*! @brief USB host transfer structure */
typedef struct _usb_host_transfer
{
struct _usb_host_transfer *next; /*!< The next transfer structure*/
uint8_t *transferBuffer; /*!< Transfer data buffer*/
uint32_t transferLength; /*!< Transfer data length*/
uint32_t transferSofar; /*!< Length transferred so far*/
host_inner_transfer_callback_t callbackFn; /*!< Transfer callback function*/
void *callbackParam; /*!< Transfer callback parameter*/
usb_host_pipe_t *transferPipe; /*!< Transfer pipe pointer*/
usb_setup_struct_t *setupPacket; /*!< Set up packet buffer*/
uint8_t direction; /*!< Transfer direction; it's values are USB_OUT or USB_IN*/
uint8_t setupStatus; /*!< Set up the transfer status*/
union
{
uint32_t unitHead; /*!< xTD head for this transfer*/
int32_t transferResult; /*!< KHCI transfer result */
} union1;
union
{
uint32_t unitTail; /*!<xTD tail for this transfer*/
uint32_t frame; /*!< KHCI transfer frame number */
} union2;
#if USB_HOST_CONFIG_KHCI
uint16_t nakTimeout; /*!< KHCI transfer NAK timeout */
uint16_t retry; /*!< KHCI transfer retry */
#endif
} usb_host_transfer_t;
/*! @brief USB host pipe information structure for opening pipe */
typedef struct _usb_host_pipe_init
{
void *devInstance; /*!< Device instance handle*/
uint16_t nakCount; /*!< Maximum NAK retry count. MUST be zero for interrupt*/
uint16_t maxPacketSize; /*!< Pipe's maximum packet size*/
uint8_t interval; /*!< Pipe's interval*/
uint8_t endpointAddress; /*!< Endpoint address*/
uint8_t direction; /*!< Endpoint direction*/
uint8_t pipeType; /*!< Endpoint type, the value is USB_ENDPOINT_INTERRUPT, USB_ENDPOINT_CONTROL,
USB_ENDPOINT_ISOCHRONOUS, USB_ENDPOINT_BULK*/
uint8_t numberPerUframe; /*!< Transaction number for each micro-frame*/
} usb_host_pipe_init_t;
/*! @brief Cancel transfer parameter structure */
typedef struct _usb_host_cancel_param
{
usb_host_pipe_handle pipeHandle; /*!< Cancelling pipe handle*/
usb_host_transfer_t *transfer; /*!< Cancelling transfer*/
} usb_host_cancel_param_t;
/*******************************************************************************
* API
******************************************************************************/
#ifdef __cplusplus
extern "C" {
#endif
/*!
* @name USB host APIs Part 1
* The following APIs are recommended for application use.
* @{
*/
/*!
* @brief Initializes the USB host stack.
*
* This function initializes the USB host module specified by the controllerId.
*
* @param[in] controllerId The controller ID of the USB IP. See the enumeration usb_controller_index_t.
* @param[out] hostHandle Returns the host handle.
* @param[in] callbackFn Host callback function notifies device attach/detach.
*
* @retval kStatus_USB_Success The host is initialized successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle is a NULL pointer.
* @retval kStatus_USB_ControllerNotFound Cannot find the controller according to the controller ID.
* @retval kStatus_USB_AllocFail Allocation memory fail.
* @retval kStatus_USB_Error Host mutex create fail; KHCI/EHCI mutex or KHCI/EHCI event create fail,
* or, KHCI/EHCI IP initialize fail.
*/
extern usb_status_t USB_HostInit(uint8_t controllerId, usb_host_handle *hostHandle, host_callback_t callbackFn);
/*!
* @brief Deinitializes the USB host stack.
*
* This function deinitializes the USB host module specified by the hostHandle.
*
* @param[in] hostHandle The host handle.
*
* @retval kStatus_USB_Success The host is initialized successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle is a NULL pointer.
* @retval kStatus_USB_Error Controller deinitialization fail.
*/
extern usb_status_t USB_HostDeinit(usb_host_handle hostHandle);
/*!
* @brief Gets the device information.
*
* This function gets the device information.
*
* @param[in] deviceHandle Removing device handle.
* @param[in] infoCode See the enumeration host_dev_info_t.
* @param[out] infoValue Return the information value.
*
* @retval kStatus_USB_Success Close successfully.
* @retval kStatus_USB_InvalidParameter The deviceHandle or info_value is a NULL pointer.
* @retval kStatus_USB_Error The info_code is not the host_dev_info_t value.
*/
extern usb_status_t USB_HostHelperGetPeripheralInformation(usb_device_handle deviceHandle,
uint32_t infoCode,
uint32_t *infoValue);
/*!
* @brief Parses the alternate interface descriptor.
*
* This function parses the alternate interface descriptor and returns an interface information through the structure
* usb_host_interface_t.
*
* @param[in] interfaceHandle The whole interface handle.
* @param[in] alternateSetting Alternate setting value.
* @param[out] interface Return interface information.
*
* @retval kStatus_USB_Success Close successfully.
* @retval kStatus_USB_InvalidHandle The interfaceHandle is a NULL pointer.
* @retval kStatus_USB_InvalidParameter The alternateSetting is 0.
* @retval kStatus_USB_Error The interface descriptor is wrong.
*/
extern usb_status_t USB_HostHelperParseAlternateSetting(usb_host_interface_handle interfaceHandle,
uint8_t alternateSetting,
usb_host_interface_t *interface);
/*!
* @brief Removes the attached device.
*
* This function removes the attached device.
* This function should not be used all the time.
*
* @param[in] hostHandle The host handle.
* @param[in] deviceHandle Removing device handle.
*
* @retval kStatus_USB_Success Remove successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle or deviceHandle is a NULL pointer.
* @retval kStatus_USB_InvalidParameter The deviceHandle instance don't belong to hostHandle instance.
*/
extern usb_status_t USB_HostRemoveDevice(usb_host_handle hostHandle, usb_device_handle deviceHandle);
/*!
* @brief KHCI task function.
*
* The function is used to handle the KHCI controller message.
* In the bare metal environment, this function should be called periodically in the main function.
* In the RTOS environment, this function should be used as a function entry to create a task.
*
* @param[in] hostHandle The host handle.
*/
extern void USB_HostKhciTaskFunction(void *hostHandle);
/*!
* @brief EHCI task function.
*
* The function is used to handle the EHCI controller message.
* In the bare metal environment, this function should be called periodically in the main function.
* In the RTOS environment, this function should be used as a function entry to create a task.
*
* @param[in] hostHandle The host handle.
*/
extern void USB_HostEhciTaskFunction(void *hostHandle);
/*!
* @brief OHCI task function.
*
* The function is used to handle the OHCI controller message.
* In the bare metal environment, this function should be called periodically in the main function.
* In the RTOS environment, this function should be used as a function entry to create a task.
*
* @param[in] hostHandle The host handle.
*/
extern void USB_HostOhciTaskFunction(void *hostHandle);
/*!
* @brief IP3516HS task function.
*
* The function is used to handle the IP3516HS controller message.
* In the bare metal environment, this function should be called periodically in the main function.
* In the RTOS environment, this function should be used as a function entry to create a task.
*
* @param[in] hostHandle The host handle.
*/
extern void USB_HostIp3516HsTaskFunction(void *hostHandle);
/*!
* @brief Device KHCI ISR function.
*
* The function is the KHCI interrupt service routine.
*
* @param[in] hostHandle The host handle.
*/
extern void USB_HostKhciIsrFunction(void *hostHandle);
/*!
* @brief Device EHCI ISR function.
*
* The function is the EHCI interrupt service routine.
*
* @param[in] hostHandle The host handle.
*/
extern void USB_HostEhciIsrFunction(void *hostHandle);
/*!
* @brief Device OHCI ISR function.
*
* The function is the OHCI interrupt service routine.
*
* @param[in] hostHandle The host handle.
*/
extern void USB_HostOhciIsrFunction(void *hostHandle);
/*!
* @brief Device IP3516HS ISR function.
*
* The function is the IP3516HS interrupt service routine.
*
* @param[in] hostHandle The host handle.
*/
extern void USB_HostIp3516HsIsrFunction(void *hostHandle);
/*! @}*/
/*!
* @name USB host APIs Part 2.
* The following APIs are not recommended for application use. They are mainly used in the class driver.
* @{
*/
/*!
* @brief Opens the USB host pipe.
*
* This function opens a pipe according to the pipe_init_ptr parameter.
*
* @param[in] hostHandle The host handle.
* @param[out] pipeHandle The pipe handle pointer used to return the pipe handle.
* @param[in] pipeInit Used to initialize the pipe.
*
* @retval kStatus_USB_Success The host is initialized successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle or pipe_handle_ptr is a NULL pointer.
* @retval kStatus_USB_Error There is no idle pipe.
* Or, there is no idle QH for EHCI.
* Or, bandwidth allocate fail for EHCI.
*/
extern usb_status_t USB_HostOpenPipe(usb_host_handle hostHandle,
usb_host_pipe_handle *pipeHandle,
usb_host_pipe_init_t *pipeInit);
/*!
* @brief Closes the USB host pipe.
*
* This function closes a pipe and frees the related resources.
*
* @param[in] hostHandle The host handle.
* @param[in] pipeHandle The closing pipe handle.
*
* @retval kStatus_USB_Success The host is initialized successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle or pipeHandle is a NULL pointer.
*/
extern usb_status_t USB_HostClosePipe(usb_host_handle hostHandle, usb_host_pipe_handle pipeHandle);
/*!
* @brief Sends data to a pipe.
*
* This function requests to send the transfer to the specified pipe.
*
* @param[in] hostHandle The host handle.
* @param[in] pipeHandle The sending pipe handle.
* @param[in] transfer The transfer information.
*
* @retval kStatus_USB_Success Send successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle, pipeHandle or transfer is a NULL pointer.
* @retval kStatus_USB_LackSwapBuffer There is no swap buffer for KHCI.
* @retval kStatus_USB_Error There is no idle QTD/ITD/SITD for EHCI.
*/
extern usb_status_t USB_HostSend(usb_host_handle hostHandle,
usb_host_pipe_handle pipeHandle,
usb_host_transfer_t *transfer);
/*!
* @brief Sends a setup transfer to the pipe.
*
* This function request to send the setup transfer to the specified pipe.
*
* @param[in] hostHandle The host handle.
* @param[in] pipeHandle The sending pipe handle.
* @param[in] transfer The transfer information.
*
* @retval kStatus_USB_Success Send successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle, pipeHandle or transfer is a NULL pointer.
* @retval kStatus_USB_LackSwapBuffer There is no swap buffer for KHCI.
* @retval kStatus_USB_Error There is no idle QTD/ITD/SITD for EHCI.
*/
extern usb_status_t USB_HostSendSetup(usb_host_handle hostHandle,
usb_host_pipe_handle pipeHandle,
usb_host_transfer_t *transfer);
/*!
* @brief Receives the data from the pipe.
*
* This function requests to receive the transfer from the specified pipe.
*
* @param[in] hostHandle The host handle.
* @param[in] pipeHandle The receiving pipe handle.
* @param[in] transfer The transfer information.
*
* @retval kStatus_USB_Success Receive successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle, pipeHandle or transfer is a NULL pointer.
* @retval kStatus_USB_LackSwapBuffer There is no swap buffer for KHCI.
* @retval kStatus_USB_Error There is no idle QTD/ITD/SITD for EHCI.
*/
extern usb_status_t USB_HostRecv(usb_host_handle hostHandle,
usb_host_pipe_handle pipeHandle,
usb_host_transfer_t *transfer);
/*!
* @brief Cancel the pipe's transfers.
*
* This function cancels all pipe's transfers when the parameter transfer is NULL or cancels the transfers altogether.
*
* @param[in] hostHandle The host handle.
* @param[in] pipeHandle The receiving pipe handle.
* @param[in] transfer The transfer information.
*
* @retval kStatus_USB_Success Cancel successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle or pipeHandle is a NULL pointer.
*/
extern usb_status_t USB_HostCancelTransfer(usb_host_handle hostHandle,
usb_host_pipe_handle pipeHandle,
usb_host_transfer_t *transfer);
/*!
* @brief Allocates a transfer resource.
*
* This function allocates a transfer. This transfer is used to pass data information to a low level stack.
*
* @param[in] hostHandle The host handle.
* @param[out] transfer Return the transfer.
*
* @retval kStatus_USB_Success Allocate successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle or transfer is a NULL pointer.
* @retval kStatus_USB_Error There is no idle transfer.
*/
extern usb_status_t USB_HostMallocTransfer(usb_host_handle hostHandle, usb_host_transfer_t **transfer);
/*!
* @brief Frees a transfer resource.
*
* This function frees a transfer. This transfer is used to pass data information to a low level stack.
*
* @param[in] hostHandle The host handle.
* @param[in] transfer Release the transfer.
*
* @retval kStatus_USB_Success Free successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle or transfer is a NULL pointer.
*/
extern usb_status_t USB_HostFreeTransfer(usb_host_handle hostHandle, usb_host_transfer_t *transfer);
/*!
* @brief Requests the USB standard request.
*
* This function sends the USB standard request packet.
*
* @param[in] deviceHandle The device handle for control transfer.
* @param[in] usbRequest A USB standard request code. Se the usb_spec.h.
* @param[in] transfer The used transfer.
* @param[in] param The parameter structure is different for different request, see
* usb_host_framework.h.
*
* @retval kStatus_USB_Success Send successfully.
* @retval kStatus_USB_InvalidHandle The deviceHandle is a NULL pointer.
* @retval kStatus_USB_LackSwapBuffer There is no swap buffer for KHCI.
* @retval kStatus_USB_Error There is no idle QTD/ITD/SITD for EHCI,
* Or, the request is not standard request.
*/
extern usb_status_t USB_HostRequestControl(usb_device_handle deviceHandle,
uint8_t usbRequest,
usb_host_transfer_t *transfer,
void *param);
/*!
* @brief Opens the interface.
*
* This function opens the interface. It is used to notify the host driver the interface is used by APP or class driver.
*
* @param[in] deviceHandle Removing device handle.
* @param[in] interfaceHandle Opening interface handle.
*
* @retval kStatus_USB_Success Open successfully.
* @retval kStatus_USB_InvalidHandle The deviceHandle or interfaceHandle is a NULL pointer.
*/
extern usb_status_t USB_HostOpenDeviceInterface(usb_device_handle deviceHandle,
usb_host_interface_handle interfaceHandle);
/*!
* @brief Closes an interface.
*
* This function opens an interface. It is used to notify the host driver the interface is not used by APP or class
* driver.
*
* @param[in] deviceHandle Removing device handle.
* @param[in] interfaceHandle Opening interface handle.
*
* @retval kStatus_USB_Success Close successfully.
* @retval kStatus_USB_InvalidHandle The deviceHandle is a NULL pointer.
*/
extern usb_status_t USB_HostCloseDeviceInterface(usb_device_handle deviceHandle,
usb_host_interface_handle interfaceHandle);
/*!
* @brief Gets a host stack version function.
*
* The function is used to get the host stack version.
*
* @param[out] version The version structure pointer to keep the host stack version.
*
*/
extern void USB_HostGetVersion(uint32_t *version);
#if ((defined(USB_HOST_CONFIG_LOW_POWER_MODE)) && (USB_HOST_CONFIG_LOW_POWER_MODE > 0U))
/*!
* @brief Send a bus or device suspend request.
*
* This function is used to send a bus or device suspend request.
*
* @param[in] hostHandle The host handle.
* @param[in] deviceHandle The device handle.
*
* @retval kStatus_USB_Success Request successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle is a NULL pointer. Or the controller handle is invalid.
* @retval kStatus_USB_Error There is no idle transfer.
* Or, the deviceHandle is invalid.
* Or, the request is invalid.
*/
extern usb_status_t USB_HostSuspendDeviceResquest(usb_host_handle hostHandle, usb_device_handle deviceHandle);
/*!
* @brief Send a bus or device resume request.
*
* This function is used to send a bus or device resume request.
*
* @param[in] hostHandle The host handle.
* @param[in] deviceHandle The device handle.
*
* @retval kStatus_USB_Success Request successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle is a NULL pointer. Or the controller handle is invalid.
* @retval kStatus_USB_Error There is no idle transfer.
* Or, the deviceHandle is invalid.
* Or, the request is invalid.
*/
extern usb_status_t USB_HostResumeDeviceResquest(usb_host_handle hostHandle, usb_device_handle deviceHandle);
#if ((defined(USB_HOST_CONFIG_LPM_L1)) && (USB_HOST_CONFIG_LPM_L1 > 0U))
/*!
* @brief Send a bus or device suspend request.
*
* This function is used to send a bus or device suspend request.
*
* @param[in] hostHandle The host handle.
* @param[in] deviceHandle The device handle.
*@param[in] sleeptype Bus suspend or single device suspend.
*
* @retval kStatus_USB_Success Request successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle is a NULL pointer. Or the controller handle is invalid.
* @retval kStatus_USB_Error There is no idle transfer.
* Or, the deviceHandle is invalid.
* Or, the request is invalid.
*/
extern usb_status_t USB_HostL1SleepDeviceResquest(usb_host_handle hostHandle,
usb_device_handle deviceHandle,
uint8_t sleeptype);
/*!
* @brief Send a bus or device resume request.
*
* This function is used to send a bus or device resume request.
*
* @param[in] hostHandle The host handle.
* @param[in] deviceHandle The device handle.
* *@param[in] sleeptype Bus suspend or single device suspend.
*
* @retval kStatus_USB_Success Request successfully.
* @retval kStatus_USB_InvalidHandle The hostHandle is a NULL pointer. Or the controller handle is invalid.
* @retval kStatus_USB_Error There is no idle transfer.
* Or, the deviceHandle is invalid.
* Or, the request is invalid.
*/
extern usb_status_t USB_HostL1ResumeDeviceResquest(usb_host_handle hostHandle,
usb_device_handle deviceHandle,
uint8_t sleepType);
/*!
* @brief Update the lpm param.
*
* The function is used to configuure the lpm token.
*
* @param[in] hostHandle The host handle.
* @param[in] lpmParam HIRD vaule and whether enable remotewakeup.
*
*/
extern usb_status_t USB_HostL1SleepDeviceResquestConfig(usb_host_handle hostHandle, uint8_t *lpmParam);
#endif
/*!
* @brief Update the hardware tick.
*
* The function is used to update the hardware tick.
*
* @param[in] hostHandle The host handle.
* @param[in] tick Current hardware tick(uint is ms).
*
*/
extern usb_status_t USB_HostUpdateHwTick(usb_host_handle hostHandle, uint64_t tick);
#endif
/*! @}*/
#ifdef __cplusplus
}
#endif
/*! @}*/
#endif /* _USB_HOST_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,178 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _USB_HOST_DEV_MNG_H_
#define _USB_HOST_DEV_MNG_H_
#include "usb_host.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*!
* @addtogroup usb_host_drv
* @{
*/
/*! @brief States of device instances enumeration */
typedef enum _usb_host_device_enumeration_status
{
kStatus_DEV_Notinit = 0, /*!< Device is invalid */
kStatus_DEV_Initial, /*!< Device has been processed by host driver */
kStatus_DEV_GetDes8, /*!< Enumeration process: get 8 bytes' device descriptor */
kStatus_DEV_SetAddress, /*!< Enumeration process: set device address */
kStatus_DEV_GetDes, /*!< Enumeration process: get device descriptor */
kStatus_DEV_GetCfg9, /*!< Enumeration process: get 9 bytes' configuration descriptor */
kStatus_DEV_GetCfg, /*!< Enumeration process: get configuration descriptor */
kStatus_DEV_SetCfg, /*!< Enumeration process: set configuration */
kStatus_DEV_EnumDone, /*!< Enumeration is done */
kStatus_DEV_AppUsed, /*!< This device has been used by application */
} usb_host_device_enumeration_status_t;
/*! @brief States of device's interface */
typedef enum _usb_host_interface_state
{
kStatus_interface_Attached = 1, /*!< Interface's default status */
kStatus_interface_Opened, /*!< Interface is used by application */
kStatus_interface_Detached, /*!< Interface is not used by application */
} usb_host_interface_state_t;
/*! @brief States of device */
typedef enum _usb_host_device_state
{
kStatus_device_Detached = 0, /*!< Device is used by application */
kStatus_device_Attached, /*!< Device's default status */
} usb_host_device_state_t;
/*! @brief Device instance */
typedef struct _usb_host_device_instance
{
struct _usb_host_device_instance *next; /*!< Next device, or NULL */
usb_host_handle hostHandle; /*!< Host handle */
usb_host_configuration_t configuration; /*!< Parsed configuration information for the device */
usb_descriptor_device_t *deviceDescriptor; /*!< Standard device descriptor */
usb_host_pipe_handle controlPipe; /*!< Device's control pipe */
uint8_t *configurationDesc; /*!< Configuration descriptor pointer */
uint16_t configurationLen; /*!< Configuration descriptor length */
uint16_t configurationValue; /*!< Configuration index */
uint8_t interfaceStatus[USB_HOST_CONFIG_CONFIGURATION_MAX_INTERFACE]; /*!< Interfaces' status, please reference to
#usb_host_interface_state_t */
uint8_t *enumBuffer; /*!< Buffer for enumeration */
uint8_t state; /*!< Device state for enumeration */
uint8_t enumRetries; /*!< Re-enumeration when error in control transfer */
uint8_t stallRetries; /*!< Re-transfer when stall */
uint8_t speed; /*!< Device speed */
uint8_t allocatedAddress; /*!< Temporary address for the device. When set address request succeeds, setAddress is
a value, 1 - 127 */
uint8_t setAddress; /*!< The address has been set to the device successfully, 1 - 127 */
uint8_t deviceAttachState; /*!< See the usb_host_device_state_t */
#if ((defined USB_HOST_CONFIG_HUB) && (USB_HOST_CONFIG_HUB))
/* hub related */
uint8_t hubNumber; /*!< Device's first connected hub address (root hub = 0) */
uint8_t portNumber; /*!< Device's first connected hub's port no (1 - 8) */
uint8_t hsHubNumber; /*!< Device's first connected high-speed hub's address (1 - 8) */
uint8_t hsHubPort; /*!< Device's first connected high-speed hub's port no (1 - 8) */
uint8_t level; /*!< Device's level (root device = 0) */
#endif
} usb_host_device_instance_t;
typedef struct _usb_host_enum_process_entry
{
uint8_t successState; /*!< When the last step is successful, the next state value */
uint8_t retryState; /*!< When the last step need retry, the next state value */
usb_status_t (*process)(usb_host_device_instance_t *deviceInstance); /*!< When the last step transfer is done, the
function is used to process the transfer
data */
} usb_host_enum_process_entry_t;
/*******************************************************************************
* API
******************************************************************************/
/*!
* @brief Calls this function when device attach.
*
* @param hostHandle Host instance handle.
* @param speed Device speed.
* @param hubNumber Device hub no. root device's hub no. is 0.
* @param portNumber Device port no. root device's port no. is 0.
* @param level Device level. root device's level is 1.
* @param deviceHandle Return device handle.
*
* @return kStatus_USB_Success or error codes.
*/
extern usb_status_t USB_HostAttachDevice(usb_host_handle hostHandle,
uint8_t speed,
uint8_t hubNumber,
uint8_t portNumber,
uint8_t level,
usb_device_handle *deviceHandle);
/*!
* @brief Call this function when device detaches.
*
* @param hostHandle Host instance handle.
* @param hubNumber Device hub no. root device's hub no. is 0.
* @param portNumber Device port no. root device's port no. is 0.
*
* @return kStatus_USB_Success or error codes.
*/
extern usb_status_t USB_HostDetachDevice(usb_host_handle hostHandle, uint8_t hubNumber, uint8_t portNumber);
/*!
* @brief Call this function when device detaches.
*
* @param hostHandle Host instance handle.
* @param deviceHandle Device handle.
*
* @return kStatus_USB_Success or error codes.
*/
extern usb_status_t USB_HostDetachDeviceInternal(usb_host_handle hostHandle, usb_device_handle deviceHandle);
/*!
* @brief Gets the device attach/detach state.
*
* @param deviceHandle Device handle.
*
* @return 0x01 - attached; 0x00 - detached.
*/
extern uint8_t USB_HostGetDeviceAttachState(usb_device_handle deviceHandle);
/*!
* @brief Determine whether the device is attached.
*
* @param hostHandle Host instance pointer.
* @param deviceHandle Device handle.
*
* @return kStatus_USB_Success or error codes.
*/
extern usb_status_t USB_HostValidateDevice(usb_host_handle hostHandle, usb_device_handle deviceHandle);
/*! @}*/
#endif /* _USB_HOST_DEV_MNG_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,499 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _USB_HOST_CONTROLLER_EHCI_H_
#define _USB_HOST_CONTROLLER_EHCI_H_
/*******************************************************************************
* KHCI private public structures, enumerations, macros, functions
******************************************************************************/
/*******************************************************************************
* Definitions
******************************************************************************/
/* EHCI host macros */
#define EHCI_HOST_T_INVALID_VALUE (1U)
#define EHCI_HOST_POINTER_TYPE_ITD (0x00U)
#define EHCI_HOST_POINTER_TYPE_QH (0x00000002U)
#define EHCI_HOST_POINTER_TYPE_SITD (0x00000004U)
#define EHCI_HOST_POINTER_TYPE_FSTN (0x00000006U)
#define EHCI_HOST_POINTER_TYPE_MASK (0x00000006U)
#define EHCI_HOST_POINTER_ADDRESS_MASK (0xFFFFFFE0U)
#define EHCI_HOST_PID_OUT (0U)
#define EHCI_HOST_PID_IN (1U)
#define EHCI_HOST_PID_SETUP (2U)
#define EHCI_HOST_QH_RL_SHIFT (28U)
#define EHCI_HOST_QH_RL_MASK (0xF0000000U)
#define EHCI_HOST_QH_C_SHIFT (27U)
#define EHCI_HOST_QH_MAX_PACKET_LENGTH_SHIFT (16U)
#define EHCI_HOST_QH_MAX_PACKET_LENGTH_MASK (0x07FF0000U)
#define EHCI_HOST_QH_H_SHIFT (15U)
#define EHCI_HOST_QH_DTC_SHIFT (14U)
#define EHCI_HOST_QH_EPS_SHIFT (12U)
#define EHCI_HOST_QH_ENDPT_SHIFT (8U)
#define EHCI_HOST_QH_I_SHIFT (7U)
#define EHCI_HOST_QH_DEVICE_ADDRESS_SHIFT (0U)
#define EHCI_HOST_QH_MULT_SHIFT (30U)
#define EHCI_HOST_QH_PORT_NUMBER_SHIFT (23U)
#define EHCI_HOST_QH_HUB_ADDR_SHIFT (16U)
#define EHCI_HOST_QH_UFRAME_CMASK_SHIFT (8U)
#define EHCI_HOST_QH_UFRAME_SMASK_SHIFT (0U)
#define EHCI_HOST_QH_STATUS_ERROR_MASK (0x0000007EU)
#define EHCI_HOST_QH_STATUS_NOSTALL_ERROR_MASK (0x0000003EU)
#define EHCI_HOST_QTD_DT_SHIFT (31U)
#define EHCI_HOST_QTD_DT_MASK (0x80000000U)
#define EHCI_HOST_QTD_TOTAL_BYTES_SHIFT (16U)
#define EHCI_HOST_QTD_TOTAL_BYTES_MASK (0x7FFF0000U)
#define EHCI_HOST_QTD_IOC_MASK (0x00008000U)
#define EHCI_HOST_QTD_C_PAGE_SHIFT (12U)
#define EHCI_HOST_QTD_CERR_SHIFT (10U)
#define EHCI_HOST_QTD_CERR_MAX_VALUE (0x00000003U)
#define EHCI_HOST_QTD_PID_CODE_SHIFT (8U)
#define EHCI_HOST_QTD_STATUS_SHIFT (0U)
#define EHCI_HOST_QTD_CURRENT_OFFSET_MASK (0x00000FFFU)
#define EHCI_HOST_QTD_BUFFER_POINTER_SHIFT (12U)
#define EHCI_HOST_QTD_STATUS_ACTIVE_MASK (0x00000080U)
#define EHCI_HOST_QTD_STATUS_MASK (0x000000ffU)
#define EHCI_HOST_QTD_STATUS_ERROR_MASK (0x0000007EU)
#define EHCI_HOST_QTD_STATUS_STALL_ERROR_MASK (0x00000040U)
#define EHCI_HOST_ITD_STATUS_ACTIVE_MASK (0x80000000U)
#define EHCI_HOST_ITD_TRANSACTION_LEN_SHIFT (16U)
#define EHCI_HOST_ITD_TRANSACTION_LEN_MASK (0x0FFF0000U)
#define EHCI_HOST_ITD_IOC_SHIFT (15U)
#define EHCI_HOST_ITD_PG_SHIFT (12U)
#define EHCI_HOST_ITD_TRANSACTION_OFFSET_SHIFT (0U)
#define EHCI_HOST_ITD_TRANSACTION_OFFSET_MASK (0x00000FFFU)
#define EHCI_HOST_ITD_BUFFER_POINTER_SHIFT (12U)
#define EHCI_HOST_ITD_ENDPT_SHIFT (8U)
#define EHCI_HOST_ITD_DEVICE_ADDRESS_SHIFT (0U)
#define EHCI_HOST_ITD_MAX_PACKET_SIZE_SHIFT (0U)
#define EHCI_HOST_ITD_MULT_SHIFT (0U)
#define EHCI_HOST_ITD_DIRECTION_SHIFT (11U)
#define EHCI_HOST_SITD_STATUS_ACTIVE_MASK (0x00000080U)
#define EHCI_HOST_SITD_DIRECTION_SHIFT (31U)
#define EHCI_HOST_SITD_PORT_NUMBER_SHIFT (24U)
#define EHCI_HOST_SITD_HUB_ADDR_SHIFT (16U)
#define EHCI_HOST_SITD_ENDPT_SHIFT (8U)
#define EHCI_HOST_SITD_DEVICE_ADDRESS_SHIFT (0U)
#define EHCI_HOST_SITD_CMASK_SHIFT (8U)
#define EHCI_HOST_SITD_SMASK_SHIFT (0U)
#define EHCI_HOST_SITD_TOTAL_BYTES_SHIFT (16U)
#define EHCI_HOST_SITD_TOTAL_BYTES_MASK (0x03FF0000U)
#define EHCI_HOST_SITD_TP_SHIFT (3U)
#define EHCI_HOST_SITD_TCOUNT_SHIFT (0U)
#define EHCI_HOST_SITD_IOC_SHIFT (31U)
/* register related MACROs */
#define EHCI_PORTSC1_W1_BITS (0x0000002AU)
#define EHCI_MAX_UFRAME_VALUE (0x00003FFFU)
/* task event */
#define EHCI_TASK_EVENT_DEVICE_ATTACH (0x01U)
#define EHCI_TASK_EVENT_TRANSACTION_DONE (0x02U)
#define EHCI_TASK_EVENT_DEVICE_DETACH (0x04U)
#define EHCI_TASK_EVENT_PORT_CHANGE (0x08U)
#define EHCI_TASK_EVENT_TIMER0 (0x10U)
#define EHCI_TASK_EVENT_TIMER1 (0x20U)
#define USB_HostEhciLock() USB_OsaMutexLock(ehciInstance->ehciMutex)
#define USB_HostEhciUnlock() USB_OsaMutexUnlock(ehciInstance->ehciMutex)
/*******************************************************************************
* KHCI driver public structures, enumerations, macros, functions
******************************************************************************/
/*!
* @addtogroup usb_host_controller_ehci
* @{
*/
/*! @brief The maximum supported ISO pipe number */
#define USB_HOST_EHCI_ISO_NUMBER USB_HOST_CONFIG_EHCI_MAX_ITD
/*! @brief Check the port connect state delay if the state is unstable */
#define USB_HOST_EHCI_PORT_CONNECT_DEBOUNCE_DELAY (101U)
/*! @brief Delay for port reset */
#define USB_HOST_EHCI_PORT_RESET_DELAY (11U)
/*! @brief The SITD inserts a frame interval for putting more SITD continuously.
* There is an interval when an application sends two FS/LS ISO transfers.
* When the interval is less than the macro, the two transfers are continuous in the frame list. Otherwise, the two
* transfers
* are not continuous.
* For example:
* - Use case 1: when inserting the SITD first, the inserted frame = the current frame value + this MACRO value.
* - Use case 2: when inserting SITD is not first, choose between the last inserted frame value and the
* current frame value according to the following criteria:
* If the interval is less than the MACRO value, the new SITD is continuous with the last SITD.
* If not, the new SITD inserting frame = the current frame value + this MACRO value.
*/
#define USB_HOST_EHCI_ISO_BOUNCE_FRAME_NUMBER (2U)
/*! @brief The ITD inserts a micro-frame interval for putting more ITD continuously.
* There is an interval when an application sends two HS ISO transfers.
* When the interval is less than the macro, the two transfers are continuous in the frame list. Otherwise, the two
* transfers
* are not continuous.
* For example:
* - Use case 1: when inserting ITD first, the inserted micro-frame = the current micro-frame value + this MACRO value.
* - Use case 2: when inserting ITD is not first, choose between the last inserted micro-frame value and the
* current micro-frame value according to the following criteria:
* If the interval is less than this MACRO value, the new ITD is continuous with the last ITD.
* If not, the new ITD inserting micro-frame = the current micro-frame value + this MACRO value.
*/
#define USB_HOST_EHCI_ISO_BOUNCE_UFRAME_NUMBER (16U)
/*! @brief Control or bulk transaction timeout value (unit: 100 ms) */
#define USB_HOST_EHCI_CONTROL_BULK_TIME_OUT_VALUE (20U)
#if ((defined(USB_HOST_CONFIG_LOW_POWER_MODE)) && (USB_HOST_CONFIG_LOW_POWER_MODE > 0U))
typedef enum _bus_ehci_suspend_request_state
{
kBus_EhciIdle = 0U,
kBus_EhciStartSuspend,
kBus_EhciSuspended,
kBus_EhciStartResume,
} bus_ehci_suspend_request_state_t;
#endif
/*! @brief EHCI state for device attachment/detachment. */
typedef enum _host_ehci_device_state_
{
kEHCIDevicePhyAttached = 1, /*!< Device is physically attached */
kEHCIDeviceAttached, /*!< Device is attached and initialized */
kEHCIDeviceDetached, /*!< Device is detached and de-initialized */
} host_ehci_device_state_t;
/*! @brief EHCI pipe structure */
typedef struct _usb_host_ehci_pipe
{
usb_host_pipe_t pipeCommon; /*!< Common pipe information */
void *ehciQh; /*!< Control/bulk/interrupt: QH; ISO: usb_host_ehci_iso_t*/
/* bandwidth */
uint16_t uframeInterval; /*!< Micro-frame interval value */
uint16_t startFrame; /*!<
Bandwidth start frame: its value is from 0 to frame_list.
*/
uint16_t dataTime; /*!<
Bandwidth time value:
- When the host works as HS: it's the data bandwidth value.
- When the host works as FS/LS:
- For FS/LS device, it's the data bandwidth value when transferring the data by FS/LS.
- For HS device, it's the data bandwidth value when transferring the data by HS.
*/
uint16_t startSplitTime; /*!<
Start splitting the bandwidth time value:
- When the host works as HS, it is the start split bandwidth value.
*/
uint16_t completeSplitTime; /*!<
Complete splitting the bandwidth time value:
- When host works as HS, it is the complete split bandwidth value.
*/
uint8_t startUframe; /*!<
Bandwidth start micro-frame: its value is from 0 to 7.
*/
uint8_t uframeSmask; /*!<
Start micro-frame.
- When host works as an HS:
- For FS/LS device, it's the interrupt or ISO transfer start-split mask.
- For HS device, it's the interrupt transfer start micro-frame mask.
- When host works as FS/LS, it's the interrupt and ISO start micro-frame mask
*/
uint8_t uframeCmask; /*!<
Complete micro-frame
- When host works as HS:
- For FS/LS device, it's the interrupt or ISO transfer complete-split mask.
*/
} usb_host_ehci_pipe_t;
/*! @brief EHCI QH structure. See the USB EHCI specification */
typedef struct _usb_host_ehci_qh
{
uint32_t horizontalLinkPointer; /*!< QH specification filed, queue head a horizontal link pointer */
uint32_t
staticEndpointStates[2]; /*!< QH specification filed, static endpoint state and configuration information */
uint32_t currentQtdPointer; /*!< QH specification filed, current qTD pointer */
uint32_t nextQtdPointer; /*!< QH specification filed, next qTD pointer */
uint32_t alternateNextQtdPointer; /*!< QH specification filed, alternate next qTD pointer */
uint32_t
transferOverlayResults[6]; /*!< QH specification filed, transfer overlay configuration and transfer results */
/* reserved space */
usb_host_ehci_pipe_t *ehciPipePointer; /*!< EHCI pipe pointer */
usb_host_transfer_t *ehciTransferHead; /*!< Transfer list head on this QH */
usb_host_transfer_t *ehciTransferTail; /*!< Transfer list tail on this QH */
uint16_t timeOutValue; /*!< Its maximum value is USB_HOST_EHCI_CONTROL_BULK_TIME_OUT_VALUE. When the value is
zero, the transfer times out. */
uint16_t timeOutLabel; /*!< It's used to judge the transfer timeout. The EHCI driver maintain the value */
} usb_host_ehci_qh_t;
/*! @brief EHCI QTD structure. See the USB EHCI specification. */
typedef struct _usb_host_ehci_qtd
{
uint32_t nextQtdPointer; /*!< QTD specification filed, the next QTD pointer */
uint32_t alternateNextQtdPointer; /*!< QTD specification filed, alternate next QTD pointer */
uint32_t transferResults[2]; /*!< QTD specification filed, transfer results fields */
uint32_t bufferPointers[4]; /*!< QTD specification filed, transfer buffer fields */
} usb_host_ehci_qtd_t;
/*! @brief EHCI ITD structure. See the USB EHCI specification. */
typedef struct _usb_host_ehci_itd
{
uint32_t nextLinkPointer; /*!< ITD specification filed, the next linker pointer */
uint32_t transactions[8]; /*!< ITD specification filed, transactions information */
uint32_t bufferPointers[7]; /*!< ITD specification filed, transfer buffer fields */
/* add space */
struct _usb_host_ehci_itd *nextItdPointer; /*!< Next ITD pointer */
uint32_t frameEntryIndex; /*!< The ITD inserted frame value */
uint32_t reserved[6]; /*!< Reserved fields for 32 bytes align */
} usb_host_ehci_itd_t;
/*! @brief EHCI SITD structure. See the USB EHCI specification. */
typedef struct _usb_host_ehci_sitd
{
uint32_t nextLinkPointer; /*!< SITD specification filed, the next linker pointer */
uint32_t endpointStates[2]; /*!< SITD specification filed, endpoint configuration information */
uint32_t transferResults[3]; /*!< SITD specification filed, transfer result fields */
uint32_t backPointer; /*!< SITD specification filed, back pointer */
/* reserved space */
uint16_t frameEntryIndex; /*!< The SITD inserted frame value */
uint8_t nextSitdIndex; /*!< The next SITD index; Get the next SITD pointer through adding base address with the
index. 0xFF means invalid. */
uint8_t reserved; /*!< Reserved fields for 32 bytes align */
} usb_host_ehci_sitd_t;
/*! @brief EHCI ISO structure; An ISO pipe has an instance of this structure to keep the ISO pipe-specific information.
*/
typedef struct _usb_host_ehci_iso
{
struct _usb_host_ehci_iso *next; /*!< Next instance pointer */
usb_host_pipe_t *ehciPipePointer; /*!< This ISO's EHCI pipe pointer */
usb_host_transfer_t *ehciTransferHead; /*!< Transfer list head on this ISO pipe */
usb_host_transfer_t *ehciTransferTail; /*!< Transfer list head on this ISO pipe */
uint16_t lastLinkFrame; /*!< It means that the inserted frame for ISO ITD/SITD. 0xFFFF is invalid. For ITD, it is a
micro-frame value. For SITD, it is a frame value */
} usb_host_ehci_iso_t;
/*! @brief EHCI instance structure */
typedef struct _usb_host_ehci_instance
{
usb_host_handle hostHandle; /*!< Related host handle*/
uint32_t *ehciUnitBase; /*!< Keep the QH/QTD/ITD/SITD buffer pointer for release*/
uint8_t *ehciFrameList; /*!< The frame list of the current ehci instance*/
usb_host_ehci_qh_t *ehciQhList; /*!< Idle QH list pointer */
usb_host_ehci_qtd_t *ehciQtdHead; /*!< Idle QTD list pointer head */
usb_host_ehci_qtd_t *ehciQtdTail; /*!< Idle QTD list pointer tail (recently used qTD will be used)*/
usb_host_ehci_itd_t *ehciItdList; /*!< Idle ITD list pointer*/
usb_host_ehci_sitd_t *ehciSitdIndexBase; /*!< SITD buffer's start pointer*/
usb_host_ehci_sitd_t *ehciSitdList; /*!< Idle SITD list pointer*/
usb_host_ehci_iso_t *ehciIsoList; /*!< Idle ISO list pointer*/
USBHS_Type *ehciIpBase; /*!< EHCI IP base address*/
usb_host_ehci_qh_t *shedFirstQh; /*!< First async QH*/
usb_host_ehci_pipe_t *ehciPipeIndexBase; /*!< Pipe buffer's start pointer*/
usb_host_ehci_pipe_t *ehciPipeList; /*!< Idle pipe list pointer*/
usb_host_ehci_pipe_t *ehciRunningPipeList; /*!< Running pipe list pointer*/
usb_osa_mutex_handle ehciMutex; /*!< EHCI mutex*/
usb_osa_event_handle taskEventHandle; /*!< EHCI task event*/
#if ((defined(USB_HOST_CONFIG_LOW_POWER_MODE)) && (USB_HOST_CONFIG_LOW_POWER_MODE > 0U))
uint64_t matchTick;
USBPHY_Type *registerPhyBase; /*!< The base address of the PHY register */
#if (defined(FSL_FEATURE_SOC_USBNC_COUNT) && (FSL_FEATURE_SOC_USBNC_COUNT > 0U))
USBNC_Type *registerNcBase; /*!< The base address of the USBNC register */
#endif
#endif
uint8_t controllerId; /*!< EHCI controller ID*/
uint8_t deviceAttached; /*!< Device attach/detach state, see #host_ehci_device_state_t */
uint8_t firstDeviceSpeed; /*!< The first device's speed, the controller's work speed*/
uint8_t ehciItdNumber; /*!< Idle ITD number*/
uint8_t ehciSitdNumber; /*!< Idle SITD number*/
uint8_t ehciQtdNumber; /*!< Idle QTD number*/
#if ((defined(USB_HOST_CONFIG_LOW_POWER_MODE)) && (USB_HOST_CONFIG_LOW_POWER_MODE > 0U))
bus_ehci_suspend_request_state_t busSuspendStatus; /*!< Bus Suspend Status*/
#endif
} usb_host_ehci_instance_t;
/*! @brief EHCI data structure */
typedef struct _usb_host_ehci_data
{
#if ((defined(USB_HOST_CONFIG_EHCI_MAX_QH)) && (USB_HOST_CONFIG_EHCI_MAX_QH > 0U))
usb_host_ehci_qh_t ehciQh[USB_HOST_CONFIG_EHCI_MAX_QH]; /*!< Idle QH list array*/
#endif
#if ((defined(USB_HOST_CONFIG_EHCI_MAX_QTD)) && (USB_HOST_CONFIG_EHCI_MAX_QTD > 0U))
usb_host_ehci_qtd_t ehciQtd[USB_HOST_CONFIG_EHCI_MAX_QTD]; /*!< Idle QTD list array*/
#endif
#if ((defined(USB_HOST_CONFIG_EHCI_MAX_ITD)) && (USB_HOST_CONFIG_EHCI_MAX_ITD > 0U))
usb_host_ehci_itd_t ehciItd[USB_HOST_CONFIG_EHCI_MAX_ITD]; /*!< Idle ITD list array*/
#endif
#if ((defined(USB_HOST_CONFIG_EHCI_MAX_SITD)) && (USB_HOST_CONFIG_EHCI_MAX_SITD > 0U))
usb_host_ehci_sitd_t ehciSitd[USB_HOST_CONFIG_EHCI_MAX_SITD]; /*!< Idle SITD list array*/
#endif
#if ((defined(USB_HOST_EHCI_ISO_NUMBER)) && (USB_HOST_EHCI_ISO_NUMBER > 0U))
usb_host_ehci_iso_t ehciIso[USB_HOST_EHCI_ISO_NUMBER]; /*!< Idle ISO list array*/
#endif
#if ((defined(USB_HOST_CONFIG_MAX_PIPES)) && (USB_HOST_CONFIG_MAX_PIPES > 0U))
usb_host_ehci_pipe_t ehciPipe[USB_HOST_CONFIG_MAX_PIPES]; /*!< Idle pipe list array*/
#endif
} usb_host_ehci_data_t;
/*******************************************************************************
* API
******************************************************************************/
#ifdef __cplusplus
extern "C" {
#endif
/*!
* @name USB host EHCI APIs
* @{
*/
/*!
* @brief Creates the USB host EHCI instance.
*
* This function initializes the USB host EHCI controller driver.
*
* @param[in] controllerId The controller ID of the USB IP. Please refer to the enumeration usb_controller_index_t.
* @param[in] upperLayerHandle The host level handle.
* @param[out] controllerHandle return the controller instance handle.
*
* @retval kStatus_USB_Success The host is initialized successfully.
* @retval kStatus_USB_AllocFail Allocating memory failed.
* @retval kStatus_USB_Error Host mutex create fail, KHCI/EHCI mutex or KHCI/EHCI event create fail.
* Or, KHCI/EHCI IP initialize fail.
*/
extern usb_status_t USB_HostEhciCreate(uint8_t controllerId,
usb_host_handle upperLayerHandle,
usb_host_controller_handle *controllerHandle);
/*!
* @brief Destroys the USB host EHCI instance.
*
* This function de-initializes The USB host EHCI controller driver.
*
* @param[in] controllerHandle The controller handle.
*
* @retval kStatus_USB_Success The host is initialized successfully.
*/
extern usb_status_t USB_HostEhciDestory(usb_host_controller_handle controllerHandle);
/*!
* @brief Opens the USB host pipe.
*
* This function opens a pipe according to the pipe_init_ptr parameter.
*
* @param[in] controllerHandle The controller handle.
* @param[out] pipeHandle The pipe handle pointer, it is used to return the pipe handle.
* @param[in] pipeInit It is used to initialize the pipe.
*
* @retval kStatus_USB_Success The host is initialized successfully.
* @retval kStatus_USB_Error There is no idle pipe.
* Or, there is no idle QH for EHCI.
* Or, bandwidth allocate fail for EHCI.
*/
extern usb_status_t USB_HostEhciOpenPipe(usb_host_controller_handle controllerHandle,
usb_host_pipe_handle *pipeHandle,
usb_host_pipe_init_t *pipeInit);
/*!
* @brief Closes the USB host pipe.
*
* This function closes a pipe and releases related resources.
*
* @param[in] controllerHandle The controller handle.
* @param[in] pipeHandle The closing pipe handle.
*
* @retval kStatus_USB_Success The host is initialized successfully.
*/
extern usb_status_t USB_HostEhciClosePipe(usb_host_controller_handle controllerHandle, usb_host_pipe_handle pipeHandle);
/*!
* @brief Sends data to the pipe.
*
* This function requests to send the transfer to the specified pipe.
*
* @param[in] controllerHandle The controller handle.
* @param[in] pipeHandle The sending pipe handle.
* @param[in] transfer The transfer information.
*
* @retval kStatus_USB_Success Sent successfully.
* @retval kStatus_USB_LackSwapBuffer There is no swap buffer for KHCI.
* @retval kStatus_USB_Error There is no idle QTD/ITD/SITD for EHCI.
*/
extern usb_status_t USB_HostEhciWritePipe(usb_host_controller_handle controllerHandle,
usb_host_pipe_handle pipeHandle,
usb_host_transfer_t *transfer);
/*!
* @brief Receives data from the pipe.
*
* This function requests to receive the transfer from the specified pipe.
*
* @param[in] controllerHandle The controller handle.
* @param[in] pipeHandle The receiving pipe handle.
* @param[in] transfer The transfer information.
* @retval kStatus_USB_Success Send successfully.
* @retval kStatus_USB_LackSwapBuffer There is no swap buffer for KHCI.
* @retval kStatus_USB_Error There is no idle QTD/ITD/SITD for EHCI.
*/
extern usb_status_t USB_HostEhciReadpipe(usb_host_controller_handle controllerHandle,
usb_host_pipe_handle pipeHandle,
usb_host_transfer_t *transfer);
/*!
* @brief Controls the EHCI.
*
* This function controls the EHCI.
*
* @param[in] controllerHandle The controller handle.
* @param[in] ioctlEvent See enumeration host_bus_control_t.
* @param[in] ioctlParam The control parameter.
*
* @retval kStatus_USB_Success Cancel successfully.
* @retval kStatus_USB_InvalidHandle The controllerHandle is a NULL pointer.
*/
extern usb_status_t USB_HostEhciIoctl(usb_host_controller_handle controllerHandle,
uint32_t ioctlEvent,
void *ioctlParam);
/*! @}*/
#ifdef __cplusplus
}
#endif
/*! @}*/
#endif /* _USB_HOST_CONTROLLER_EHCI_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,131 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _USB_HOST_HCI_H_
#define _USB_HOST_HCI_H_
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief USB host lock */
#define USB_HostLock() USB_OsaMutexLock(hostInstance->hostMutex)
/*! @brief USB host unlock */
#define USB_HostUnlock() USB_OsaMutexUnlock(hostInstance->hostMutex)
/*!
* @addtogroup usb_host_controller_driver
* @{
*/
/*! @brief USB host controller control code */
typedef enum _usb_host_controller_control
{
kUSB_HostCancelTransfer = 1U, /*!< Cancel transfer code */
kUSB_HostBusControl, /*!< Bus control code */
kUSB_HostGetFrameNumber, /*!< Get frame number code */
kUSB_HostUpdateControlEndpointAddress, /*!< Update control endpoint address */
kUSB_HostUpdateControlPacketSize, /*!< Update control endpoint maximum packet size */
kUSB_HostPortAttachDisable, /*!< Disable the port attach event */
kUSB_HostPortAttachEnable, /*!< Enable the port attach event */
kUSB_HostL1Config, /*!< L1 suspend Bus control code */
} usb_host_controller_control_t;
/*! @brief USB host controller bus control code */
typedef enum _usb_host_bus_control
{
kUSB_HostBusReset = 1U, /*!< Reset bus */
kUSB_HostBusRestart, /*!< Restart bus */
kUSB_HostBusEnableAttach, /*!< Enable attach */
kUSB_HostBusDisableAttach, /*!< Disable attach */
kUSB_HostBusSuspend, /*!< Suspend BUS */
kUSB_HostBusResume, /*!< Resume BUS */
kUSB_HostBusL1SuspendInit, /*!< L1 Suspend BUS */
kUSB_HostBusL1Sleep, /*!< L1 Suspend BUS */
kUSB_HostBusL1Resume, /*!< L1 Resume BUS */
} usb_host_bus_control_t;
/*! @brief USB host controller interface structure */
typedef struct _usb_host_controller_interface
{
usb_status_t (*controllerCreate)(
uint8_t controllerId,
usb_host_handle upperLayerHandle,
usb_host_controller_handle *controllerHandle); /*!< Create a controller instance function prototype*/
usb_status_t (*controllerDestory)(
usb_host_controller_handle controllerHandle); /*!< Destroy a controller instance function prototype*/
usb_status_t (*controllerOpenPipe)(usb_host_controller_handle controllerHandle,
usb_host_pipe_handle *pipeHandle,
usb_host_pipe_init_t *pipeInit); /*!< Open a controller pipe function prototype*/
usb_status_t (*controllerClosePipe)(
usb_host_controller_handle controllerHandle,
usb_host_pipe_handle pipeHandle); /*!< Close a controller pipe function prototype*/
usb_status_t (*controllerWritePipe)(usb_host_controller_handle controllerHandle,
usb_host_pipe_handle pipeHandle,
usb_host_transfer_t *transfer); /*!< Write data to a pipe function prototype*/
usb_status_t (*controllerReadPipe)(usb_host_controller_handle controllerHandle,
usb_host_pipe_handle pipeHandle,
usb_host_transfer_t *transfer); /*!< Read data from a pipe function prototype*/
usb_status_t (*controllerIoctl)(usb_host_controller_handle controllerHandle,
uint32_t ioctlEvent,
void *ioctlParam); /*!< Control a controller function prototype*/
} usb_host_controller_interface_t;
/*! @}*/
/*!
* @addtogroup usb_host_drv
* @{
*/
/*! @brief USB host instance structure */
typedef struct _usb_host_instance
{
void *controllerHandle; /*!< The low level controller handle*/
host_callback_t deviceCallback; /*!< Device attach/detach callback*/
usb_osa_mutex_handle hostMutex; /*!< Host layer mutex*/
usb_host_transfer_t transferList[USB_HOST_CONFIG_MAX_TRANSFERS]; /*!< Transfer resource*/
usb_host_transfer_t *transferHead; /*!< Idle transfer head*/
const usb_host_controller_interface_t *controllerTable; /*!< KHCI/EHCI interface*/
void *deviceList; /*!< Device list*/
#if ((defined(USB_HOST_CONFIG_LOW_POWER_MODE)) && (USB_HOST_CONFIG_LOW_POWER_MODE > 0U))
void *suspendedDevice; /*!< Suspended device handle*/
volatile uint64_t hwTick; /*!< Current hw tick(ms)*/
uint8_t sleepType; /*!< L1 LPM device handle*/
#endif
uint8_t addressBitMap[16]; /*!< Used for address allocation. The first bit is the address 1, second bit is the
address 2*/
uint8_t occupied; /*!< 0 - the instance is not occupied; 1 - the instance is occupied*/
uint8_t controllerId; /*!< The controller ID*/
} usb_host_instance_t;
/*! @}*/
#endif /* _USB_HOST_HCI_H_ */

View File

@ -0,0 +1,140 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __USB_H__
#define __USB_H__
#include <stdint.h>
#include <stdio.h>
#include <fsl_common.h>
#include "usb_misc.h"
#include "usb_spec.h"
/*!
* @addtogroup usb_drv
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief Defines USB stack major version */
#define USB_STACK_VERSION_MAJOR (1U)
/*! @brief Defines USB stack minor version */
#define USB_STACK_VERSION_MINOR (6U)
/*! @brief Defines USB stack bugfix version */
#define USB_STACK_VERSION_BUGFIX (3U)
/*! @brief USB stack version definition */
#define USB_MAKE_VERSION(major, minor, bugfix) (((major) << 16) | ((minor) << 8) | (bugfix))
/*! @brief USB error code */
typedef enum _usb_status
{
kStatus_USB_Success = 0x00U, /*!< Success */
kStatus_USB_Error, /*!< Failed */
kStatus_USB_Busy, /*!< Busy */
kStatus_USB_InvalidHandle, /*!< Invalid handle */
kStatus_USB_InvalidParameter, /*!< Invalid parameter */
kStatus_USB_InvalidRequest, /*!< Invalid request */
kStatus_USB_ControllerNotFound, /*!< Controller cannot be found */
kStatus_USB_InvalidControllerInterface, /*!< Invalid controller interface */
kStatus_USB_NotSupported, /*!< Configuration is not supported */
kStatus_USB_Retry, /*!< Enumeration get configuration retry */
kStatus_USB_TransferStall, /*!< Transfer stalled */
kStatus_USB_TransferFailed, /*!< Transfer failed */
kStatus_USB_AllocFail, /*!< Allocation failed */
kStatus_USB_LackSwapBuffer, /*!< Insufficient swap buffer for KHCI */
kStatus_USB_TransferCancel, /*!< The transfer cancelled */
kStatus_USB_BandwidthFail, /*!< Allocate bandwidth failed */
kStatus_USB_MSDStatusFail, /*!< For MSD, the CSW status means fail */
kStatus_USB_EHCIAttached,
kStatus_USB_EHCIDetached,
} usb_status_t;
/*! @brief USB host handle type define */
typedef void *usb_host_handle;
/*! @brief USB device handle type define. For device stack it is the whole device handle; for host stack it is the
* attached device instance handle*/
typedef void *usb_device_handle;
/*! @brief USB OTG handle type define */
typedef void *usb_otg_handle;
/*! @brief USB controller ID */
typedef enum _usb_controller_index
{
kUSB_ControllerKhci0 = 0U, /*!< KHCI 0U */
kUSB_ControllerKhci1 = 1U, /*!< KHCI 1U, Currently, there are no platforms which have two KHCI IPs, this is reserved
to be used in the future. */
kUSB_ControllerEhci0 = 2U, /*!< EHCI 0U */
kUSB_ControllerEhci1 = 3U, /*!< EHCI 1U, Currently, there are no platforms which have two EHCI IPs, this is reserved
to be used in the future. */
kUSB_ControllerLpcIp3511Fs0 = 4U, /*!< LPC USB IP3511 FS controller 0 */
kUSB_ControllerLpcIp3511Fs1 =
5U, /*!< LPC USB IP3511 FS controller 1, there are no platforms which have two IP3511 IPs, this is reserved
to be used in the future. */
kUSB_ControllerLpcIp3511Hs0 = 6U, /*!< LPC USB IP3511 HS controller 0 */
kUSB_ControllerLpcIp3511Hs1 =
7U, /*!< LPC USB IP3511 HS controller 1, there are no platforms which have two IP3511 IPs, this is reserved
to be used in the future. */
kUSB_ControllerOhci0 = 8U, /*!< OHCI 0U */
kUSB_ControllerOhci1 = 9U, /*!< OHCI 1U, Currently, there are no platforms which have two OHCI IPs, this is reserved
to be used in the future. */
kUSB_ControllerIp3516Hs0 = 10U, /*!< IP3516HS 0U */
kUSB_ControllerIp3516Hs1 =
11U, /*!< IP3516HS 1U, Currently, there are no platforms which have two IP3516HS IPs, this is reserved
to be used in the future. */
} usb_controller_index_t;
/**
* @brief USB stack version fields
*/
typedef struct _usb_version
{
uint8_t major; /*!< Major */
uint8_t minor; /*!< Minor */
uint8_t bugfix; /*!< Bug fix */
} usb_version_t;
/*******************************************************************************
* API
******************************************************************************/
/*! @} */
#endif /* __USB_H__ */

View File

@ -0,0 +1,185 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016 - 2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _USB_DEVICE_CONFIG_H_
#define _USB_DEVICE_CONFIG_H_
/*******************************************************************************
* Definitions
******************************************************************************/
/*!
* @addtogroup usb_device_configuration
* @{
*/
/*!
* @name Hardware instance define
* @{
*/
/*! @brief KHCI instance count */
#define USB_DEVICE_CONFIG_KHCI (0U)
/*! @brief EHCI instance count */
#define USB_DEVICE_CONFIG_EHCI (2U)
/*! @brief LPC USB IP3511 FS instance count */
#define USB_DEVICE_CONFIG_LPCIP3511FS (0U)
/*! @brief LPC USB IP3511 HS instance count */
#define USB_DEVICE_CONFIG_LPCIP3511HS (0U)
/*! @brief Device instance count, the sum of KHCI and EHCI instance counts*/
#define USB_DEVICE_CONFIG_NUM \
(USB_DEVICE_CONFIG_KHCI + USB_DEVICE_CONFIG_EHCI + USB_DEVICE_CONFIG_LPCIP3511FS + USB_DEVICE_CONFIG_LPCIP3511HS)
/* @} */
/*!
* @name class instance define
* @{
*/
/*! @brief HID instance count */
#define USB_DEVICE_CONFIG_HID (0U)
/*! @brief CDC ACM instance count */
#define USB_DEVICE_CONFIG_CDC_ACM (1U)
/*! @brief MSC instance count */
#define USB_DEVICE_CONFIG_MSC (0U)
/*! @brief Audio instance count */
#define USB_DEVICE_CONFIG_AUDIO (0U)
/*! @brief PHDC instance count */
#define USB_DEVICE_CONFIG_PHDC (0U)
/*! @brief Video instance count */
#define USB_DEVICE_CONFIG_VIDEO (0U)
/*! @brief CCID instance count */
#define USB_DEVICE_CONFIG_CCID (0U)
/*! @brief Printer instance count */
#define USB_DEVICE_CONFIG_PRINTER (0U)
/*! @brief DFU instance count */
#define USB_DEVICE_CONFIG_DFU (0U)
/* @} */
/*! @brief Whether device is self power. 1U supported, 0U not supported */
#define USB_DEVICE_CONFIG_SELF_POWER (1U)
/*! @brief How many endpoints are supported in the stack. */
#define USB_DEVICE_CONFIG_ENDPOINTS (4U)
/*! @brief Whether the device task is enabled. */
#define USB_DEVICE_CONFIG_USE_TASK (0U)
/*! @brief How many the notification message are supported when the device task is enabled. */
#define USB_DEVICE_CONFIG_MAX_MESSAGES (8U)
/*! @brief Whether test mode enabled. */
#define USB_DEVICE_CONFIG_USB20_TEST_MODE (0U)
/*! @brief Whether device CV test is enabled. */
#define USB_DEVICE_CONFIG_CV_TEST (0U)
/*! @brief Whether device compliance test is enabled. If the macro is enabled,
the test mode and CV test macroes will be set.*/
#define USB_DEVICE_CONFIG_COMPLIANCE_TEST (0U)
#if ((defined(USB_DEVICE_CONFIG_COMPLIANCE_TEST)) && (USB_DEVICE_CONFIG_COMPLIANCE_TEST > 0U))
/*! @brief Undefine the marco USB_DEVICE_CONFIG_USB20_TEST_MODE. */
#undef USB_DEVICE_CONFIG_USB20_TEST_MODE
/*! @brief Undefine the marco USB_DEVICE_CONFIG_CV_TEST. */
#undef USB_DEVICE_CONFIG_CV_TEST
/*! @brief enable the test mode. */
#define USB_DEVICE_CONFIG_USB20_TEST_MODE (1U)
/*! @brief enable the CV test */
#define USB_DEVICE_CONFIG_CV_TEST (1U)
#endif
#if ((defined(USB_DEVICE_CONFIG_KHCI)) && (USB_DEVICE_CONFIG_KHCI > 0U))
/*! @brief The MAX buffer length for the KHCI DMA workaround.*/
#define USB_DEVICE_CONFIG_KHCI_DMA_ALIGN_BUFFER_LENGTH (64U)
#endif
#if ((defined(USB_DEVICE_CONFIG_EHCI)) && (USB_DEVICE_CONFIG_EHCI > 0U))
/*! @brief How many the DTD are supported. */
#define USB_DEVICE_CONFIG_EHCI_MAX_DTD (16U)
/*! @brief Whether the EHCI ID pin detect feature enabled. */
#define USB_DEVICE_CONFIG_EHCI_ID_PIN_DETECT (0U)
#endif
/*! @brief Whether the keep alive feature enabled. */
#define USB_DEVICE_CONFIG_KEEP_ALIVE_MODE (0U)
/*! @brief Whether the transfer buffer is cache-enabled or not. */
#define USB_DEVICE_CONFIG_BUFFER_PROPERTY_CACHEABLE (1U)
/*! @brief Whether the low power mode is enabled or not. */
#define USB_DEVICE_CONFIG_LOW_POWER_MODE (0U)
#if ((defined(USB_DEVICE_CONFIG_LOW_POWER_MODE)) && (USB_DEVICE_CONFIG_LOW_POWER_MODE > 0U))
/*! @brief Whether device remote wakeup supported. 1U supported, 0U not supported */
#define USB_DEVICE_CONFIG_REMOTE_WAKEUP (0U)
/*! @brief Whether LPM is supported. 1U supported, 0U not supported */
#define USB_DEVICE_CONFIG_LPM_L1 (0U)
#else
/*! @brief The device remote wakeup is unsupported. */
#define USB_DEVICE_CONFIG_REMOTE_WAKEUP (0U)
#endif
/*! @brief Whether the device detached feature is enabled or not. */
#define USB_DEVICE_CONFIG_DETACH_ENABLE (0U)
/*! @brief Whether handle the USB bus error. */
#define USB_DEVICE_CONFIG_ERROR_HANDLING (0U)
/* @} */
/*! @brief rt-thread port alloc */
#include <rtthread.h>
#define USB_OSA_SR_ALLOC(...)
/*! @brief rt-thread port enter critical */
#define USB_OSA_ENTER_CRITICAL rt_enter_critical
/*! @brief rt-thread port exit critical */
#define USB_OSA_EXIT_CRITICAL rt_exit_critical
#endif /* _USB_DEVICE_CONFIG_H_ */

View File

@ -0,0 +1,140 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __USB_EHCI_H__
#define __USB_EHCI_H__
/*******************************************************************************
* Definitions
******************************************************************************/
/* Device QH */
#define USB_DEVICE_EHCI_QH_POINTER_MASK (0xFFFFFFC0U)
#define USB_DEVICE_EHCI_QH_MULT_MASK (0xC0000000U)
#define USB_DEVICE_EHCI_QH_ZLT_MASK (0x20000000U)
#define USB_DEVICE_EHCI_QH_MAX_PACKET_SIZE_MASK (0x07FF0000U)
#define USB_DEVICE_EHCI_QH_MAX_PACKET_SIZE (0x00000800U)
#define USB_DEVICE_EHCI_QH_IOS_MASK (0x00008000U)
/* Device DTD */
#define USB_DEVICE_ECHI_DTD_POINTER_MASK (0xFFFFFFE0U)
#define USB_DEVICE_ECHI_DTD_TERMINATE_MASK (0x00000001U)
#define USB_DEVICE_ECHI_DTD_PAGE_MASK (0xFFFFF000U)
#define USB_DEVICE_ECHI_DTD_PAGE_OFFSET_MASK (0x00000FFFU)
#define USB_DEVICE_ECHI_DTD_PAGE_BLOCK (0x00001000U)
#define USB_DEVICE_ECHI_DTD_TOTAL_BYTES_MASK (0x7FFF0000U)
#define USB_DEVICE_ECHI_DTD_TOTAL_BYTES (0x00004000U)
#define USB_DEVICE_ECHI_DTD_IOC_MASK (0x00008000U)
#define USB_DEVICE_ECHI_DTD_MULTIO_MASK (0x00000C00U)
#define USB_DEVICE_ECHI_DTD_STATUS_MASK (0x000000FFU)
#define USB_DEVICE_EHCI_DTD_STATUS_ERROR_MASK (0x00000068U)
#define USB_DEVICE_ECHI_DTD_STATUS_ACTIVE (0x00000080U)
#define USB_DEVICE_ECHI_DTD_STATUS_HALTED (0x00000040U)
#define USB_DEVICE_ECHI_DTD_STATUS_DATA_BUFFER_ERROR (0x00000020U)
#define USB_DEVICE_ECHI_DTD_STATUS_TRANSACTION_ERROR (0x00000008U)
typedef struct _usb_device_ehci_qh_struct
{
union
{
volatile uint32_t capabilttiesCharacteristics;
struct
{
volatile uint32_t reserved1 : 15;
volatile uint32_t ios : 1;
volatile uint32_t maxPacketSize : 11;
volatile uint32_t reserved2 : 2;
volatile uint32_t zlt : 1;
volatile uint32_t mult : 2;
} capabilttiesCharacteristicsBitmap;
} capabilttiesCharacteristicsUnion;
volatile uint32_t currentDtdPointer;
volatile uint32_t nextDtdPointer;
union
{
volatile uint32_t dtdToken;
struct
{
volatile uint32_t status : 8;
volatile uint32_t reserved1 : 2;
volatile uint32_t multiplierOverride : 2;
volatile uint32_t reserved2 : 3;
volatile uint32_t ioc : 1;
volatile uint32_t totalBytes : 15;
volatile uint32_t reserved3 : 1;
} dtdTokenBitmap;
} dtdTokenUnion;
volatile uint32_t bufferPointerPage[5];
volatile uint32_t reserved1;
uint32_t setupBuffer[2];
uint32_t setupBufferBack[2];
union
{
uint32_t endpointStatus;
struct
{
uint32_t isOpened : 1;
uint32_t : 31;
} endpointStatusBitmap;
} endpointStatusUnion;
uint32_t reserved2;
} usb_device_ehci_qh_struct_t;
typedef struct _usb_device_ehci_dtd_struct
{
volatile uint32_t nextDtdPointer;
union
{
volatile uint32_t dtdToken;
struct
{
volatile uint32_t status : 8;
volatile uint32_t reserved1 : 2;
volatile uint32_t multiplierOverride : 2;
volatile uint32_t reserved2 : 3;
volatile uint32_t ioc : 1;
volatile uint32_t totalBytes : 15;
volatile uint32_t reserved3 : 1;
} dtdTokenBitmap;
} dtdTokenUnion;
volatile uint32_t bufferPointerPage[5];
union
{
volatile uint32_t reserved;
struct
{
uint32_t originalBufferOffest : 12;
uint32_t originalBufferLength : 19;
uint32_t dtdInvalid : 1;
} originalBufferInfo;
} reservedUnion;
} usb_device_ehci_dtd_struct_t;
#endif /* __USB_EHCI_H__ */

View File

@ -0,0 +1,452 @@
/*
* Copyright (c) 2015 - 2016, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __USB_MISC_H__
#define __USB_MISC_H__
#ifndef ENDIANNESS
#error ENDIANNESS should be defined, and then rebulid the project.
#endif
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief Define USB printf */
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus */
extern int DbgConsole_Printf(const char *fmt_s, ...);
#if defined(__cplusplus)
}
#endif /* __cplusplus */
#if defined(SDK_DEBUGCONSOLE) && (SDK_DEBUGCONSOLE < 1)
#define usb_echo printf
#else
#define usb_echo DbgConsole_Printf
#endif
#if defined(__ICCARM__)
#ifndef STRUCT_PACKED
#define STRUCT_PACKED __packed
#endif
#ifndef STRUCT_UNPACKED
#define STRUCT_UNPACKED
#endif
#elif defined(__GNUC__)
#ifndef STRUCT_PACKED
#define STRUCT_PACKED
#endif
#ifndef STRUCT_UNPACKED
#define STRUCT_UNPACKED __attribute__((__packed__))
#endif
#elif defined(__CC_ARM)
#ifndef STRUCT_PACKED
#define STRUCT_PACKED _Pragma("pack(1U)")
#endif
#ifndef STRUCT_UNPACKED
#define STRUCT_UNPACKED _Pragma("pack()")
#endif
#endif
#define USB_SHORT_GET_LOW(x) (((uint16_t)x) & 0xFFU)
#define USB_SHORT_GET_HIGH(x) ((uint8_t)(((uint16_t)x) >> 8U) & 0xFFU)
#define USB_LONG_GET_BYTE0(x) ((uint8_t)(((uint32_t)(x))) & 0xFFU)
#define USB_LONG_GET_BYTE1(x) ((uint8_t)(((uint32_t)(x)) >> 8U) & 0xFFU)
#define USB_LONG_GET_BYTE2(x) ((uint8_t)(((uint32_t)(x)) >> 16U) & 0xFFU)
#define USB_LONG_GET_BYTE3(x) ((uint8_t)(((uint32_t)(x)) >> 24U) & 0xFFU)
#define USB_MEM4_ALIGN_MASK (0x03U)
/* accessory macro */
#define USB_MEM4_ALIGN(n) ((n + 3U) & (0xFFFFFFFCu))
#define USB_MEM32_ALIGN(n) ((n + 31U) & (0xFFFFFFE0u))
#define USB_MEM64_ALIGN(n) ((n + 63U) & (0xFFFFFFC0u))
/* big/little endian */
#define SWAP2BYTE_CONST(n) ((((n)&0x00FFU) << 8U) | (((n)&0xFF00U) >> 8U))
#define SWAP4BYTE_CONST(n) \
((((n)&0x000000FFU) << 24U) | (((n)&0x0000FF00U) << 8U) | (((n)&0x00FF0000U) >> 8U) | (((n)&0xFF000000U) >> 24U))
#define USB_ASSIGN_VALUE_ADDRESS_LONG_BY_BYTE(n, m) \
{ \
*((uint8_t *)&(n)) = *((uint8_t *)&(m)); \
*((uint8_t *)&(n) + 1) = *((uint8_t *)&(m) + 1); \
*((uint8_t *)&(n) + 2) = *((uint8_t *)&(m) + 2); \
*((uint8_t *)&(n) + 3) = *((uint8_t *)&(m) + 3); \
}
#define USB_ASSIGN_VALUE_ADDRESS_SHORT_BY_BYTE(n, m) \
{ \
*((uint8_t *)&(n)) = *((uint8_t *)&(m)); \
*((uint8_t *)&(n) + 1) = *((uint8_t *)&(m) + 1); \
}
#define USB_ASSIGN_MACRO_VALUE_ADDRESS_LONG_BY_BYTE(n, m) \
{ \
*((uint8_t *)&(n)) = (uint8_t)m; \
*((uint8_t *)&(n) + 1) = (uint8_t)(m >> 8); \
*((uint8_t *)&(n) + 2) = (uint8_t)(m >> 16); \
*((uint8_t *)&(n) + 3) = (uint8_t)(m >> 24); \
}
#define USB_ASSIGN_MACRO_VALUE_ADDRESS_SHORT_BY_BYTE(n, m) \
{ \
*((uint8_t *)&(n)) = (uint8_t)m; \
*((uint8_t *)&(n) + 1) = (uint8_t)(m >> 8); \
}
#if (ENDIANNESS == USB_BIG_ENDIAN)
#define USB_SHORT_TO_LITTLE_ENDIAN(n) SWAP2BYTE_CONST(n)
#define USB_LONG_TO_LITTLE_ENDIAN(n) SWAP4BYTE_CONST(n)
#define USB_SHORT_FROM_LITTLE_ENDIAN(n) SWAP2BYTE_CONST(n)
#define USB_LONG_FROM_LITTLE_ENDIAN(n) SWAP2BYTE_CONST(n)
#define USB_SHORT_TO_BIG_ENDIAN(n) (n)
#define USB_LONG_TO_BIG_ENDIAN(n) (n)
#define USB_SHORT_FROM_BIG_ENDIAN(n) (n)
#define USB_LONG_FROM_BIG_ENDIAN(n) (n)
#define USB_LONG_TO_LITTLE_ENDIAN_ADDRESS(n, m) \
{ \
m[3] = ((n >> 24U) & 0xFFU); \
m[2] = ((n >> 16U) & 0xFFU); \
m[1] = ((n >> 8U) & 0xFFU); \
m[0] = (n & 0xFFU); \
}
#define USB_LONG_FROM_LITTLE_ENDIAN_ADDRESS(n) \
((uint32_t)((((uint8_t)n[3]) << 24U) | (((uint8_t)n[2]) << 16U) | (((uint8_t)n[1]) << 8U) | \
(((uint8_t)n[0]) << 0U)))
#define USB_LONG_TO_BIG_ENDIAN_ADDRESS(n, m) \
{ \
m[0] = ((n >> 24U) & 0xFFU); \
m[1] = ((n >> 16U) & 0xFFU); \
m[2] = ((n >> 8U) & 0xFFU); \
m[3] = (n & 0xFFU); \
}
#define USB_LONG_FROM_BIG_ENDIAN_ADDRESS(n) \
((uint32_t)((((uint8_t)n[0]) << 24U) | (((uint8_t)n[1]) << 16U) | (((uint8_t)n[2]) << 8U) | \
(((uint8_t)n[3]) << 0U)))
#define USB_SHORT_TO_LITTLE_ENDIAN_ADDRESS(n, m) \
{ \
m[1] = ((n >> 8U) & 0xFFU); \
m[0] = (n & 0xFFU); \
}
#define USB_SHORT_FROM_LITTLE_ENDIAN_ADDRESS(n) ((uint32_t)((((uint8_t)n[1]) << 8U) | (((uint8_t)n[0]) << 0U)))
#define USB_SHORT_TO_BIG_ENDIAN_ADDRESS(n, m) \
{ \
m[0] = ((n >> 8U) & 0xFFU); \
m[1] = (n & 0xFFU); \
}
#define USB_SHORT_FROM_BIG_ENDIAN_ADDRESS(n) ((uint32_t)((((uint8_t)n[0]) << 8U) | (((uint8_t)n[1]) << 0U)))
#define USB_LONG_TO_LITTLE_ENDIAN_DATA(n, m) \
{ \
*((uint8_t *)&(m) + 3) = ((n >> 24U) & 0xFFU); \
*((uint8_t *)&(m) + 2) = ((n >> 16U) & 0xFFU); \
*((uint8_t *)&(m) + 1) = ((n >> 8U) & 0xFFU); \
*((uint8_t *)&(m) + 0) = (n & 0xFFU); \
}
#define USB_LONG_FROM_LITTLE_ENDIAN_DATA(n) \
((uint32_t)(((*((uint8_t *)&(n) + 3)) << 24U) | ((*((uint8_t *)&(n) + 2)) << 16U) | \
((*((uint8_t *)&(n) + 1)) << 8U) | ((*((uint8_t *)&(n))) << 0U)))
#define USB_SHORT_TO_LITTLE_ENDIAN_DATA(n, m) \
{ \
*((uint8_t *)&(m) + 1) = ((n >> 8U) & 0xFFU); \
*((uint8_t *)&(m)) = ((n)&0xFFU); \
}
#define USB_SHORT_FROM_LITTLE_ENDIAN_DATA(n) ((uint32_t)(((*((uint8_t *)&(n) + 1)) << 8U) | ((*((uint8_t *)&(n))))))
#else
#define USB_SHORT_TO_LITTLE_ENDIAN(n) (n)
#define USB_LONG_TO_LITTLE_ENDIAN(n) (n)
#define USB_SHORT_FROM_LITTLE_ENDIAN(n) (n)
#define USB_LONG_FROM_LITTLE_ENDIAN(n) (n)
#define USB_SHORT_TO_BIG_ENDIAN(n) SWAP2BYTE_CONST(n)
#define USB_LONG_TO_BIG_ENDIAN(n) SWAP4BYTE_CONST(n)
#define USB_SHORT_FROM_BIG_ENDIAN(n) SWAP2BYTE_CONST(n)
#define USB_LONG_FROM_BIG_ENDIAN(n) SWAP4BYTE_CONST(n)
#define USB_LONG_TO_LITTLE_ENDIAN_ADDRESS(n, m) \
{ \
m[3] = ((n >> 24U) & 0xFFU); \
m[2] = ((n >> 16U) & 0xFFU); \
m[1] = ((n >> 8U) & 0xFFU); \
m[0] = (n & 0xFFU); \
}
#define USB_LONG_FROM_LITTLE_ENDIAN_ADDRESS(n) \
((uint32_t)((((uint8_t)n[3]) << 24U) | (((uint8_t)n[2]) << 16U) | (((uint8_t)n[1]) << 8U) | \
(((uint8_t)n[0]) << 0U)))
#define USB_LONG_TO_BIG_ENDIAN_ADDRESS(n, m) \
{ \
m[0] = ((n >> 24U) & 0xFFU); \
m[1] = ((n >> 16U) & 0xFFU); \
m[2] = ((n >> 8U) & 0xFFU); \
m[3] = (n & 0xFFU); \
}
#define USB_LONG_FROM_BIG_ENDIAN_ADDRESS(n) \
((uint32_t)((((uint8_t)n[0]) << 24U) | (((uint8_t)n[1]) << 16U) | (((uint8_t)n[2]) << 8U) | \
(((uint8_t)n[3]) << 0U)))
#define USB_SHORT_TO_LITTLE_ENDIAN_ADDRESS(n, m) \
{ \
m[1] = ((n >> 8U) & 0xFFU); \
m[0] = (n & 0xFFU); \
}
#define USB_SHORT_FROM_LITTLE_ENDIAN_ADDRESS(n) ((uint32_t)((((uint8_t)n[1]) << 8U) | (((uint8_t)n[0]) << 0U)))
#define USB_SHORT_TO_BIG_ENDIAN_ADDRESS(n, m) \
{ \
m[0] = ((n >> 8U) & 0xFFU); \
m[1] = (n & 0xFFU); \
}
#define USB_SHORT_FROM_BIG_ENDIAN_ADDRESS(n) ((uint32_t)((((uint8_t)n[0]) << 8U) | (((uint8_t)n[1]) << 0U)))
#define USB_LONG_TO_LITTLE_ENDIAN_DATA(n, m) \
{ \
*((uint8_t *)&(m) + 3) = ((n >> 24U) & 0xFFU); \
*((uint8_t *)&(m) + 2) = ((n >> 16U) & 0xFFU); \
*((uint8_t *)&(m) + 1) = ((n >> 8U) & 0xFFU); \
*((uint8_t *)&(m) + 0) = (n & 0xFFU); \
}
#define USB_LONG_FROM_LITTLE_ENDIAN_DATA(n) \
((uint32_t)(((*((uint8_t *)&(n) + 3)) << 24U) | ((*((uint8_t *)&(n) + 2)) << 16U) | \
((*((uint8_t *)&(n) + 1)) << 8U) | ((*((uint8_t *)&(n))) << 0U)))
#define USB_SHORT_TO_LITTLE_ENDIAN_DATA(n, m) \
{ \
*((uint8_t *)&(m) + 1) = ((n >> 8U) & 0xFFU); \
*((uint8_t *)&(m)) = ((n)&0xFFU); \
}
#define USB_SHORT_FROM_LITTLE_ENDIAN_DATA(n) ((uint32_t)(((*((uint8_t *)&(n) + 1)) << 8U) | ((*((uint8_t *)&(n))))))
#endif
/*
* The following MACROs (USB_GLOBAL, USB_BDT, USB_RAM_ADDRESS_ALIGNMENT, etc) are only used for USB device stack.
* The USB device global variables are put into the section m_usb_global and m_usb_bdt or the section
* .bss.m_usb_global and .bss.m_usb_bdt by using the MACRO USB_GLOBAL and USB_BDT. In this way, the USB device
* global variables can be linked into USB dedicated RAM by USB_STACK_USE_DEDICATED_RAM.
* The MACRO USB_STACK_USE_DEDICATED_RAM is used to decide the USB stack uses dedicated RAM or not. The value of
* the marco can be set as 0, USB_STACK_DEDICATED_RAM_TYPE_BDT_GLOBAL, or USB_STACK_DEDICATED_RAM_TYPE_BDT.
* The MACRO USB_STACK_DEDICATED_RAM_TYPE_BDT_GLOBAL means USB device global variables, including USB_BDT and
* USB_GLOBAL, are put into the USB dedicated RAM. This feature can only be enabled when the USB dedicated RAM
* is not less than 2K Bytes.
* The MACRO USB_STACK_DEDICATED_RAM_TYPE_BDT means USB device global variables, only including USB_BDT, are put
* into the USB dedicated RAM, the USB_GLOBAL will be put into .bss section. This feature is used for some SOCs,
* the USB dedicated RAM size is not more than 512 Bytes.
*/
#define USB_STACK_DEDICATED_RAM_TYPE_BDT_GLOBAL 1
#define USB_STACK_DEDICATED_RAM_TYPE_BDT 2
#if defined(__ICCARM__)
#define USB_WEAK_VAR __attribute__((weak))
#define USB_WEAK_FUN __attribute__((weak))
/* disable misra 19.13 */
_Pragma("diag_suppress=Pm120")
#define USB_ALIGN_PRAGMA(x) _Pragma(#x)
_Pragma("diag_default=Pm120")
#define USB_RAM_ADDRESS_ALIGNMENT(n) USB_ALIGN_PRAGMA(data_alignment = n)
_Pragma("diag_suppress=Pm120")
#define USB_LINK_SECTION_PART(str) _Pragma(#str)
#define USB_LINK_SECTION_SUB(sec) USB_LINK_SECTION_PART(location = #sec)
#define USB_LINK_USB_GLOBAL _Pragma("location = \"m_usb_global\"")
#define USB_LINK_USB_BDT _Pragma("location = \"m_usb_bdt\"")
#define USB_LINK_USB_GLOBAL_BSS _Pragma("location = \".bss.m_usb_global\"")
#define USB_LINK_USB_BDT_BSS _Pragma("location = \".bss.m_usb_bdt\"")
_Pragma("diag_default=Pm120")
#define USB_LINK_DMA_NONINIT_DATA _Pragma("location = \"m_usb_dma_noninit_data\"")
#define USB_LINK_NONCACHE_NONINIT_DATA _Pragma("location = \"NonCacheable\"")
#elif defined(__CC_ARM)
#define USB_WEAK_VAR __attribute__((weak))
#define USB_WEAK_FUN __weak
#define USB_RAM_ADDRESS_ALIGNMENT(n) __attribute__((aligned(n)))
#define USB_LINK_SECTION_SUB(sec) __attribute__((section(#sec)))
#define USB_LINK_USB_GLOBAL __attribute__((section("m_usb_global"))) __attribute__((zero_init))
#define USB_LINK_USB_BDT __attribute__((section("m_usb_bdt"))) __attribute__((zero_init))
#define USB_LINK_USB_GLOBAL_BSS __attribute__((section(".bss.m_usb_global"))) __attribute__((zero_init))
#define USB_LINK_USB_BDT_BSS __attribute__((section(".bss.m_usb_bdt"))) __attribute__((zero_init))
#define USB_LINK_DMA_NONINIT_DATA __attribute__((section("m_usb_dma_noninit_data"))) __attribute__((zero_init))
#define USB_LINK_NONCACHE_NONINIT_DATA __attribute__((section("NonCacheable"))) __attribute__((zero_init))
#elif defined(__GNUC__)
#define USB_WEAK_VAR __attribute__((weak))
#define USB_WEAK_FUN __attribute__((weak))
#define USB_RAM_ADDRESS_ALIGNMENT(n) __attribute__((aligned(n)))
#define USB_LINK_SECTION_SUB(sec) __attribute__((section(#sec)))
#define USB_LINK_USB_GLOBAL __attribute__((section("m_usb_global, \"aw\", %nobits @")))
#define USB_LINK_USB_BDT __attribute__((section("m_usb_bdt, \"aw\", %nobits @")))
#define USB_LINK_USB_GLOBAL_BSS __attribute__((section(".bss.m_usb_global, \"aw\", %nobits @")))
#define USB_LINK_USB_BDT_BSS __attribute__((section(".bss.m_usb_bdt, \"aw\", %nobits @")))
#define USB_LINK_DMA_NONINIT_DATA __attribute__((section("m_usb_dma_noninit_data, \"aw\", %nobits @")))
#define USB_LINK_NONCACHE_NONINIT_DATA __attribute__((section("NonCacheable, \"aw\", %nobits @")))
#else
#error The tool-chain is not supported.
#endif
#if (defined(USB_DEVICE_CONFIG_BUFFER_PROPERTY_CACHEABLE) && (USB_DEVICE_CONFIG_BUFFER_PROPERTY_CACHEABLE)) || \
(defined(USB_HOST_CONFIG_BUFFER_PROPERTY_CACHEABLE) && (USB_HOST_CONFIG_BUFFER_PROPERTY_CACHEABLE))
#if ((defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE)) && (defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)))
#define USB_CACHE_LINESIZE MAX(FSL_FEATURE_L2CACHE_LINESIZE_BYTE, FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)
#elif(defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE))
#define USB_CACHE_LINESIZE MAX(FSL_FEATURE_L2CACHE_LINESIZE_BYTE, 0)
#elif(defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE))
#define USB_CACHE_LINESIZE MAX(0, FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)
#else
#define USB_CACHE_LINESIZE 4
#endif
#else
#define USB_CACHE_LINESIZE 4
#endif
#if (((defined(USB_DEVICE_CONFIG_LPCIP3511FS)) && (USB_DEVICE_CONFIG_LPCIP3511FS > 0U)) || \
((defined(USB_DEVICE_CONFIG_LPCIP3511HS)) && (USB_DEVICE_CONFIG_LPCIP3511HS > 0U)))
#define USB_DATA_ALIGN 64
#else
#define USB_DATA_ALIGN 4
#endif
#define USB_DATA_ALIGN_SIZE MAX(USB_CACHE_LINESIZE, USB_DATA_ALIGN)
#define USB_DATA_ALIGN_SIZE_MULTIPLE(n) ((n + USB_DATA_ALIGN_SIZE - 1) & (~(USB_DATA_ALIGN_SIZE - 1)))
#if defined(USB_STACK_USE_DEDICATED_RAM) && (USB_STACK_USE_DEDICATED_RAM == USB_STACK_DEDICATED_RAM_TYPE_BDT_GLOBAL)
#define USB_GLOBAL USB_LINK_USB_GLOBAL
#define USB_BDT USB_LINK_USB_BDT
#if (defined(USB_DEVICE_CONFIG_BUFFER_PROPERTY_CACHEABLE) && (USB_DEVICE_CONFIG_BUFFER_PROPERTY_CACHEABLE)) || \
(defined(USB_HOST_CONFIG_BUFFER_PROPERTY_CACHEABLE) && (USB_HOST_CONFIG_BUFFER_PROPERTY_CACHEABLE))
#define USB_DMA_DATA_NONINIT_SUB USB_LINK_DMA_NONINIT_DATA
#define USB_DMA_DATA_INIT_SUB USB_LINK_SECTION_SUB(m_usb_dma_init_data)
#define USB_CONTROLLER_DATA USB_LINK_NONCACHE_NONINIT_DATA
#else
#define USB_DMA_DATA_NONINIT_SUB
#define USB_DMA_DATA_INIT_SUB
#define USB_CONTROLLER_DATA USB_LINK_USB_GLOBAL
#endif
#elif defined(USB_STACK_USE_DEDICATED_RAM) && (USB_STACK_USE_DEDICATED_RAM == USB_STACK_DEDICATED_RAM_TYPE_BDT)
#define USB_BDT USB_LINK_USB_BDT
#if (defined(USB_DEVICE_CONFIG_BUFFER_PROPERTY_CACHEABLE) && (USB_DEVICE_CONFIG_BUFFER_PROPERTY_CACHEABLE)) || \
(defined(USB_HOST_CONFIG_BUFFER_PROPERTY_CACHEABLE) && (USB_HOST_CONFIG_BUFFER_PROPERTY_CACHEABLE))
#define USB_GLOBAL USB_LINK_DMA_NONINIT_DATA
#define USB_DMA_DATA_NONINIT_SUB USB_LINK_DMA_NONINIT_DATA
#define USB_DMA_DATA_INIT_SUB USB_LINK_SECTION_SUB(m_usb_dma_init_data)
#define USB_CONTROLLER_DATA USB_LINK_NONCACHE_NONINIT_DATA
#else
#define USB_GLOBAL USB_LINK_USB_GLOBAL_BSS
#define USB_DMA_DATA_NONINIT_SUB
#define USB_DMA_DATA_INIT_SUB
#define USB_CONTROLLER_DATA
#endif
#else
#if (defined(USB_DEVICE_CONFIG_BUFFER_PROPERTY_CACHEABLE) && (USB_DEVICE_CONFIG_BUFFER_PROPERTY_CACHEABLE)) || \
(defined(USB_HOST_CONFIG_BUFFER_PROPERTY_CACHEABLE) && (USB_HOST_CONFIG_BUFFER_PROPERTY_CACHEABLE))
#define USB_GLOBAL USB_LINK_DMA_NONINIT_DATA
#define USB_BDT USB_LINK_NONCACHE_NONINIT_DATA
#define USB_DMA_DATA_NONINIT_SUB USB_LINK_DMA_NONINIT_DATA
#define USB_DMA_DATA_INIT_SUB USB_LINK_SECTION_SUB(m_usb_dma_init_data)
#define USB_CONTROLLER_DATA USB_LINK_NONCACHE_NONINIT_DATA
#else
#define USB_GLOBAL USB_LINK_USB_GLOBAL_BSS
#define USB_BDT USB_LINK_USB_BDT_BSS
#define USB_DMA_DATA_NONINIT_SUB
#define USB_DMA_DATA_INIT_SUB
#define USB_CONTROLLER_DATA
#endif
#endif
#define USB_DMA_NONINIT_DATA_ALIGN(n) USB_RAM_ADDRESS_ALIGNMENT(n) USB_DMA_DATA_NONINIT_SUB
#define USB_DMA_INIT_DATA_ALIGN(n) USB_RAM_ADDRESS_ALIGNMENT(n) USB_DMA_DATA_INIT_SUB
#if (defined(USB_DEVICE_CONFIG_BUFFER_PROPERTY_CACHEABLE) && (USB_DEVICE_CONFIG_BUFFER_PROPERTY_CACHEABLE)) || \
(defined(USB_HOST_CONFIG_BUFFER_PROPERTY_CACHEABLE) && (USB_HOST_CONFIG_BUFFER_PROPERTY_CACHEABLE))
#define USB_DMA_DATA_NONCACHEABLE USB_LINK_NONCACHE_NONINIT_DATA
#else
#define USB_DMA_DATA_NONCACHEABLE
#endif
#define USB_GLOBAL_DEDICATED_RAM USB_LINK_USB_GLOBAL
/* #define USB_RAM_ADDRESS_NONCACHEREG_ALIGNMENT(n, var) AT_NONCACHEABLE_SECTION_ALIGN(var, n) */
/* #define USB_RAM_ADDRESS_NONCACHEREG(var) AT_NONCACHEABLE_SECTION(var) */
#endif /* __USB_MISC_H__ */

View File

@ -0,0 +1,296 @@
/*
* Copyright (c) 2015 - 2016, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __USB_SPEC_H__
#define __USB_SPEC_H__
/*******************************************************************************
* Definitions
******************************************************************************/
/* USB speed (the value cannot be changed because EHCI QH use the value directly)*/
#define USB_SPEED_FULL (0x00U)
#define USB_SPEED_LOW (0x01U)
#define USB_SPEED_HIGH (0x02U)
/* Set up packet structure */
typedef struct _usb_setup_struct
{
uint8_t bmRequestType;
uint8_t bRequest;
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
} usb_setup_struct_t;
/* USB standard descriptor endpoint type */
#define USB_ENDPOINT_CONTROL (0x00U)
#define USB_ENDPOINT_ISOCHRONOUS (0x01U)
#define USB_ENDPOINT_BULK (0x02U)
#define USB_ENDPOINT_INTERRUPT (0x03U)
/* USB standard descriptor transfer direction (cannot change the value because iTD use the value directly) */
#define USB_OUT (0U)
#define USB_IN (1U)
/* USB standard descriptor length */
#define USB_DESCRIPTOR_LENGTH_DEVICE (0x12U)
#define USB_DESCRIPTOR_LENGTH_CONFIGURE (0x09U)
#define USB_DESCRIPTOR_LENGTH_INTERFACE (0x09U)
#define USB_DESCRIPTOR_LENGTH_ENDPOINT (0x07U)
#define USB_DESCRIPTOR_LENGTH_DEVICE_QUALITIER (0x0AU)
#define USB_DESCRIPTOR_LENGTH_OTG_DESCRIPTOR (5U)
#define USB_DESCRIPTOR_LENGTH_BOS_DESCRIPTOR (5U)
/* USB Device Capability Type Codes */
#define USB_DESCRIPTOR_TYPE_DEVICE_CAPABILITY_WIRELESS (0x01U)
#define USB_DESCRIPTOR_TYPE_DEVICE_CAPABILITY_USB20_EXTENSION (0x02U)
#define USB_DESCRIPTOR_TYPE_DEVICE_CAPABILITY_SUPERSPEED (0x03U)
/* USB standard descriptor type */
#define USB_DESCRIPTOR_TYPE_DEVICE (0x01U)
#define USB_DESCRIPTOR_TYPE_CONFIGURE (0x02U)
#define USB_DESCRIPTOR_TYPE_STRING (0x03U)
#define USB_DESCRIPTOR_TYPE_INTERFACE (0x04U)
#define USB_DESCRIPTOR_TYPE_ENDPOINT (0x05U)
#define USB_DESCRIPTOR_TYPE_DEVICE_QUALITIER (0x06U)
#define USB_DESCRIPTOR_TYPE_OTHER_SPEED_CONFIGURATION (0x07U)
#define USB_DESCRIPTOR_TYPE_INTERFAACE_POWER (0x08U)
#define USB_DESCRIPTOR_TYPE_OTG (0x09U)
#define USB_DESCRIPTOR_TYPE_INTERFACE_ASSOCIATION (0x0BU)
#define USB_DESCRIPTOR_TYPE_BOS (0x0F)
#define USB_DESCRIPTOR_TYPE_DEVICE_CAPABILITY (0x10)
#define USB_DESCRIPTOR_TYPE_HID (0x21U)
#define USB_DESCRIPTOR_TYPE_HID_REPORT (0x22U)
#define USB_DESCRIPTOR_TYPE_HID_PHYSICAL (0x23U)
/* USB standard request type */
#define USB_REQUEST_TYPE_DIR_MASK (0x80U)
#define USB_REQUEST_TYPE_DIR_SHIFT (7U)
#define USB_REQUEST_TYPE_DIR_OUT (0x00U)
#define USB_REQUEST_TYPE_DIR_IN (0x80U)
#define USB_REQUEST_TYPE_TYPE_MASK (0x60U)
#define USB_REQUEST_TYPE_TYPE_SHIFT (5U)
#define USB_REQUEST_TYPE_TYPE_STANDARD (0U)
#define USB_REQUEST_TYPE_TYPE_CLASS (0x20U)
#define USB_REQUEST_TYPE_TYPE_VENDOR (0x40U)
#define USB_REQUEST_TYPE_RECIPIENT_MASK (0x1FU)
#define USB_REQUEST_TYPE_RECIPIENT_SHIFT (0U)
#define USB_REQUEST_TYPE_RECIPIENT_DEVICE (0x00U)
#define USB_REQUEST_TYPE_RECIPIENT_INTERFACE (0x01U)
#define USB_REQUEST_TYPE_RECIPIENT_ENDPOINT (0x02U)
#define USB_REQUEST_TYPE_RECIPIENT_OTHER (0x03U)
/* USB standard request */
#define USB_REQUEST_STANDARD_GET_STATUS (0x00U)
#define USB_REQUEST_STANDARD_CLEAR_FEATURE (0x01U)
#define USB_REQUEST_STANDARD_SET_FEATURE (0x03U)
#define USB_REQUEST_STANDARD_SET_ADDRESS (0x05U)
#define USB_REQUEST_STANDARD_GET_DESCRIPTOR (0x06U)
#define USB_REQUEST_STANDARD_SET_DESCRIPTOR (0x07U)
#define USB_REQUEST_STANDARD_GET_CONFIGURATION (0x08U)
#define USB_REQUEST_STANDARD_SET_CONFIGURATION (0x09U)
#define USB_REQUEST_STANDARD_GET_INTERFACE (0x0AU)
#define USB_REQUEST_STANDARD_SET_INTERFACE (0x0BU)
#define USB_REQUEST_STANDARD_SYNCH_FRAME (0x0CU)
/* USB standard request GET Status */
#define USB_REQUEST_STANDARD_GET_STATUS_DEVICE_SELF_POWERED_SHIFT (0U)
#define USB_REQUEST_STANDARD_GET_STATUS_DEVICE_REMOTE_WARKUP_SHIFT (1U)
#define USB_REQUEST_STANDARD_GET_STATUS_ENDPOINT_HALT_MASK (0x01U)
#define USB_REQUEST_STANDARD_GET_STATUS_ENDPOINT_HALT_SHIFT (0U)
#define USB_REQUEST_STANDARD_GET_STATUS_OTG_STATUS_SELECTOR (0xF000U)
/* USB standard request CLEAR/SET feature */
#define USB_REQUEST_STANDARD_FEATURE_SELECTOR_ENDPOINT_HALT (0U)
#define USB_REQUEST_STANDARD_FEATURE_SELECTOR_DEVICE_REMOTE_WAKEUP (1U)
#define USB_REQUEST_STANDARD_FEATURE_SELECTOR_DEVICE_TEST_MODE (2U)
#define USB_REQUEST_STANDARD_FEATURE_SELECTOR_B_HNP_ENABLE (3U)
#define USB_REQUEST_STANDARD_FEATURE_SELECTOR_A_HNP_SUPPORT (4U)
#define USB_REQUEST_STANDARD_FEATURE_SELECTOR_A_ALT_HNP_SUPPORT (5U)
/* USB standard descriptor configure bmAttributes */
#define USB_DESCRIPTOR_CONFIGURE_ATTRIBUTE_D7_MASK (0x80U)
#define USB_DESCRIPTOR_CONFIGURE_ATTRIBUTE_D7_SHIFT (7U)
#define USB_DESCRIPTOR_CONFIGURE_ATTRIBUTE_SELF_POWERED_MASK (0x40U)
#define USB_DESCRIPTOR_CONFIGURE_ATTRIBUTE_SELF_POWERED_SHIFT (6U)
#define USB_DESCRIPTOR_CONFIGURE_ATTRIBUTE_REMOTE_WAKEUP_MASK (0x20U)
#define USB_DESCRIPTOR_CONFIGURE_ATTRIBUTE_REMOTE_WAKEUP_SHIFT (5U)
/* USB standard descriptor endpoint bmAttributes */
#define USB_DESCRIPTOR_ENDPOINT_ADDRESS_DIRECTION_MASK (0x80U)
#define USB_DESCRIPTOR_ENDPOINT_ADDRESS_DIRECTION_SHIFT (7U)
#define USB_DESCRIPTOR_ENDPOINT_ADDRESS_DIRECTION_OUT (0U)
#define USB_DESCRIPTOR_ENDPOINT_ADDRESS_DIRECTION_IN (0x80U)
#define USB_DESCRIPTOR_ENDPOINT_ADDRESS_NUMBER_MASK (0x0FU)
#define USB_DESCRIPTOR_ENDPOINT_ADDRESS_NUMBER_SHFIT (0U)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_TYPE_MASK (0x03U)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_NUMBER_SHFIT (0U)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_SYNC_TYPE_MASK (0x0CU)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_SYNC_TYPE_SHFIT (2U)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_SYNC_TYPE_NO_SYNC (0x00U)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_SYNC_TYPE_ASYNC (0x04U)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_SYNC_TYPE_ADAPTIVE (0x08U)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_SYNC_TYPE_SYNC (0x0CU)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_USAGE_TYPE_MASK (0x30U)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_USAGE_TYPE_SHFIT (4U)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_USAGE_TYPE_DATA_ENDPOINT (0x00U)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_USAGE_TYPE_FEEDBACK_ENDPOINT (0x10U)
#define USB_DESCRIPTOR_ENDPOINT_ATTRIBUTE_USAGE_TYPE_IMPLICIT_FEEDBACK_DATA_ENDPOINT (0x20U)
#define USB_DESCRIPTOR_ENDPOINT_MAXPACKETSIZE_SIZE_MASK (0x07FFu)
#define USB_DESCRIPTOR_ENDPOINT_MAXPACKETSIZE_MULT_TRANSACTIONS_MASK (0x1800u)
#define USB_DESCRIPTOR_ENDPOINT_MAXPACKETSIZE_MULT_TRANSACTIONS_SHFIT (11U)
/* USB standard descriptor otg bmAttributes */
#define USB_DESCRIPTOR_OTG_ATTRIBUTES_SRP_MASK (0x01u)
#define USB_DESCRIPTOR_OTG_ATTRIBUTES_HNP_MASK (0x02u)
#define USB_DESCRIPTOR_OTG_ATTRIBUTES_ADP_MASK (0x04u)
/* USB standard descriptor device capability usb20 extension bmAttributes */
#define USB_DESCRIPTOR_DEVICE_CAPABILITY_USB20_EXTENSION_LPM_MASK (0x02U)
#define USB_DESCRIPTOR_DEVICE_CAPABILITY_USB20_EXTENSION_LPM_SHIFT (1U)
#define USB_DESCRIPTOR_DEVICE_CAPABILITY_USB20_EXTENSION_BESL_MASK (0x04U)
#define USB_DESCRIPTOR_DEVICE_CAPABILITY_USB20_EXTENSION_BESL_SHIFT (2U)
/* Language structure */
typedef struct _usb_language
{
uint8_t **string; /* The Strings descriptor array */
uint32_t *length; /* The strings descriptor length array */
uint16_t languageId; /* The language id of current language */
} usb_language_t;
typedef struct _usb_language_list
{
uint8_t *languageString; /* The String 0U pointer */
uint32_t stringLength; /* The String 0U Length */
usb_language_t *languageList; /* The language list */
uint8_t count; /* The language count */
} usb_language_list_t;
typedef struct _usb_descriptor_common
{
uint8_t bLength; /* Size of this descriptor in bytes */
uint8_t bDescriptorType; /* DEVICE Descriptor Type */
uint8_t bData[1]; /* Data */
} usb_descriptor_common_t;
typedef struct _usb_descriptor_device
{
uint8_t bLength; /* Size of this descriptor in bytes */
uint8_t bDescriptorType; /* DEVICE Descriptor Type */
uint8_t bcdUSB[2]; /* UUSB Specification Release Number in Binary-Coded Decimal, e.g. 0x0200U */
uint8_t bDeviceClass; /* Class code */
uint8_t bDeviceSubClass; /* Sub-Class code */
uint8_t bDeviceProtocol; /* Protocol code */
uint8_t bMaxPacketSize0; /* Maximum packet size for endpoint zero */
uint8_t idVendor[2]; /* Vendor ID (assigned by the USB-IF) */
uint8_t idProduct[2]; /* Product ID (assigned by the manufacturer) */
uint8_t bcdDevice[2]; /* 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 the device serial number */
uint8_t bNumConfigurations; /* Number of possible configurations */
} usb_descriptor_device_t;
typedef struct _usb_descriptor_configuration
{
uint8_t bLength; /* Descriptor size in bytes = 9U */
uint8_t bDescriptorType; /* CONFIGURATION type = 2U or 7U */
uint8_t wTotalLength[2]; /* Length of concatenated descriptors */
uint8_t bNumInterfaces; /* Number of interfaces, this configuration. */
uint8_t bConfigurationValue; /* Value to set this configuration. */
uint8_t iConfiguration; /* Index to configuration string */
uint8_t bmAttributes; /* Configuration characteristics */
uint8_t bMaxPower; /* Maximum power from bus, 2 mA units */
} usb_descriptor_configuration_t;
typedef struct _usb_descriptor_interface
{
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bInterfaceNumber;
uint8_t bAlternateSetting;
uint8_t bNumEndpoints;
uint8_t bInterfaceClass;
uint8_t bInterfaceSubClass;
uint8_t bInterfaceProtocol;
uint8_t iInterface;
} usb_descriptor_interface_t;
typedef struct _usb_descriptor_endpoint
{
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bEndpointAddress;
uint8_t bmAttributes;
uint8_t wMaxPacketSize[2];
uint8_t bInterval;
} usb_descriptor_endpoint_t;
typedef struct _usb_descriptor_binary_device_object_store
{
uint8_t bLength; /* Descriptor size in bytes = 5U */
uint8_t bDescriptorType; /* BOS Descriptor type = 0FU*/
uint8_t wTotalLength[2]; /*Length of this descriptor and all of its sub descriptors*/
uint8_t bNumDeviceCaps; /*The number of separate device capability descriptors in the BOS*/
} usb_descriptor_bos_t;
typedef struct _usb_descriptor_usb20_extension
{
uint8_t bLength; /* Descriptor size in bytes = 7U */
uint8_t bDescriptorType; /* DEVICE CAPABILITY Descriptor type = 0x10U*/
uint8_t bDevCapabilityType; /*Length of this descriptor and all of its sub descriptors*/
uint8_t bmAttributes[4]; /*Bitmap encoding of supported device level features.*/
} usb_descriptor_usb20_extension_t;
typedef union _usb_descriptor_union
{
usb_descriptor_common_t common; /* Common descriptor */
usb_descriptor_device_t device; /* Device descriptor */
usb_descriptor_configuration_t configuration; /* Configuration descriptor */
usb_descriptor_interface_t interface; /* Interface descriptor */
usb_descriptor_endpoint_t endpoint; /* Endpoint descriptor */
} usb_descriptor_union_t;
#endif /* __USB_SPEC_H__ */

View File

@ -0,0 +1,240 @@
/*
* Copyright (c) 2015 - 2016, Freescale Semiconductor, Inc.
* Copyright 2016 - 2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include <usb/include/usb.h>
#include "fsl_device_registers.h"
#include <usb/phy/usb_phy.h>
void *USB_EhciPhyGetBase(uint8_t controllerId)
{
void *usbPhyBase = NULL;
#if ((defined FSL_FEATURE_SOC_USBPHY_COUNT) && (FSL_FEATURE_SOC_USBPHY_COUNT > 0U))
uint32_t instance;
uint32_t newinstance = 0;
uint32_t usbphy_base_temp[] = USBPHY_BASE_ADDRS;
uint32_t usbphy_base[] = USBPHY_BASE_ADDRS;
if (controllerId < kUSB_ControllerEhci0)
{
return NULL;
}
controllerId = controllerId - kUSB_ControllerEhci0;
for (instance = 0; instance < (sizeof(usbphy_base_temp) / sizeof(usbphy_base_temp[0])); instance++)
{
if (usbphy_base_temp[instance])
{
usbphy_base[newinstance++] = usbphy_base_temp[instance];
}
}
if (controllerId > newinstance)
{
return NULL;
}
usbPhyBase = (void *)usbphy_base[controllerId];
#endif
return usbPhyBase;
}
/*!
* @brief ehci phy initialization.
*
* This function initialize ehci phy IP.
*
* @param[in] controllerId ehci controller id, please reference to #usb_controller_index_t.
* @param[in] freq the external input clock.
* for example: if the external input clock is 16M, the parameter freq should be 16000000.
*
* @retval kStatus_USB_Success cancel successfully.
* @retval kStatus_USB_Error the freq value is incorrect.
*/
uint32_t USB_EhciPhyInit(uint8_t controllerId, uint32_t freq, usb_phy_config_struct_t *phyConfig)
{
#if ((defined FSL_FEATURE_SOC_USBPHY_COUNT) && (FSL_FEATURE_SOC_USBPHY_COUNT > 0U))
USBPHY_Type *usbPhyBase;
usbPhyBase = (USBPHY_Type *)USB_EhciPhyGetBase(controllerId);
if (NULL == usbPhyBase)
{
return kStatus_USB_Error;
}
#if ((defined FSL_FEATURE_SOC_ANATOP_COUNT) && (FSL_FEATURE_SOC_ANATOP_COUNT > 0U))
ANATOP->HW_ANADIG_REG_3P0.RW =
(ANATOP->HW_ANADIG_REG_3P0.RW &
(~(ANATOP_HW_ANADIG_REG_3P0_OUTPUT_TRG(0x1F) | ANATOP_HW_ANADIG_REG_3P0_ENABLE_ILIMIT_MASK))) |
ANATOP_HW_ANADIG_REG_3P0_OUTPUT_TRG(0x17) | ANATOP_HW_ANADIG_REG_3P0_ENABLE_LINREG_MASK;
ANATOP->HW_ANADIG_USB2_CHRG_DETECT.SET =
ANATOP_HW_ANADIG_USB2_CHRG_DETECT_CHK_CHRG_B_MASK | ANATOP_HW_ANADIG_USB2_CHRG_DETECT_EN_B_MASK;
#endif
#if (defined USB_ANALOG)
USB_ANALOG->INSTANCE[controllerId - kUSB_ControllerEhci0].CHRG_DETECT_SET = USB_ANALOG_CHRG_DETECT_CHK_CHRG_B(1) | USB_ANALOG_CHRG_DETECT_EN_B(1);
#endif
#if ((!(defined FSL_FEATURE_SOC_CCM_ANALOG_COUNT)) && (!(defined FSL_FEATURE_SOC_ANATOP_COUNT)))
usbPhyBase->TRIM_OVERRIDE_EN = 0x001fU; /* override IFR value */
#endif
usbPhyBase->CTRL |= USBPHY_CTRL_SET_ENUTMILEVEL2_MASK; /* support LS device. */
usbPhyBase->CTRL |= USBPHY_CTRL_SET_ENUTMILEVEL3_MASK; /* support external FS Hub with LS device connected. */
/* PWD register provides overall control of the PHY power state */
usbPhyBase->PWD = 0U;
/* Decode to trim the nominal 17.78mA current source for the High Speed TX drivers on USB_DP and USB_DM. */
usbPhyBase->TX =
((usbPhyBase->TX & (~(USBPHY_TX_D_CAL_MASK | USBPHY_TX_TXCAL45DM_MASK | USBPHY_TX_TXCAL45DP_MASK))) |
(USBPHY_TX_D_CAL(phyConfig->D_CAL) | USBPHY_TX_TXCAL45DP(phyConfig->TXCAL45DP) |
USBPHY_TX_TXCAL45DM(phyConfig->TXCAL45DM)));
#endif
return kStatus_USB_Success;
}
/*!
* @brief ehci phy initialization for suspend and resume.
*
* This function initialize ehci phy IP for suspend and resume.
*
* @param[in] controllerId ehci controller id, please reference to #usb_controller_index_t.
* @param[in] freq the external input clock.
* for example: if the external input clock is 16M, the parameter freq should be 16000000.
*
* @retval kStatus_USB_Success cancel successfully.
* @retval kStatus_USB_Error the freq value is incorrect.
*/
uint32_t USB_EhciLowPowerPhyInit(uint8_t controllerId, uint32_t freq, usb_phy_config_struct_t *phyConfig)
{
#if ((defined FSL_FEATURE_SOC_USBPHY_COUNT) && (FSL_FEATURE_SOC_USBPHY_COUNT > 0U))
USBPHY_Type *usbPhyBase;
usbPhyBase = (USBPHY_Type *)USB_EhciPhyGetBase(controllerId);
if (NULL == usbPhyBase)
{
return kStatus_USB_Error;
}
#if ((!(defined FSL_FEATURE_SOC_CCM_ANALOG_COUNT)) && (!(defined FSL_FEATURE_SOC_ANATOP_COUNT)))
usbPhyBase->TRIM_OVERRIDE_EN = 0x001fU; /* override IFR value */
#endif
#if ((defined USBPHY_CTRL_AUTORESUME_EN_MASK) && (USBPHY_CTRL_AUTORESUME_EN_MASK > 0U))
usbPhyBase->CTRL |= USBPHY_CTRL_AUTORESUME_EN_MASK;
#else
usbPhyBase->CTRL |= USBPHY_CTRL_ENAUTO_PWRON_PLL_MASK;
#endif
usbPhyBase->CTRL |= USBPHY_CTRL_ENAUTOCLR_CLKGATE_MASK | USBPHY_CTRL_ENAUTOCLR_PHY_PWD_MASK;
usbPhyBase->CTRL |= USBPHY_CTRL_SET_ENUTMILEVEL2_MASK; /* support LS device. */
usbPhyBase->CTRL |= USBPHY_CTRL_SET_ENUTMILEVEL3_MASK; /* support external FS Hub with LS device connected. */
/* PWD register provides overall control of the PHY power state */
usbPhyBase->PWD = 0U;
#if ((!(defined FSL_FEATURE_SOC_CCM_ANALOG_COUNT)) && (!(defined FSL_FEATURE_SOC_ANATOP_COUNT)))
/* now the 480MHz USB clock is up, then configure fractional divider after PLL with PFD
* pfd clock = 480MHz*18/N, where N=18~35
* Please note that USB1PFDCLK has to be less than 180MHz for RUN or HSRUN mode
*/
usbPhyBase->ANACTRL |= USBPHY_ANACTRL_PFD_FRAC(24); /* N=24 */
usbPhyBase->ANACTRL |= USBPHY_ANACTRL_PFD_CLK_SEL(1); /* div by 4 */
usbPhyBase->ANACTRL &= ~USBPHY_ANACTRL_DEV_PULLDOWN_MASK;
usbPhyBase->ANACTRL &= ~USBPHY_ANACTRL_PFD_CLKGATE_MASK;
while (!(usbPhyBase->ANACTRL & USBPHY_ANACTRL_PFD_STABLE_MASK))
{
}
#endif
/* Decode to trim the nominal 17.78mA current source for the High Speed TX drivers on USB_DP and USB_DM. */
usbPhyBase->TX =
((usbPhyBase->TX & (~(USBPHY_TX_D_CAL_MASK | USBPHY_TX_TXCAL45DM_MASK | USBPHY_TX_TXCAL45DP_MASK))) |
(USBPHY_TX_D_CAL(phyConfig->D_CAL) | USBPHY_TX_TXCAL45DP(phyConfig->TXCAL45DP) |
USBPHY_TX_TXCAL45DM(phyConfig->TXCAL45DM)));
#endif
return kStatus_USB_Success;
}
/*!
* @brief ehci phy de-initialization.
*
* This function de-initialize ehci phy IP.
*
* @param[in] controllerId ehci controller id, please reference to #usb_controller_index_t.
*/
void USB_EhciPhyDeinit(uint8_t controllerId)
{
#if ((defined FSL_FEATURE_SOC_USBPHY_COUNT) && (FSL_FEATURE_SOC_USBPHY_COUNT > 0U))
USBPHY_Type *usbPhyBase;
usbPhyBase = (USBPHY_Type *)USB_EhciPhyGetBase(controllerId);
if (NULL == usbPhyBase)
{
return;
}
#if ((!(defined FSL_FEATURE_SOC_CCM_ANALOG_COUNT)) && (!(defined FSL_FEATURE_SOC_ANATOP_COUNT)))
usbPhyBase->PLL_SIC &= ~USBPHY_PLL_SIC_PLL_POWER_MASK; /* power down PLL */
usbPhyBase->PLL_SIC &= ~USBPHY_PLL_SIC_PLL_EN_USB_CLKS_MASK; /* disable USB clock output from USB PHY PLL */
#endif
usbPhyBase->CTRL |= USBPHY_CTRL_CLKGATE_MASK; /* set to 1U to gate clocks */
#endif
}
/*!
* @brief ehci phy disconnect detection enable or disable.
*
* This function enable/disable host ehci disconnect detection.
*
* @param[in] controllerId ehci controller id, please reference to #usb_controller_index_t.
* @param[in] enable
* 1U - enable;
* 0U - disable;
*/
void USB_EhcihostPhyDisconnectDetectCmd(uint8_t controllerId, uint8_t enable)
{
#if ((defined FSL_FEATURE_SOC_USBPHY_COUNT) && (FSL_FEATURE_SOC_USBPHY_COUNT > 0U))
USBPHY_Type *usbPhyBase;
usbPhyBase = (USBPHY_Type *)USB_EhciPhyGetBase(controllerId);
if (NULL == usbPhyBase)
{
return;
}
if (enable)
{
usbPhyBase->CTRL |= USBPHY_CTRL_ENHOSTDISCONDETECT_MASK;
}
else
{
usbPhyBase->CTRL &= (~USBPHY_CTRL_ENHOSTDISCONDETECT_MASK);
}
#endif
}

View File

@ -0,0 +1,113 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016 - 2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __USB_PHY_H__
#define __USB_PHY_H__
/*******************************************************************************
* Definitions
******************************************************************************/
typedef struct _usb_phy_config_struct
{
uint8_t D_CAL; /* Decode to trim the nominal 17.78mA current source */
uint8_t TXCAL45DP; /* Decode to trim the nominal 45-Ohm series termination resistance to the USB_DP output pin */
uint8_t TXCAL45DM; /* Decode to trim the nominal 45-Ohm series termination resistance to the USB_DM output pin */
} usb_phy_config_struct_t;
#if defined(__cplusplus)
extern "C" {
#endif
/*******************************************************************************
* API
******************************************************************************/
/*!
* @brief EHCI PHY get USB phy bass address.
*
* This function is used to get USB phy bass address.
*
* @param[in] controllerId EHCI controller ID; See the #usb_controller_index_t.
*
* @retval USB phy bass address.
*/
extern void *USB_EhciPhyGetBase(uint8_t controllerId);
/*!
* @brief EHCI PHY initialization.
*
* This function initializes the EHCI PHY IP.
*
* @param[in] controllerId EHCI controller ID; See the #usb_controller_index_t.
* @param[in] freq The external input clock.
*
* @retval kStatus_USB_Success Cancel successfully.
* @retval kStatus_USB_Error The freq value is incorrect.
*/
extern uint32_t USB_EhciPhyInit(uint8_t controllerId, uint32_t freq, usb_phy_config_struct_t *phyConfig);
/*!
* @brief ehci phy initialization for suspend and resume.
*
* This function initialize ehci phy IP for suspend and resume.
*
* @param[in] controllerId ehci controller id, please reference to #usb_controller_index_t.
* @param[in] freq the external input clock.
* for example: if the external input clock is 16M, the parameter freq should be 16000000.
*
* @retval kStatus_USB_Success cancel successfully.
* @retval kStatus_USB_Error the freq value is incorrect.
*/
extern uint32_t USB_EhciLowPowerPhyInit(uint8_t controllerId, uint32_t freq, usb_phy_config_struct_t *phyConfig);
/*!
* @brief EHCI PHY deinitialization.
*
* This function deinitializes the EHCI PHY IP.
*
* @param[in] controllerId EHCI controller ID; See #usb_controller_index_t.
*/
extern void USB_EhciPhyDeinit(uint8_t controllerId);
/*!
* @brief EHCI PHY disconnect detection enable or disable.
*
* This function enable/disable the host EHCI disconnect detection.
*
* @param[in] controllerId EHCI controller ID; See #usb_controller_index_t.
* @param[in] enable
* 1U - enable;
* 0U - disable;
*/
extern void USB_EhcihostPhyDisconnectDetectCmd(uint8_t controllerId, uint8_t enable);
#if defined(__cplusplus)
}
#endif
#endif /* __USB_PHY_H__ */