ext: mcux: Import NXP SDK USB EHCI controller driver to ext/ directory.

Put the driver files to ext/hal/nxp/mcux/middleware/usb/device.

Signed-off-by: Mark Wang <yichang.wang@nxp.com>
This commit is contained in:
Mark Wang 2019-05-05 13:17:50 +08:00 committed by Maureen Helm
commit 8487a1eb2c
12 changed files with 3174 additions and 0 deletions

View file

@ -32,6 +32,11 @@ add_subdirectory(boards)
add_subdirectory(components)
add_subdirectory(drivers)
add_subdirectory_ifdef(
CONFIG_USB
middleware/usb
)
add_subdirectory_ifdef(
CONFIG_IEEE802154_KW41Z
middleware/wireless/framework_5.3.3

View file

@ -97,4 +97,9 @@ config HAS_MCUX_TRNG
Set if the true random number generator (TRNG) module is present in
the SoC.
config HAS_MCUX_USB_EHCI
bool
help
Set if the USB controller EHCI module is present in the SoC.
endif # HAS_MCUX

View file

@ -85,3 +85,5 @@ Patch List:
* Automatically enable ENET_ENHANCEDBUFFERDESCRIPTOR_MODE in HAL if gPTP
support is enabled.
* Add USB device controller drivers, the drivers are based on MCUXpresso SDK release tag REL_2.5.0_REL9_RFP_RC3_7_1.

View file

@ -0,0 +1,15 @@
#
# Copyright (c) 2019, NXP
#
# SPDX-License-Identifier: Apache-2.0
#
zephyr_include_directories(./include)
add_subdirectory_ifdef(
CONFIG_USB
device
)
add_subdirectory_ifdef(
CONFIG_USB
phy
)

View file

@ -0,0 +1,9 @@
#
# Copyright (c) 2019, NXP
#
# SPDX-License-Identifier: Apache-2.0
#
zephyr_include_directories(.)
zephyr_include_directories(./port/zephyr)
zephyr_sources_ifdef(CONFIG_USB_DC_NXP_EHCI usb_device_ehci.c)

View file

@ -0,0 +1,340 @@
/*
* Copyright 2018 - 2019 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef __USB_DC_MCUX_H__
#define __USB_DC_MCUX_H__
#include <usb/usb_dc.h>
#include "usb_spec.h"
/******************************************************************************
* Definitions
*****************************************************************************/
/* EHCI instance count */
#ifdef CONFIG_USB_DC_NXP_EHCI
#define USB_DEVICE_CONFIG_EHCI (1U)
#else
#define USB_DEVICE_CONFIG_EHCI (0U)
#endif
/* Macro to define controller handle */
typedef void *usb_device_handle;
#define usb_device_controller_handle usb_device_handle
/* controller driver do the ZLP for controler transfer automatically or not */
#define USB_DEVICE_CONTROLLER_AUTO_CONTROL_TRANSFER_ZLP (0)
/* endpoint related macros */
#define EP0_MAX_PACKET_SIZE 64
#define EP0_OUT 0
#define EP0_IN 0x80
/* USB endpoint mask */
#define USB_ENDPOINT_NUMBER_MASK (0x0FU)
/* The setup packet size of USB control transfer. */
#define USB_SETUP_PACKET_SIZE (8U)
/* enter critical macros */
#define USB_OSA_SR_ALLOC() int usbOsaCurrentSr
#define USB_OSA_ENTER_CRITICAL() usbOsaCurrentSr = irq_lock()
#define USB_OSA_EXIT_CRITICAL() irq_unlock(usbOsaCurrentSr)
/* Control endpoint index */
#define USB_CONTROL_ENDPOINT (0U)
/* Default invalid value or the endpoint callback length of cancelled transfer*/
#define USB_UNINITIALIZED_VAL_32 (0xFFFFFFFFU)
/* NXP SDK USB controller driver configuration macros */
#define USB_BDT
#define USB_GLOBAL
#define USB_DATA_ALIGN_SIZE 4
#define USB_RAM_ADDRESS_ALIGNMENT(n) __aligned(n)
/* EHCI */
#if defined(CONFIG_NOCACHE_MEMORY)
#define USB_CONTROLLER_DATA __nocache
#else
#define USB_CONTROLLER_DATA
#endif
/* How many the DTD are supported. */
#define USB_DEVICE_CONFIG_EHCI_MAX_DTD (16U)
/* Control endpoint maxPacketSize */
#define USB_CONTROL_MAX_PACKET_SIZE (64U)
/* Whether device is self power. 1U supported, 0U not supported */
#define USB_DEVICE_CONFIG_SELF_POWER (1U)
/* USB controller ID */
typedef enum _usb_controller_index {
/* KHCI 0U */
kUSB_ControllerKhci0 = 0U,
/* KHCI 1U, Currently, there are no platforms which have two KHCI IPs,
* this is reserved to be used in the future.
*/
kUSB_ControllerKhci1 = 1U,
/* EHCI 0U */
kUSB_ControllerEhci0 = 2U,
/* EHCI 1U, Currently, there are no platforms which have two EHCI IPs,
* this is reserved to be used in the future.
*/
kUSB_ControllerEhci1 = 3U,
/* LPC USB IP3511 FS controller 0 */
kUSB_ControllerLpcIp3511Fs0 = 4U,
/* 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_ControllerLpcIp3511Fs1 = 5U,
/* LPC USB IP3511 HS controller 0 */
kUSB_ControllerLpcIp3511Hs0 = 6U,
/* 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_ControllerLpcIp3511Hs1 = 7U,
} usb_controller_index_t;
/* Control type for controller */
typedef enum _usb_device_control_type {
/* Enable the device functionality */
kUSB_DeviceControlRun = 0U,
/* Disable the device functionality */
kUSB_DeviceControlStop,
/* Initialize a specified endpoint */
kUSB_DeviceControlEndpointInit,
/* De-initialize a specified endpoint */
kUSB_DeviceControlEndpointDeinit,
/* Stall a specified endpoint */
kUSB_DeviceControlEndpointStall,
/* Unstall a specified endpoint */
kUSB_DeviceControlEndpointUnstall,
/* Get device status */
kUSB_DeviceControlGetDeviceStatus,
/* Get endpoint status */
kUSB_DeviceControlGetEndpointStatus,
/* Set device address */
kUSB_DeviceControlSetDeviceAddress,
/* Get current frame */
kUSB_DeviceControlGetSynchFrame,
/* Drive controller to generate a resume signal in USB bus */
kUSB_DeviceControlResume,
/* Drive controller to generate a LPM resume signal in USB bus */
kUSB_DeviceControlSleepResume,
/* Drive controller to enetr into suspend mode */
kUSB_DeviceControlSuspend,
/* Drive controller to enetr into sleep mode */
kUSB_DeviceControlSleep,
/* Set controller to default status */
kUSB_DeviceControlSetDefaultStatus,
/* Get current speed */
kUSB_DeviceControlGetSpeed,
/* Get OTG status */
kUSB_DeviceControlGetOtgStatus,
/* Set OTG status */
kUSB_DeviceControlSetOtgStatus,
/* Drive xCHI into test mode */
kUSB_DeviceControlSetTestMode,
/* Get flag of LPM Remote Wake-up Enabled by USB host. */
kUSB_DeviceControlGetRemoteWakeUp,
#if (defined(USB_DEVICE_CHARGER_DETECT_ENABLE) && \
(USB_DEVICE_CHARGER_DETECT_ENABLE > 0U))
kUSB_DeviceControlDcdInitModule,
kUSB_DeviceControlDcdDeinitModule,
#endif
} usb_device_control_type_t;
/* Available notify types for device notification */
typedef enum _usb_device_notification {
/* Reset signal detected */
kUSB_DeviceNotifyBusReset = 0x10U,
/* Suspend signal detected */
kUSB_DeviceNotifySuspend,
/* Resume signal detected */
kUSB_DeviceNotifyResume,
/* LPM signal detected */
kUSB_DeviceNotifyLPMSleep,
/* Resume signal detected */
kUSB_DeviceNotifyLPMResume,
/* Errors happened in bus */
kUSB_DeviceNotifyError,
/* Device disconnected from a host */
kUSB_DeviceNotifyDetach,
/* Device connected to a host */
kUSB_DeviceNotifyAttach,
#if (defined(USB_DEVICE_CHARGER_DETECT_ENABLE) && \
(USB_DEVICE_CHARGER_DETECT_ENABLE > 0U))
/* Device charger detection timeout */
kUSB_DeviceNotifyDcdTimeOut,
/* Device charger detection unknown port type */
kUSB_DeviceNotifyDcdUnknownPortType,
/* The SDP facility is detected */
kUSB_DeviceNotifySDPDetected,
/* The charging port is detected */
kUSB_DeviceNotifyChargingPortDetected,
/* The CDP facility is detected */
kUSB_DeviceNotifyChargingHostDetected,
/* The DCP facility is detected */
kUSB_DeviceNotifyDedicatedChargerDetected,
#endif
} usb_device_notification_t;
/* USB error code */
typedef enum _usb_status {
/* Success */
kStatus_USB_Success = 0x00U,
/* Failed */
kStatus_USB_Error,
/* Busy */
kStatus_USB_Busy,
/* Invalid handle */
kStatus_USB_InvalidHandle,
/* Invalid parameter */
kStatus_USB_InvalidParameter,
/* Invalid request */
kStatus_USB_InvalidRequest,
/* Controller cannot be found */
kStatus_USB_ControllerNotFound,
/* Invalid controller interface */
kStatus_USB_InvalidControllerInterface,
/* Configuration is not supported */
kStatus_USB_NotSupported,
/* Enumeration get configuration retry */
kStatus_USB_Retry,
/* Transfer stalled */
kStatus_USB_TransferStall,
/* Transfer failed */
kStatus_USB_TransferFailed,
/* Allocation failed */
kStatus_USB_AllocFail,
/* Insufficient swap buffer for KHCI */
kStatus_USB_LackSwapBuffer,
/* The transfer cancelled */
kStatus_USB_TransferCancel,
/* Allocate bandwidth failed */
kStatus_USB_BandwidthFail,
/* For MSD, the CSW status means fail */
kStatus_USB_MSDStatusFail,
kStatus_USB_EHCIAttached,
kStatus_USB_EHCIDetached,
} usb_status_t;
/* Device notification message structure */
typedef struct _usb_device_callback_message_struct {
u8_t *buffer; /* Transferred buffer */
u32_t length; /* Transferred data length */
u8_t code; /* Notification code */
u8_t isSetup; /* Is in a setup phase */
} usb_device_callback_message_struct_t;
typedef struct usb_ep_ctrl_data {
usb_device_callback_message_struct_t transfer_message;
struct k_mem_block block;
usb_dc_ep_callback callback;
u16_t ep_mps;
u8_t ep_type;
u8_t ep_enabled : 1;
u8_t ep_occupied : 1;
} usb_ep_ctrl_data_t;
/* USB device controller initialization function typedef */
typedef usb_status_t (*usb_device_controller_init_t)(u8_t controllerId,
usb_device_handle handle,
usb_device_controller_handle *controllerHandle);
/* USB device controller de-initialization function typedef */
typedef usb_status_t (*usb_device_controller_deinit_t)(usb_device_controller_handle controllerHandle);
/* USB device controller send data function typedef */
typedef usb_status_t (*usb_device_controller_send_t)(usb_device_controller_handle controllerHandle,
u8_t endpointAddress,
u8_t *buffer,
u32_t length);
/* USB device controller receive data function typedef */
typedef usb_status_t (*usb_device_controller_recv_t)(usb_device_controller_handle controllerHandle,
u8_t endpointAddress,
u8_t *buffer,
u32_t length);
/* 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,
u8_t endpointAddress);
/* 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);
/* USB device controller interface structure */
typedef struct _usb_device_controller_interface_struct {
/* Controller initialization */
usb_device_controller_init_t deviceInit;
/* Controller de-initialization */
usb_device_controller_deinit_t deviceDeinit;
/* Controller send data */
usb_device_controller_send_t deviceSend;
/* Controller receive data */
usb_device_controller_recv_t deviceRecv;
/* Controller cancel transfer */
usb_device_controller_cancel_t deviceCancel;
/* Controller control */
usb_device_controller_control_t deviceControl;
} usb_device_controller_interface_struct_t;
typedef struct _usb_device_struct {
/* Controller handle */
usb_device_controller_handle controllerHandle;
/* Controller interface handle */
const usb_device_controller_interface_struct_t *interface;
usb_dc_status_callback status_callback;
usb_ep_ctrl_data_t *eps;
bool attached;
/* Current device address */
u8_t address;
/* Controller ID */
u8_t controllerId;
/* Current device state */
u8_t state;
/* Is doing device reset or not */
u8_t isResetting;
u8_t setupDataStage;
} usb_device_struct_t;
/* Endpoint status structure */
typedef struct _usb_device_endpoint_status_struct {
/* Endpoint address */
u8_t endpointAddress;
/* Endpoint status : idle or stalled */
u16_t endpointStatus;
} usb_device_endpoint_status_struct_t;
/* Defines endpoint state */
typedef enum _usb_endpoint_status {
/* Endpoint state, idle*/
kUSB_DeviceEndpointStateIdle = 0U,
/* Endpoint state, stalled*/
kUSB_DeviceEndpointStateStalled,
} usb_device_endpoint_status_t;
/* Endpoint initialization structure */
typedef struct _usb_device_endpoint_init_struct {
/* Endpoint maximum packet size */
u16_t maxPacketSize;
/* Endpoint address*/
u8_t endpointAddress;
/* Endpoint transfer type*/
u8_t transferType;
/* ZLT flag*/
u8_t zlt;
} usb_device_endpoint_init_struct_t;
#endif /* __USB_DC_MCUX_H__ */

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,303 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef __USB_DEVICE_EHCI_H__
#define __USB_DEVICE_EHCI_H__
/*!
* @addtogroup usb_device_controller_ehci_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
#define USB_DEVICE_CONFIG_ENDPOINTS (DT_USBD_MCUX_EHCI_NUM_BIDIR_EP / 2)
/*! @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)
#define USB_DEVICE_MAX_TRANSFER_PRIME_TIMES (10000000U) /* The max prime times of EPPRIME, if still doesn't take effect, means status has been reset*/
/* 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 zlt: 1;
uint32_t : 30;
} 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;
/*! @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,300 @@
/*
* Copyright (c) 2015 - 2016, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#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)
#define USB_SPEED_SUPER (0x04U)
/* 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_ENDPOINT_COMPANION (0x06U)
#define USB_DESCRIPTOR_LENGTH_DEVICE_QUALITIER (0x0AU)
#define USB_DESCRIPTOR_LENGTH_OTG_DESCRIPTOR (5U)
#define USB_DESCRIPTOR_LENGTH_BOS_DESCRIPTOR (5U)
#define USB_DESCRIPTOR_LENGTH_DEVICE_CAPABILITY_USB20_EXTENSION (0x07U)
#define USB_DESCRIPTOR_LENGTH_DEVICE_CAPABILITY_SUPERSPEED (0x0AU)
/* 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)
#define USB_DESCRIPTOR_TYPE_ENDPOINT_COMPANION (0x30U)
/* 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_endpoint_companion
{
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bMaxBurst;
uint8_t bmAttributes;
uint8_t wBytesPerInterval[2];
} usb_descriptor_endpoint_companion_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 struct _usb_descriptor_super_speed_device_capability
{
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDevCapabilityType;
uint8_t bmAttributes;
uint8_t wSpeedsSupported[2];
uint8_t bFunctionalitySupport;
uint8_t bU1DevExitLat;
uint8_t wU2DevExitLat[2];
} usb_bos_device_capability_susperspeed_desc_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_endpoint_companion_t endpointCompanion; /* Endpoint companion descriptor */
} usb_descriptor_union_t;
#endif /* __USB_SPEC_H__ */

View file

@ -0,0 +1,8 @@
#
# Copyright (c) 2019, NXP
#
# SPDX-License-Identifier: Apache-2.0
#
zephyr_include_directories(.)
zephyr_sources_ifdef(CONFIG_USB_DC_NXP_EHCI usb_phy.c)

View file

@ -0,0 +1,235 @@
/*
* Copyright (c) 2015 - 2016, Freescale Semiconductor, Inc.
* Copyright 2016 - 2017 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "usb_dc_mcux.h"
#include "fsl_device_registers.h"
#include "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;
}
if ((controllerId == kUSB_ControllerEhci0) || (controllerId == kUSB_ControllerEhci1))
{
controllerId = controllerId - kUSB_ControllerEhci0;
}
else if ((controllerId == kUSB_ControllerLpcIp3511Hs0) || (controllerId == kUSB_ControllerLpcIp3511Hs1))
{
controllerId = controllerId - kUSB_ControllerLpcIp3511Hs0;
}
else
{
}
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;
if ((kUSB_ControllerLpcIp3511Hs0 == controllerId) || (kUSB_ControllerLpcIp3511Hs0 == controllerId))
{
usbPhyBase->CTRL_SET = USBPHY_CTRL_SET_ENAUTOCLR_CLKGATE_MASK;
usbPhyBase->CTRL_SET = USBPHY_CTRL_SET_ENAUTOCLR_PHY_PWD_MASK;
}
if (NULL != phyConfig)
{
/* 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,91 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016 - 2017 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#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__ */