提交 00fa2e2d 编写于 作者: T tyustli

solve gcc build err

上级 8d0ca475
......@@ -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
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')
/*
* 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 ************************/
此差异已折叠。
此差异已折叠。
/*
* 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__ */
/*
* 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__ */
此差异已折叠。
此差异已折叠。
/*
* 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_ */
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册