mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 19:40:31 +03:00
STM32F4: Libraries
This commit is contained in:
parent
55d8eb57be
commit
d4e96ba8e7
206 changed files with 141406 additions and 0 deletions
202
lib/main/STM32_USB_OTG_Driver/src/usb_bsp_template.c
Normal file
202
lib/main/STM32_USB_OTG_Driver/src/usb_bsp_template.c
Normal file
|
@ -0,0 +1,202 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usb_bsp.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief This file is responsible to offer board support package and is
|
||||
* configurable by user.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usb_bsp.h"
|
||||
|
||||
/** @addtogroup USB_OTG_DRIVER
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup USB_BSP
|
||||
* @brief This file is responsible to offer board support package
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup USB_BSP_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_BSP_Private_TypesDefinitions
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
/** @defgroup USB_BSP_Private_Macros
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup USBH_BSP_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup USBH_BSP_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup USB_BSP_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_BSP_Init
|
||||
* Initilizes BSP configurations
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
|
||||
void USB_OTG_BSP_Init(void)
|
||||
{
|
||||
|
||||
}
|
||||
/**
|
||||
* @brief USB_OTG_BSP_EnableInterrupt
|
||||
* Enabele USB Global interrupt
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void USB_OTG_BSP_EnableInterrupt(void)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief BSP_Drive_VBUS
|
||||
* Drives the Vbus signal through IO
|
||||
* @param speed : Full, Low
|
||||
* @param state : VBUS states
|
||||
* @retval None
|
||||
*/
|
||||
|
||||
void USB_OTG_BSP_DriveVBUS(uint32_t speed, uint8_t state)
|
||||
{
|
||||
(void)speed;
|
||||
(void)state;
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_BSP_ConfigVBUS
|
||||
* Configures the IO for the Vbus and OverCurrent
|
||||
* @param Speed : Full, Low
|
||||
* @retval None
|
||||
*/
|
||||
|
||||
void USB_OTG_BSP_ConfigVBUS(uint32_t speed)
|
||||
{
|
||||
(void)speed;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_BSP_TimeInit
|
||||
* Initialises delay unit Systick timer /Timer2
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void USB_OTG_BSP_TimeInit ( void )
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_BSP_uDelay
|
||||
* This function provides delay time in micro sec
|
||||
* @param usec : Value of delay required in micro sec
|
||||
* @retval None
|
||||
*/
|
||||
void USB_OTG_BSP_uDelay (const uint32_t usec)
|
||||
{
|
||||
|
||||
uint32_t count = 0;
|
||||
const uint32_t utime = (120 * usec / 7);
|
||||
do
|
||||
{
|
||||
if ( ++count > utime )
|
||||
{
|
||||
return ;
|
||||
}
|
||||
}
|
||||
while (1);
|
||||
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_BSP_mDelay
|
||||
* This function provides delay time in milli sec
|
||||
* @param msec : Value of delay required in milli sec
|
||||
* @retval None
|
||||
*/
|
||||
void USB_OTG_BSP_mDelay (const uint32_t msec)
|
||||
{
|
||||
|
||||
USB_OTG_BSP_uDelay(msec * 1000);
|
||||
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_BSP_TimerIRQ
|
||||
* Time base IRQ
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
|
||||
void USB_OTG_BSP_TimerIRQ (void)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
2187
lib/main/STM32_USB_OTG_Driver/src/usb_core.c
Normal file
2187
lib/main/STM32_USB_OTG_Driver/src/usb_core.c
Normal file
File diff suppressed because it is too large
Load diff
472
lib/main/STM32_USB_OTG_Driver/src/usb_dcd.c
Normal file
472
lib/main/STM32_USB_OTG_Driver/src/usb_dcd.c
Normal file
|
@ -0,0 +1,472 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usb_dcd.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief Peripheral Device Interface Layer
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usb_dcd.h"
|
||||
#include "usb_bsp.h"
|
||||
|
||||
|
||||
/** @addtogroup USB_OTG_DRIVER
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup USB_DCD
|
||||
* @brief This file is the interface between EFSL ans Host mass-storage class
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_DCD_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_DCD_Private_TypesDefinitions
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/** @defgroup USB_DCD_Private_Macros
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_DCD_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_DCD_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_DCD_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
|
||||
void DCD_Init(USB_OTG_CORE_HANDLE *pdev ,
|
||||
USB_OTG_CORE_ID_TypeDef coreID)
|
||||
{
|
||||
uint32_t i;
|
||||
USB_OTG_EP *ep;
|
||||
|
||||
USB_OTG_SelectCore (pdev , coreID);
|
||||
|
||||
pdev->dev.device_status = USB_OTG_DEFAULT;
|
||||
pdev->dev.device_address = 0;
|
||||
|
||||
/* Init ep structure */
|
||||
for (i = 0; i < pdev->cfg.dev_endpoints ; i++)
|
||||
{
|
||||
ep = &pdev->dev.in_ep[i];
|
||||
/* Init ep structure */
|
||||
ep->is_in = 1;
|
||||
ep->num = i;
|
||||
ep->tx_fifo_num = i;
|
||||
/* Control until ep is actvated */
|
||||
ep->type = EP_TYPE_CTRL;
|
||||
ep->maxpacket = USB_OTG_MAX_EP0_SIZE;
|
||||
ep->xfer_buff = 0;
|
||||
ep->xfer_len = 0;
|
||||
}
|
||||
|
||||
for (i = 0; i < pdev->cfg.dev_endpoints; i++)
|
||||
{
|
||||
ep = &pdev->dev.out_ep[i];
|
||||
/* Init ep structure */
|
||||
ep->is_in = 0;
|
||||
ep->num = i;
|
||||
ep->tx_fifo_num = i;
|
||||
/* Control until ep is activated */
|
||||
ep->type = EP_TYPE_CTRL;
|
||||
ep->maxpacket = USB_OTG_MAX_EP0_SIZE;
|
||||
ep->xfer_buff = 0;
|
||||
ep->xfer_len = 0;
|
||||
}
|
||||
|
||||
USB_OTG_DisableGlobalInt(pdev);
|
||||
|
||||
/*Init the Core (common init.) */
|
||||
USB_OTG_CoreInit(pdev);
|
||||
|
||||
|
||||
/* Force Device Mode*/
|
||||
USB_OTG_SetCurrentMode(pdev, DEVICE_MODE);
|
||||
|
||||
/* Init Device */
|
||||
USB_OTG_CoreInitDev(pdev);
|
||||
|
||||
|
||||
/* Enable USB Global interrupt */
|
||||
USB_OTG_EnableGlobalInt(pdev);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Configure an EP
|
||||
* @param pdev : Device instance
|
||||
* @param epdesc : Endpoint Descriptor
|
||||
* @retval : status
|
||||
*/
|
||||
uint32_t DCD_EP_Open(USB_OTG_CORE_HANDLE *pdev ,
|
||||
uint8_t ep_addr,
|
||||
uint16_t ep_mps,
|
||||
uint8_t ep_type)
|
||||
{
|
||||
USB_OTG_EP *ep;
|
||||
|
||||
if ((ep_addr & 0x80) == 0x80)
|
||||
{
|
||||
ep = &pdev->dev.in_ep[ep_addr & 0x7F];
|
||||
}
|
||||
else
|
||||
{
|
||||
ep = &pdev->dev.out_ep[ep_addr & 0x7F];
|
||||
}
|
||||
ep->num = ep_addr & 0x7F;
|
||||
|
||||
ep->is_in = (0x80 & ep_addr) != 0;
|
||||
ep->maxpacket = ep_mps;
|
||||
ep->type = ep_type;
|
||||
if (ep->is_in)
|
||||
{
|
||||
/* Assign a Tx FIFO */
|
||||
ep->tx_fifo_num = ep->num;
|
||||
}
|
||||
/* Set initial data PID. */
|
||||
if (ep_type == USB_OTG_EP_BULK )
|
||||
{
|
||||
ep->data_pid_start = 0;
|
||||
}
|
||||
USB_OTG_EPActivate(pdev , ep );
|
||||
return 0;
|
||||
}
|
||||
/**
|
||||
* @brief called when an EP is disabled
|
||||
* @param pdev: device instance
|
||||
* @param ep_addr: endpoint address
|
||||
* @retval : status
|
||||
*/
|
||||
uint32_t DCD_EP_Close(USB_OTG_CORE_HANDLE *pdev , uint8_t ep_addr)
|
||||
{
|
||||
USB_OTG_EP *ep;
|
||||
|
||||
if ((ep_addr&0x80) == 0x80)
|
||||
{
|
||||
ep = &pdev->dev.in_ep[ep_addr & 0x7F];
|
||||
}
|
||||
else
|
||||
{
|
||||
ep = &pdev->dev.out_ep[ep_addr & 0x7F];
|
||||
}
|
||||
ep->num = ep_addr & 0x7F;
|
||||
ep->is_in = (0x80 & ep_addr) != 0;
|
||||
USB_OTG_EPDeactivate(pdev , ep );
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief DCD_EP_PrepareRx
|
||||
* @param pdev: device instance
|
||||
* @param ep_addr: endpoint address
|
||||
* @param pbuf: pointer to Rx buffer
|
||||
* @param buf_len: data length
|
||||
* @retval : status
|
||||
*/
|
||||
uint32_t DCD_EP_PrepareRx( USB_OTG_CORE_HANDLE *pdev,
|
||||
uint8_t ep_addr,
|
||||
uint8_t *pbuf,
|
||||
uint16_t buf_len)
|
||||
{
|
||||
USB_OTG_EP *ep;
|
||||
|
||||
ep = &pdev->dev.out_ep[ep_addr & 0x7F];
|
||||
|
||||
/*setup and start the Xfer */
|
||||
ep->xfer_buff = pbuf;
|
||||
ep->xfer_len = buf_len;
|
||||
ep->xfer_count = 0;
|
||||
ep->is_in = 0;
|
||||
ep->num = ep_addr & 0x7F;
|
||||
|
||||
if (pdev->cfg.dma_enable == 1)
|
||||
{
|
||||
ep->dma_addr = (uint32_t)pbuf;
|
||||
}
|
||||
|
||||
if ( ep->num == 0 )
|
||||
{
|
||||
USB_OTG_EP0StartXfer(pdev , ep);
|
||||
}
|
||||
else
|
||||
{
|
||||
USB_OTG_EPStartXfer(pdev, ep );
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Transmit data over USB
|
||||
* @param pdev: device instance
|
||||
* @param ep_addr: endpoint address
|
||||
* @param pbuf: pointer to Tx buffer
|
||||
* @param buf_len: data length
|
||||
* @retval : status
|
||||
*/
|
||||
uint32_t DCD_EP_Tx ( USB_OTG_CORE_HANDLE *pdev,
|
||||
uint8_t ep_addr,
|
||||
uint8_t *pbuf,
|
||||
uint32_t buf_len)
|
||||
{
|
||||
USB_OTG_EP *ep;
|
||||
|
||||
ep = &pdev->dev.in_ep[ep_addr & 0x7F];
|
||||
|
||||
/* Setup and start the Transfer */
|
||||
ep->is_in = 1;
|
||||
ep->num = ep_addr & 0x7F;
|
||||
ep->xfer_buff = pbuf;
|
||||
ep->dma_addr = (uint32_t)pbuf;
|
||||
ep->xfer_count = 0;
|
||||
ep->xfer_len = buf_len;
|
||||
|
||||
if ( ep->num == 0 )
|
||||
{
|
||||
USB_OTG_EP0StartXfer(pdev , ep);
|
||||
}
|
||||
else
|
||||
{
|
||||
USB_OTG_EPStartXfer(pdev, ep );
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Stall an endpoint.
|
||||
* @param pdev: device instance
|
||||
* @param epnum: endpoint address
|
||||
* @retval : status
|
||||
*/
|
||||
uint32_t DCD_EP_Stall (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
|
||||
{
|
||||
USB_OTG_EP *ep;
|
||||
if ((0x80 & epnum) == 0x80)
|
||||
{
|
||||
ep = &pdev->dev.in_ep[epnum & 0x7F];
|
||||
}
|
||||
else
|
||||
{
|
||||
ep = &pdev->dev.out_ep[epnum];
|
||||
}
|
||||
|
||||
ep->is_stall = 1;
|
||||
ep->num = epnum & 0x7F;
|
||||
ep->is_in = ((epnum & 0x80) == 0x80);
|
||||
|
||||
USB_OTG_EPSetStall(pdev , ep);
|
||||
return (0);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Clear stall condition on endpoints.
|
||||
* @param pdev: device instance
|
||||
* @param epnum: endpoint address
|
||||
* @retval : status
|
||||
*/
|
||||
uint32_t DCD_EP_ClrStall (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
|
||||
{
|
||||
USB_OTG_EP *ep;
|
||||
if ((0x80 & epnum) == 0x80)
|
||||
{
|
||||
ep = &pdev->dev.in_ep[epnum & 0x7F];
|
||||
}
|
||||
else
|
||||
{
|
||||
ep = &pdev->dev.out_ep[epnum];
|
||||
}
|
||||
|
||||
ep->is_stall = 0;
|
||||
ep->num = epnum & 0x7F;
|
||||
ep->is_in = ((epnum & 0x80) == 0x80);
|
||||
|
||||
USB_OTG_EPClearStall(pdev , ep);
|
||||
return (0);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief This Function flushes the FIFOs.
|
||||
* @param pdev: device instance
|
||||
* @param epnum: endpoint address
|
||||
* @retval : status
|
||||
*/
|
||||
uint32_t DCD_EP_Flush (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum)
|
||||
{
|
||||
|
||||
if ((epnum & 0x80) == 0x80)
|
||||
{
|
||||
USB_OTG_FlushTxFifo(pdev, epnum & 0x7F);
|
||||
}
|
||||
else
|
||||
{
|
||||
USB_OTG_FlushRxFifo(pdev);
|
||||
}
|
||||
|
||||
return (0);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief This Function set USB device address
|
||||
* @param pdev: device instance
|
||||
* @param address: new device address
|
||||
* @retval : status
|
||||
*/
|
||||
void DCD_EP_SetAddress (USB_OTG_CORE_HANDLE *pdev, uint8_t address)
|
||||
{
|
||||
USB_OTG_DCFG_TypeDef dcfg;
|
||||
dcfg.d32 = 0;
|
||||
dcfg.b.devaddr = address;
|
||||
USB_OTG_MODIFY_REG32( &pdev->regs.DREGS->DCFG, 0, dcfg.d32);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Connect device (enable internal pull-up)
|
||||
* @param pdev: device instance
|
||||
* @retval : None
|
||||
*/
|
||||
void DCD_DevConnect (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
#ifndef USE_OTG_MODE
|
||||
USB_OTG_DCTL_TypeDef dctl;
|
||||
dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL);
|
||||
/* Connect device */
|
||||
dctl.b.sftdiscon = 0;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32);
|
||||
USB_OTG_BSP_mDelay(3);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Disconnect device (disable internal pull-up)
|
||||
* @param pdev: device instance
|
||||
* @retval : None
|
||||
*/
|
||||
void DCD_DevDisconnect (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
#ifndef USE_OTG_MODE
|
||||
USB_OTG_DCTL_TypeDef dctl;
|
||||
dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL);
|
||||
/* Disconnect device for 3ms */
|
||||
dctl.b.sftdiscon = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32);
|
||||
USB_OTG_BSP_mDelay(3);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief returns the EP Status
|
||||
* @param pdev : Selected device
|
||||
* epnum : endpoint address
|
||||
* @retval : EP status
|
||||
*/
|
||||
|
||||
uint32_t DCD_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,uint8_t epnum)
|
||||
{
|
||||
USB_OTG_EP *ep;
|
||||
uint32_t Status = 0;
|
||||
|
||||
if ((0x80 & epnum) == 0x80)
|
||||
{
|
||||
ep = &pdev->dev.in_ep[epnum & 0x7F];
|
||||
}
|
||||
else
|
||||
{
|
||||
ep = &pdev->dev.out_ep[epnum];
|
||||
}
|
||||
|
||||
Status = USB_OTG_GetEPStatus(pdev ,ep);
|
||||
|
||||
/* Return the current status */
|
||||
return Status;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Set the EP Status
|
||||
* @param pdev : Selected device
|
||||
* Status : new Status
|
||||
* epnum : EP address
|
||||
* @retval : None
|
||||
*/
|
||||
void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum , uint32_t Status)
|
||||
{
|
||||
USB_OTG_EP *ep;
|
||||
|
||||
if ((0x80 & epnum) == 0x80)
|
||||
{
|
||||
ep = &pdev->dev.in_ep[epnum & 0x7F];
|
||||
}
|
||||
else
|
||||
{
|
||||
ep = &pdev->dev.out_ep[epnum];
|
||||
}
|
||||
|
||||
USB_OTG_SetEPStatus(pdev ,ep , Status);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
886
lib/main/STM32_USB_OTG_Driver/src/usb_dcd_int.c
Normal file
886
lib/main/STM32_USB_OTG_Driver/src/usb_dcd_int.c
Normal file
|
@ -0,0 +1,886 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usb_dcd_int.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief Peripheral Device interrupt subroutines
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usb_dcd_int.h"
|
||||
/** @addtogroup USB_OTG_DRIVER
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup USB_DCD_INT
|
||||
* @brief This file contains the interrupt subroutines for the Device mode.
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_DCD_INT_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_DCD_INT_Private_TypesDefinitions
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/** @defgroup USB_DCD_INT_Private_Macros
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_DCD_INT_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_DCD_INT_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
/* static functions */
|
||||
static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum);
|
||||
|
||||
/* Interrupt Handlers */
|
||||
static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t DCD_HandleOutEP_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t DCD_HandleSof_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
|
||||
static uint32_t DCD_HandleRxStatusQueueLevel_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev , uint32_t epnum);
|
||||
|
||||
static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t DCD_HandleEnumDone_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t DCD_HandleResume_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
|
||||
static uint32_t DCD_IsoINIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t DCD_IsoOUTIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
#ifdef VBUS_SENSING_ENABLED
|
||||
static uint32_t DCD_SessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t DCD_OTG_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_DCD_INT_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
|
||||
/**
|
||||
* @brief USBD_OTG_EP1OUT_ISR_Handler
|
||||
* handles all USB Interrupts
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
uint32_t USBD_OTG_EP1OUT_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
|
||||
USB_OTG_DOEPINTn_TypeDef doepint;
|
||||
USB_OTG_DEPXFRSIZ_TypeDef deptsiz;
|
||||
|
||||
doepint.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[1]->DOEPINT);
|
||||
doepint.d32&= USB_OTG_READ_REG32(&pdev->regs.DREGS->DOUTEP1MSK);
|
||||
|
||||
/* Transfer complete */
|
||||
if ( doepint.b.xfercompl )
|
||||
{
|
||||
/* Clear the bit in DOEPINTn for this interrupt */
|
||||
CLEAR_OUT_EP_INTR(1, xfercompl);
|
||||
if (pdev->cfg.dma_enable == 1)
|
||||
{
|
||||
deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[1]->DOEPTSIZ));
|
||||
/*ToDo : handle more than one single MPS size packet */
|
||||
pdev->dev.out_ep[1].xfer_count = pdev->dev.out_ep[1].maxpacket - \
|
||||
deptsiz.b.xfersize;
|
||||
}
|
||||
/* Inform upper layer: data ready */
|
||||
/* RX COMPLETE */
|
||||
USBD_DCD_INT_fops->DataOutStage(pdev , 1);
|
||||
|
||||
}
|
||||
|
||||
/* Endpoint disable */
|
||||
if ( doepint.b.epdisabled )
|
||||
{
|
||||
/* Clear the bit in DOEPINTn for this interrupt */
|
||||
CLEAR_OUT_EP_INTR(1, epdisabled);
|
||||
}
|
||||
/* AHB Error */
|
||||
if ( doepint.b.ahberr )
|
||||
{
|
||||
CLEAR_OUT_EP_INTR(1, ahberr);
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USBD_OTG_EP1IN_ISR_Handler
|
||||
* handles all USB Interrupts
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
|
||||
USB_OTG_DIEPINTn_TypeDef diepint;
|
||||
uint32_t fifoemptymsk, msk, emp;
|
||||
|
||||
msk = USB_OTG_READ_REG32(&pdev->regs.DREGS->DINEP1MSK);
|
||||
emp = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPEMPMSK);
|
||||
msk |= ((emp >> 1 ) & 0x1) << 7;
|
||||
diepint.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[1]->DIEPINT) & msk;
|
||||
|
||||
if ( diepint.b.xfercompl )
|
||||
{
|
||||
fifoemptymsk = 0x1 << 1;
|
||||
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0);
|
||||
CLEAR_IN_EP_INTR(1, xfercompl);
|
||||
/* TX COMPLETE */
|
||||
USBD_DCD_INT_fops->DataInStage(pdev , 1);
|
||||
}
|
||||
if ( diepint.b.ahberr )
|
||||
{
|
||||
CLEAR_IN_EP_INTR(1, ahberr);
|
||||
}
|
||||
if ( diepint.b.epdisabled )
|
||||
{
|
||||
CLEAR_IN_EP_INTR(1, epdisabled);
|
||||
}
|
||||
if ( diepint.b.timeout )
|
||||
{
|
||||
CLEAR_IN_EP_INTR(1, timeout);
|
||||
}
|
||||
if (diepint.b.intktxfemp)
|
||||
{
|
||||
CLEAR_IN_EP_INTR(1, intktxfemp);
|
||||
}
|
||||
if (diepint.b.intknepmis)
|
||||
{
|
||||
CLEAR_IN_EP_INTR(1, intknepmis);
|
||||
}
|
||||
if (diepint.b.inepnakeff)
|
||||
{
|
||||
CLEAR_IN_EP_INTR(1, inepnakeff);
|
||||
}
|
||||
if (diepint.b.emptyintr)
|
||||
{
|
||||
DCD_WriteEmptyTxFifo(pdev , 1);
|
||||
CLEAR_IN_EP_INTR(1, emptyintr);
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief STM32_USBF_OTG_ISR_Handler
|
||||
* handles all USB Interrupts
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
uint32_t USBD_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintr_status;
|
||||
uint32_t retval = 0;
|
||||
|
||||
if (USB_OTG_IsDeviceMode(pdev)) /* ensure that we are in device mode */
|
||||
{
|
||||
gintr_status.d32 = USB_OTG_ReadCoreItr(pdev);
|
||||
if (!gintr_status.d32) /* avoid spurious interrupt */
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (gintr_status.b.outepintr)
|
||||
{
|
||||
retval |= DCD_HandleOutEP_ISR(pdev);
|
||||
}
|
||||
|
||||
if (gintr_status.b.inepint)
|
||||
{
|
||||
retval |= DCD_HandleInEP_ISR(pdev);
|
||||
}
|
||||
|
||||
if (gintr_status.b.modemismatch)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
|
||||
/* Clear interrupt */
|
||||
gintsts.d32 = 0;
|
||||
gintsts.b.modemismatch = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
}
|
||||
|
||||
if (gintr_status.b.wkupintr)
|
||||
{
|
||||
retval |= DCD_HandleResume_ISR(pdev);
|
||||
}
|
||||
|
||||
if (gintr_status.b.usbsuspend)
|
||||
{
|
||||
retval |= DCD_HandleUSBSuspend_ISR(pdev);
|
||||
}
|
||||
if (gintr_status.b.sofintr)
|
||||
{
|
||||
retval |= DCD_HandleSof_ISR(pdev);
|
||||
|
||||
}
|
||||
|
||||
if (gintr_status.b.rxstsqlvl)
|
||||
{
|
||||
retval |= DCD_HandleRxStatusQueueLevel_ISR(pdev);
|
||||
|
||||
}
|
||||
|
||||
if (gintr_status.b.usbreset)
|
||||
{
|
||||
retval |= DCD_HandleUsbReset_ISR(pdev);
|
||||
|
||||
}
|
||||
if (gintr_status.b.enumdone)
|
||||
{
|
||||
retval |= DCD_HandleEnumDone_ISR(pdev);
|
||||
}
|
||||
|
||||
if (gintr_status.b.incomplisoin)
|
||||
{
|
||||
retval |= DCD_IsoINIncomplete_ISR(pdev);
|
||||
}
|
||||
|
||||
if (gintr_status.b.incomplisoout)
|
||||
{
|
||||
retval |= DCD_IsoOUTIncomplete_ISR(pdev);
|
||||
}
|
||||
#ifdef VBUS_SENSING_ENABLED
|
||||
if (gintr_status.b.sessreqintr)
|
||||
{
|
||||
retval |= DCD_SessionRequest_ISR(pdev);
|
||||
}
|
||||
|
||||
if (gintr_status.b.otgintr)
|
||||
{
|
||||
retval |= DCD_OTG_ISR(pdev);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
return retval;
|
||||
}
|
||||
|
||||
#ifdef VBUS_SENSING_ENABLED
|
||||
/**
|
||||
* @brief DCD_SessionRequest_ISR
|
||||
* Indicates that the USB_OTG controller has detected a connection
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_SessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
USBD_DCD_INT_fops->DevConnected (pdev);
|
||||
|
||||
/* Clear interrupt */
|
||||
gintsts.d32 = 0;
|
||||
gintsts.b.sessreqintr = 1;
|
||||
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DCD_OTG_ISR
|
||||
* Indicates that the USB_OTG controller has detected an OTG event:
|
||||
* used to detect the end of session i.e. disconnection
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_OTG_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
|
||||
USB_OTG_GOTGINT_TypeDef gotgint;
|
||||
|
||||
gotgint.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGINT);
|
||||
|
||||
if (gotgint.b.sesenddet)
|
||||
{
|
||||
USBD_DCD_INT_fops->DevDisconnected (pdev);
|
||||
}
|
||||
/* Clear OTG interrupt */
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGINT, gotgint.d32);
|
||||
return 1;
|
||||
}
|
||||
#endif
|
||||
/**
|
||||
* @brief DCD_HandleResume_ISR
|
||||
* Indicates that the USB_OTG controller has detected a resume or
|
||||
* remote Wake-up sequence
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_HandleResume_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
USB_OTG_DCTL_TypeDef devctl;
|
||||
USB_OTG_PCGCCTL_TypeDef power;
|
||||
|
||||
if(pdev->cfg.low_power)
|
||||
{
|
||||
/* un-gate USB Core clock */
|
||||
power.d32 = USB_OTG_READ_REG32(pdev->regs.PCGCCTL);
|
||||
power.b.gatehclk = 0;
|
||||
power.b.stoppclk = 0;
|
||||
USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, power.d32);
|
||||
}
|
||||
|
||||
/* Clear the Remote Wake-up Signaling */
|
||||
devctl.d32 = 0;
|
||||
devctl.b.rmtwkupsig = 1;
|
||||
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, devctl.d32, 0);
|
||||
|
||||
/* Inform upper layer by the Resume Event */
|
||||
USBD_DCD_INT_fops->Resume (pdev);
|
||||
|
||||
/* Clear interrupt */
|
||||
gintsts.d32 = 0;
|
||||
gintsts.b.wkupintr = 1;
|
||||
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_HandleUSBSuspend_ISR
|
||||
* Indicates that SUSPEND state has been detected on the USB
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
USB_OTG_PCGCCTL_TypeDef power;
|
||||
USB_OTG_DSTS_TypeDef dsts;
|
||||
|
||||
USBD_DCD_INT_fops->Suspend (pdev);
|
||||
|
||||
dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS);
|
||||
|
||||
/* Clear interrupt */
|
||||
gintsts.d32 = 0;
|
||||
gintsts.b.usbsuspend = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
|
||||
if((pdev->cfg.low_power) && (dsts.b.suspsts == 1))
|
||||
{
|
||||
/* switch-off the clocks */
|
||||
power.d32 = 0;
|
||||
power.b.stoppclk = 1;
|
||||
USB_OTG_MODIFY_REG32(pdev->regs.PCGCCTL, 0, power.d32);
|
||||
|
||||
power.b.gatehclk = 1;
|
||||
USB_OTG_MODIFY_REG32(pdev->regs.PCGCCTL, 0, power.d32);
|
||||
|
||||
/* Request to enter Sleep mode after exit from current ISR */
|
||||
SCB->SCR |= (SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk);
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DCD_HandleInEP_ISR
|
||||
* Indicates that an IN EP has a pending Interrupt
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_DIEPINTn_TypeDef diepint;
|
||||
|
||||
uint32_t ep_intr;
|
||||
uint32_t epnum = 0;
|
||||
uint32_t fifoemptymsk;
|
||||
diepint.d32 = 0;
|
||||
ep_intr = USB_OTG_ReadDevAllInEPItr(pdev);
|
||||
|
||||
while ( ep_intr )
|
||||
{
|
||||
if (ep_intr&0x1) /* In ITR */
|
||||
{
|
||||
diepint.d32 = DCD_ReadDevInEP(pdev , epnum); /* Get In ITR status */
|
||||
if ( diepint.b.xfercompl )
|
||||
{
|
||||
fifoemptymsk = 0x1 << epnum;
|
||||
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0);
|
||||
CLEAR_IN_EP_INTR(epnum, xfercompl);
|
||||
/* TX COMPLETE */
|
||||
USBD_DCD_INT_fops->DataInStage(pdev , epnum);
|
||||
|
||||
if (pdev->cfg.dma_enable == 1)
|
||||
{
|
||||
if((epnum == 0) && (pdev->dev.device_state == USB_OTG_EP0_STATUS_IN))
|
||||
{
|
||||
/* prepare to rx more setup packets */
|
||||
USB_OTG_EP0_OutStart(pdev);
|
||||
}
|
||||
}
|
||||
}
|
||||
if ( diepint.b.ahberr )
|
||||
{
|
||||
CLEAR_IN_EP_INTR(epnum, ahberr);
|
||||
}
|
||||
if ( diepint.b.timeout )
|
||||
{
|
||||
CLEAR_IN_EP_INTR(epnum, timeout);
|
||||
}
|
||||
if (diepint.b.intktxfemp)
|
||||
{
|
||||
CLEAR_IN_EP_INTR(epnum, intktxfemp);
|
||||
}
|
||||
if (diepint.b.intknepmis)
|
||||
{
|
||||
CLEAR_IN_EP_INTR(epnum, intknepmis);
|
||||
}
|
||||
if (diepint.b.inepnakeff)
|
||||
{
|
||||
CLEAR_IN_EP_INTR(epnum, inepnakeff);
|
||||
}
|
||||
if ( diepint.b.epdisabled )
|
||||
{
|
||||
CLEAR_IN_EP_INTR(epnum, epdisabled);
|
||||
}
|
||||
if (diepint.b.emptyintr)
|
||||
{
|
||||
|
||||
DCD_WriteEmptyTxFifo(pdev , epnum);
|
||||
|
||||
CLEAR_IN_EP_INTR(epnum, emptyintr);
|
||||
}
|
||||
}
|
||||
epnum++;
|
||||
ep_intr >>= 1;
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DCD_HandleOutEP_ISR
|
||||
* Indicates that an OUT EP has a pending Interrupt
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_HandleOutEP_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
uint32_t ep_intr;
|
||||
USB_OTG_DOEPINTn_TypeDef doepint;
|
||||
USB_OTG_DEPXFRSIZ_TypeDef deptsiz;
|
||||
uint32_t epnum = 0;
|
||||
|
||||
doepint.d32 = 0;
|
||||
|
||||
/* Read in the device interrupt bits */
|
||||
ep_intr = USB_OTG_ReadDevAllOutEp_itr(pdev);
|
||||
|
||||
while ( ep_intr )
|
||||
{
|
||||
if (ep_intr&0x1)
|
||||
{
|
||||
|
||||
doepint.d32 = USB_OTG_ReadDevOutEP_itr(pdev, epnum);
|
||||
|
||||
/* Transfer complete */
|
||||
if ( doepint.b.xfercompl )
|
||||
{
|
||||
/* Clear the bit in DOEPINTn for this interrupt */
|
||||
CLEAR_OUT_EP_INTR(epnum, xfercompl);
|
||||
if (pdev->cfg.dma_enable == 1)
|
||||
{
|
||||
deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[epnum]->DOEPTSIZ));
|
||||
/*ToDo : handle more than one single MPS size packet */
|
||||
pdev->dev.out_ep[epnum].xfer_count = pdev->dev.out_ep[epnum].maxpacket - \
|
||||
deptsiz.b.xfersize;
|
||||
}
|
||||
/* Inform upper layer: data ready */
|
||||
/* RX COMPLETE */
|
||||
USBD_DCD_INT_fops->DataOutStage(pdev , epnum);
|
||||
|
||||
if (pdev->cfg.dma_enable == 1)
|
||||
{
|
||||
if((epnum == 0) && (pdev->dev.device_state == USB_OTG_EP0_STATUS_OUT))
|
||||
{
|
||||
/* prepare to rx more setup packets */
|
||||
USB_OTG_EP0_OutStart(pdev);
|
||||
}
|
||||
}
|
||||
}
|
||||
/* Endpoint disable */
|
||||
if ( doepint.b.epdisabled )
|
||||
{
|
||||
/* Clear the bit in DOEPINTn for this interrupt */
|
||||
CLEAR_OUT_EP_INTR(epnum, epdisabled);
|
||||
}
|
||||
/* AHB Error */
|
||||
if ( doepint.b.ahberr )
|
||||
{
|
||||
CLEAR_OUT_EP_INTR(epnum, ahberr);
|
||||
}
|
||||
/* Setup Phase Done (control EPs) */
|
||||
if ( doepint.b.setup )
|
||||
{
|
||||
|
||||
/* inform the upper layer that a setup packet is available */
|
||||
/* SETUP COMPLETE */
|
||||
USBD_DCD_INT_fops->SetupStage(pdev);
|
||||
CLEAR_OUT_EP_INTR(epnum, setup);
|
||||
}
|
||||
}
|
||||
epnum++;
|
||||
ep_intr >>= 1;
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DCD_HandleSof_ISR
|
||||
* Handles the SOF Interrupts
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_HandleSof_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef GINTSTS;
|
||||
|
||||
|
||||
USBD_DCD_INT_fops->SOF(pdev);
|
||||
|
||||
/* Clear interrupt */
|
||||
GINTSTS.d32 = 0;
|
||||
GINTSTS.b.sofintr = 1;
|
||||
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, GINTSTS.d32);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DCD_HandleRxStatusQueueLevel_ISR
|
||||
* Handles the Rx Status Queue Level Interrupt
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_HandleRxStatusQueueLevel_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTMSK_TypeDef int_mask;
|
||||
USB_OTG_DRXSTS_TypeDef status;
|
||||
USB_OTG_EP *ep;
|
||||
|
||||
/* Disable the Rx Status Queue Level interrupt */
|
||||
int_mask.d32 = 0;
|
||||
int_mask.b.rxstsqlvl = 1;
|
||||
USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, int_mask.d32, 0);
|
||||
|
||||
/* Get the Status from the top of the FIFO */
|
||||
status.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GRXSTSP );
|
||||
|
||||
ep = &pdev->dev.out_ep[status.b.epnum];
|
||||
|
||||
switch (status.b.pktsts)
|
||||
{
|
||||
case STS_GOUT_NAK:
|
||||
break;
|
||||
case STS_DATA_UPDT:
|
||||
if (status.b.bcnt)
|
||||
{
|
||||
USB_OTG_ReadPacket(pdev,ep->xfer_buff, status.b.bcnt);
|
||||
ep->xfer_buff += status.b.bcnt;
|
||||
ep->xfer_count += status.b.bcnt;
|
||||
}
|
||||
break;
|
||||
case STS_XFER_COMP:
|
||||
break;
|
||||
case STS_SETUP_COMP:
|
||||
break;
|
||||
case STS_SETUP_UPDT:
|
||||
/* Copy the setup packet received in FIFO into the setup buffer in RAM */
|
||||
USB_OTG_ReadPacket(pdev , pdev->dev.setup_packet, 8);
|
||||
ep->xfer_count += status.b.bcnt;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
/* Enable the Rx Status Queue Level interrupt */
|
||||
USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, 0, int_mask.d32);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DCD_WriteEmptyTxFifo
|
||||
* check FIFO for the next packet to be loaded
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev, uint32_t epnum)
|
||||
{
|
||||
USB_OTG_DTXFSTSn_TypeDef txstatus;
|
||||
USB_OTG_EP *ep;
|
||||
uint32_t len = 0;
|
||||
uint32_t len32b;
|
||||
txstatus.d32 = 0;
|
||||
|
||||
ep = &pdev->dev.in_ep[epnum];
|
||||
|
||||
len = ep->xfer_len - ep->xfer_count;
|
||||
|
||||
if (len > ep->maxpacket)
|
||||
{
|
||||
len = ep->maxpacket;
|
||||
}
|
||||
|
||||
len32b = (len + 3) / 4;
|
||||
txstatus.d32 = USB_OTG_READ_REG32( &pdev->regs.INEP_REGS[epnum]->DTXFSTS);
|
||||
|
||||
|
||||
|
||||
while (txstatus.b.txfspcavail > len32b &&
|
||||
ep->xfer_count < ep->xfer_len &&
|
||||
ep->xfer_len != 0)
|
||||
{
|
||||
/* Write the FIFO */
|
||||
len = ep->xfer_len - ep->xfer_count;
|
||||
|
||||
if (len > ep->maxpacket)
|
||||
{
|
||||
len = ep->maxpacket;
|
||||
}
|
||||
len32b = (len + 3) / 4;
|
||||
|
||||
USB_OTG_WritePacket (pdev , ep->xfer_buff, epnum, len);
|
||||
|
||||
ep->xfer_buff += len;
|
||||
ep->xfer_count += len;
|
||||
|
||||
txstatus.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[epnum]->DTXFSTS);
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DCD_HandleUsbReset_ISR
|
||||
* This interrupt occurs when a USB Reset is detected
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_DAINT_TypeDef daintmsk;
|
||||
USB_OTG_DOEPMSK_TypeDef doepmsk;
|
||||
USB_OTG_DIEPMSK_TypeDef diepmsk;
|
||||
USB_OTG_DCFG_TypeDef dcfg;
|
||||
USB_OTG_DCTL_TypeDef dctl;
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
uint32_t i;
|
||||
|
||||
dctl.d32 = 0;
|
||||
daintmsk.d32 = 0;
|
||||
doepmsk.d32 = 0;
|
||||
diepmsk.d32 = 0;
|
||||
dcfg.d32 = 0;
|
||||
gintsts.d32 = 0;
|
||||
|
||||
/* Clear the Remote Wake-up Signaling */
|
||||
dctl.b.rmtwkupsig = 1;
|
||||
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, dctl.d32, 0 );
|
||||
|
||||
/* Flush the Tx FIFO */
|
||||
USB_OTG_FlushTxFifo(pdev , 0 );
|
||||
|
||||
for (i = 0; i < pdev->cfg.dev_endpoints ; i++)
|
||||
{
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPINT, 0xFF);
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPINT, 0xFF);
|
||||
}
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINT, 0xFFFFFFFF );
|
||||
|
||||
daintmsk.ep.in = 1;
|
||||
daintmsk.ep.out = 1;
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINTMSK, daintmsk.d32 );
|
||||
|
||||
doepmsk.b.setup = 1;
|
||||
doepmsk.b.xfercompl = 1;
|
||||
doepmsk.b.ahberr = 1;
|
||||
doepmsk.b.epdisabled = 1;
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOEPMSK, doepmsk.d32 );
|
||||
#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOUTEP1MSK, doepmsk.d32 );
|
||||
#endif
|
||||
diepmsk.b.xfercompl = 1;
|
||||
diepmsk.b.timeout = 1;
|
||||
diepmsk.b.epdisabled = 1;
|
||||
diepmsk.b.ahberr = 1;
|
||||
diepmsk.b.intknepmis = 1;
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DIEPMSK, diepmsk.d32 );
|
||||
#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DINEP1MSK, diepmsk.d32 );
|
||||
#endif
|
||||
/* Reset Device Address */
|
||||
dcfg.d32 = USB_OTG_READ_REG32( &pdev->regs.DREGS->DCFG);
|
||||
dcfg.b.devaddr = 0;
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DCFG, dcfg.d32);
|
||||
|
||||
|
||||
/* setup EP0 to receive SETUP packets */
|
||||
USB_OTG_EP0_OutStart(pdev);
|
||||
|
||||
/* Clear interrupt */
|
||||
gintsts.d32 = 0;
|
||||
gintsts.b.usbreset = 1;
|
||||
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
|
||||
/*Reset internal state machine */
|
||||
USBD_DCD_INT_fops->Reset(pdev);
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DCD_HandleEnumDone_ISR
|
||||
* Read the device status register and set the device speed
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_HandleEnumDone_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
USB_OTG_GUSBCFG_TypeDef gusbcfg;
|
||||
|
||||
USB_OTG_EP0Activate(pdev);
|
||||
|
||||
/* Set USB turn-around time based on device speed and PHY interface. */
|
||||
gusbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);
|
||||
|
||||
/* Full or High speed */
|
||||
if ( USB_OTG_GetDeviceSpeed(pdev) == USB_SPEED_HIGH)
|
||||
{
|
||||
pdev->cfg.speed = USB_OTG_SPEED_HIGH;
|
||||
pdev->cfg.mps = USB_OTG_HS_MAX_PACKET_SIZE ;
|
||||
gusbcfg.b.usbtrdtim = 9;
|
||||
}
|
||||
else
|
||||
{
|
||||
pdev->cfg.speed = USB_OTG_SPEED_FULL;
|
||||
pdev->cfg.mps = USB_OTG_FS_MAX_PACKET_SIZE ;
|
||||
gusbcfg.b.usbtrdtim = 5;
|
||||
}
|
||||
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, gusbcfg.d32);
|
||||
|
||||
/* Clear interrupt */
|
||||
gintsts.d32 = 0;
|
||||
gintsts.b.enumdone = 1;
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, gintsts.d32 );
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief DCD_IsoINIncomplete_ISR
|
||||
* handle the ISO IN incomplete interrupt
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_IsoINIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
|
||||
gintsts.d32 = 0;
|
||||
|
||||
USBD_DCD_INT_fops->IsoINIncomplete (pdev);
|
||||
|
||||
/* Clear interrupt */
|
||||
gintsts.b.incomplisoin = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DCD_IsoOUTIncomplete_ISR
|
||||
* handle the ISO OUT incomplete interrupt
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_IsoOUTIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
|
||||
gintsts.d32 = 0;
|
||||
|
||||
USBD_DCD_INT_fops->IsoOUTIncomplete (pdev);
|
||||
|
||||
/* Clear interrupt */
|
||||
gintsts.b.incomplisoout = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
return 1;
|
||||
}
|
||||
/**
|
||||
* @brief DCD_ReadDevInEP
|
||||
* Reads ep flags
|
||||
* @param pdev: device instance
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
|
||||
{
|
||||
uint32_t v, msk, emp;
|
||||
msk = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPMSK);
|
||||
emp = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPEMPMSK);
|
||||
msk |= ((emp >> epnum) & 0x1) << 7;
|
||||
v = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[epnum]->DIEPINT) & msk;
|
||||
return v;
|
||||
}
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
256
lib/main/STM32_USB_OTG_Driver/src/usb_hcd.c
Normal file
256
lib/main/STM32_USB_OTG_Driver/src/usb_hcd.c
Normal file
|
@ -0,0 +1,256 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usb_hcd.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief Host Interface Layer
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usb_core.h"
|
||||
#include "usb_hcd.h"
|
||||
#include "usb_conf.h"
|
||||
#include "usb_bsp.h"
|
||||
|
||||
|
||||
/** @addtogroup USB_OTG_DRIVER
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup USB_HCD
|
||||
* @brief This file is the interface between EFSL ans Host mass-storage class
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_HCD_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_HCD_Private_TypesDefinitions
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/** @defgroup USB_HCD_Private_Macros
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_HCD_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_HCD_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_HCD_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief HCD_Init
|
||||
* Initialize the HOST portion of the driver.
|
||||
* @param pdev: Selected device
|
||||
* @param base_address: OTG base address
|
||||
* @retval Status
|
||||
*/
|
||||
uint32_t HCD_Init(USB_OTG_CORE_HANDLE *pdev ,
|
||||
USB_OTG_CORE_ID_TypeDef coreID)
|
||||
{
|
||||
uint8_t i = 0;
|
||||
pdev->host.ConnSts = 0;
|
||||
|
||||
for (i= 0; i< USB_OTG_MAX_TX_FIFOS; i++)
|
||||
{
|
||||
pdev->host.ErrCnt[i] = 0;
|
||||
pdev->host.XferCnt[i] = 0;
|
||||
pdev->host.HC_Status[i] = HC_IDLE;
|
||||
}
|
||||
pdev->host.hc[0].max_packet = 8;
|
||||
|
||||
USB_OTG_SelectCore(pdev, coreID);
|
||||
#ifndef DUAL_ROLE_MODE_ENABLED
|
||||
USB_OTG_DisableGlobalInt(pdev);
|
||||
USB_OTG_CoreInit(pdev);
|
||||
|
||||
/* Force Host Mode*/
|
||||
USB_OTG_SetCurrentMode(pdev , HOST_MODE);
|
||||
USB_OTG_CoreInitHost(pdev);
|
||||
USB_OTG_EnableGlobalInt(pdev);
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief HCD_GetCurrentSpeed
|
||||
* Get Current device Speed.
|
||||
* @param pdev : Selected device
|
||||
* @retval Status
|
||||
*/
|
||||
|
||||
uint32_t HCD_GetCurrentSpeed (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_HPRT0_TypeDef HPRT0;
|
||||
HPRT0.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0);
|
||||
|
||||
return HPRT0.b.prtspd;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief HCD_ResetPort
|
||||
* Issues the reset command to device
|
||||
* @param pdev : Selected device
|
||||
* @retval Status
|
||||
*/
|
||||
uint32_t HCD_ResetPort(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
/*
|
||||
Before starting to drive a USB reset, the application waits for the OTG
|
||||
interrupt triggered by the debounce done bit (DBCDNE bit in OTG_FS_GOTGINT),
|
||||
which indicates that the bus is stable again after the electrical debounce
|
||||
caused by the attachment of a pull-up resistor on DP (FS) or DM (LS).
|
||||
*/
|
||||
|
||||
USB_OTG_ResetPort(pdev);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief HCD_IsDeviceConnected
|
||||
* Check if the device is connected.
|
||||
* @param pdev : Selected device
|
||||
* @retval Device connection status. 1 -> connected and 0 -> disconnected
|
||||
*
|
||||
*/
|
||||
uint32_t HCD_IsDeviceConnected(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
return (pdev->host.ConnSts);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief HCD_GetCurrentFrame
|
||||
* This function returns the frame number for sof packet
|
||||
* @param pdev : Selected device
|
||||
* @retval Frame number
|
||||
*
|
||||
*/
|
||||
uint32_t HCD_GetCurrentFrame (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
return (USB_OTG_READ_REG32(&pdev->regs.HREGS->HFNUM) & 0xFFFF) ;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief HCD_GetURB_State
|
||||
* This function returns the last URBstate
|
||||
* @param pdev: Selected device
|
||||
* @retval URB_STATE
|
||||
*
|
||||
*/
|
||||
URB_STATE HCD_GetURB_State (USB_OTG_CORE_HANDLE *pdev , uint8_t ch_num)
|
||||
{
|
||||
return pdev->host.URB_State[ch_num] ;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief HCD_GetXferCnt
|
||||
* This function returns the last URBstate
|
||||
* @param pdev: Selected device
|
||||
* @retval No. of data bytes transferred
|
||||
*
|
||||
*/
|
||||
uint32_t HCD_GetXferCnt (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num)
|
||||
{
|
||||
return pdev->host.XferCnt[ch_num] ;
|
||||
}
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @brief HCD_GetHCState
|
||||
* This function returns the HC Status
|
||||
* @param pdev: Selected device
|
||||
* @retval HC_STATUS
|
||||
*
|
||||
*/
|
||||
HC_STATUS HCD_GetHCState (USB_OTG_CORE_HANDLE *pdev , uint8_t ch_num)
|
||||
{
|
||||
return pdev->host.HC_Status[ch_num] ;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief HCD_HC_Init
|
||||
* This function prepare a HC and start a transfer
|
||||
* @param pdev: Selected device
|
||||
* @param hc_num: Channel number
|
||||
* @retval status
|
||||
*/
|
||||
uint32_t HCD_HC_Init (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
|
||||
{
|
||||
return USB_OTG_HC_Init(pdev, hc_num);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief HCD_SubmitRequest
|
||||
* This function prepare a HC and start a transfer
|
||||
* @param pdev: Selected device
|
||||
* @param hc_num: Channel number
|
||||
* @retval status
|
||||
*/
|
||||
uint32_t HCD_SubmitRequest (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
|
||||
{
|
||||
|
||||
pdev->host.URB_State[hc_num] = URB_IDLE;
|
||||
pdev->host.hc[hc_num].xfer_count = 0 ;
|
||||
return USB_OTG_HC_StartXfer(pdev, hc_num);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
832
lib/main/STM32_USB_OTG_Driver/src/usb_hcd_int.c
Normal file
832
lib/main/STM32_USB_OTG_Driver/src/usb_hcd_int.c
Normal file
|
@ -0,0 +1,832 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usb_hcd_int.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief Host driver interrupt subroutines
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usb_core.h"
|
||||
#include "usb_defines.h"
|
||||
#include "usb_hcd_int.h"
|
||||
|
||||
#if defined (__CC_ARM) /*!< ARM Compiler */
|
||||
#pragma O0
|
||||
#elif defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma O0
|
||||
#elif defined (__GNUC__) /*!< GNU Compiler */
|
||||
#pragma GCC optimize ("O0")
|
||||
#elif defined (__TASKING__) /*!< TASKING Compiler */
|
||||
#pragma optimize=0
|
||||
|
||||
#endif /* __CC_ARM */
|
||||
|
||||
/** @addtogroup USB_OTG_DRIVER
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup USB_HCD_INT
|
||||
* @brief This file contains the interrupt subroutines for the Host mode.
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_HCD_INT_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_HCD_INT_Private_TypesDefinitions
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/** @defgroup USB_HCD_INT_Private_Macros
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_HCD_INT_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_HCD_INT_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
|
||||
static uint32_t USB_OTG_USBH_handle_sof_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t USB_OTG_USBH_handle_port_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t USB_OTG_USBH_handle_hc_ISR (USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev ,
|
||||
uint32_t num);
|
||||
static uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev ,
|
||||
uint32_t num);
|
||||
static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t USB_OTG_USBH_handle_nptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t USB_OTG_USBH_handle_Disconnect_ISR (USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (USB_OTG_CORE_HANDLE *pdev);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_HCD_INT_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief HOST_Handle_ISR
|
||||
* This function handles all USB Host Interrupts
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
|
||||
uint32_t USBH_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
uint32_t retval = 0;
|
||||
|
||||
gintsts.d32 = 0;
|
||||
|
||||
/* Check if HOST Mode */
|
||||
if (USB_OTG_IsHostMode(pdev))
|
||||
{
|
||||
gintsts.d32 = USB_OTG_ReadCoreItr(pdev);
|
||||
if (!gintsts.d32)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (gintsts.b.sofintr)
|
||||
{
|
||||
retval |= USB_OTG_USBH_handle_sof_ISR (pdev);
|
||||
}
|
||||
|
||||
if (gintsts.b.rxstsqlvl)
|
||||
{
|
||||
retval |= USB_OTG_USBH_handle_rx_qlvl_ISR (pdev);
|
||||
}
|
||||
|
||||
if (gintsts.b.nptxfempty)
|
||||
{
|
||||
retval |= USB_OTG_USBH_handle_nptxfempty_ISR (pdev);
|
||||
}
|
||||
|
||||
if (gintsts.b.ptxfempty)
|
||||
{
|
||||
retval |= USB_OTG_USBH_handle_ptxfempty_ISR (pdev);
|
||||
}
|
||||
|
||||
if (gintsts.b.hcintr)
|
||||
{
|
||||
retval |= USB_OTG_USBH_handle_hc_ISR (pdev);
|
||||
}
|
||||
|
||||
if (gintsts.b.portintr)
|
||||
{
|
||||
retval |= USB_OTG_USBH_handle_port_ISR (pdev);
|
||||
}
|
||||
|
||||
if (gintsts.b.disconnect)
|
||||
{
|
||||
retval |= USB_OTG_USBH_handle_Disconnect_ISR (pdev);
|
||||
|
||||
}
|
||||
|
||||
if (gintsts.b.incomplisoout)
|
||||
{
|
||||
retval |= USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (pdev);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
return retval;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_hc_ISR
|
||||
* This function indicates that one or more host channels has a pending
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t USB_OTG_USBH_handle_hc_ISR (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_HAINT_TypeDef haint;
|
||||
USB_OTG_HCCHAR_TypeDef hcchar;
|
||||
uint32_t i = 0;
|
||||
uint32_t retval = 0;
|
||||
|
||||
/* Clear appropriate bits in HCINTn to clear the interrupt bit in
|
||||
* GINTSTS */
|
||||
|
||||
haint.d32 = USB_OTG_ReadHostAllChannels_intr(pdev);
|
||||
|
||||
for (i = 0; i < pdev->cfg.host_channels ; i++)
|
||||
{
|
||||
if (haint.b.chint & (1 << i))
|
||||
{
|
||||
hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[i]->HCCHAR);
|
||||
|
||||
if (hcchar.b.epdir)
|
||||
{
|
||||
retval |= USB_OTG_USBH_handle_hc_n_In_ISR (pdev, i);
|
||||
}
|
||||
else
|
||||
{
|
||||
retval |= USB_OTG_USBH_handle_hc_n_Out_ISR (pdev, i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return retval;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_otg_hcd_handle_sof_intr
|
||||
* Handles the start-of-frame interrupt in host mode.
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t USB_OTG_USBH_handle_sof_ISR (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
|
||||
|
||||
gintsts.d32 = 0;
|
||||
/* Clear interrupt */
|
||||
gintsts.b.sofintr = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_Disconnect_ISR
|
||||
* Handles disconnect event.
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t USB_OTG_USBH_handle_Disconnect_ISR (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
|
||||
pdev->host.ConnSts = 0;
|
||||
gintsts.d32 = 0;
|
||||
|
||||
pdev->host.port_cb->Disconnect(pdev);
|
||||
|
||||
/* Clear interrupt */
|
||||
gintsts.b.disconnect = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_nptxfempty_ISR
|
||||
* Handles non periodic tx fifo empty.
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t USB_OTG_USBH_handle_nptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTMSK_TypeDef intmsk;
|
||||
USB_OTG_HNPTXSTS_TypeDef hnptxsts;
|
||||
uint16_t len_words , len;
|
||||
|
||||
hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS);
|
||||
|
||||
len_words = (pdev->host.hc[hnptxsts.b.chnum].xfer_len + 3) / 4;
|
||||
|
||||
while ((hnptxsts.b.nptxfspcavail > len_words)&&
|
||||
(pdev->host.hc[hnptxsts.b.chnum].xfer_len != 0))
|
||||
{
|
||||
|
||||
len = hnptxsts.b.nptxfspcavail * 4;
|
||||
|
||||
if (len > pdev->host.hc[hnptxsts.b.chnum].xfer_len)
|
||||
{
|
||||
/* Last packet */
|
||||
len = pdev->host.hc[hnptxsts.b.chnum].xfer_len;
|
||||
|
||||
intmsk.d32 = 0;
|
||||
intmsk.b.nptxfempty = 1;
|
||||
USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0);
|
||||
}
|
||||
|
||||
len_words = (pdev->host.hc[hnptxsts.b.chnum].xfer_len + 3) / 4;
|
||||
|
||||
USB_OTG_WritePacket (pdev , pdev->host.hc[hnptxsts.b.chnum].xfer_buff, hnptxsts.b.chnum, len);
|
||||
|
||||
pdev->host.hc[hnptxsts.b.chnum].xfer_buff += len;
|
||||
pdev->host.hc[hnptxsts.b.chnum].xfer_len -= len;
|
||||
pdev->host.hc[hnptxsts.b.chnum].xfer_count += len;
|
||||
|
||||
hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS);
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_ptxfempty_ISR
|
||||
* Handles periodic tx fifo empty
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTMSK_TypeDef intmsk;
|
||||
USB_OTG_HPTXSTS_TypeDef hptxsts;
|
||||
uint16_t len_words , len;
|
||||
|
||||
hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS);
|
||||
|
||||
len_words = (pdev->host.hc[hptxsts.b.chnum].xfer_len + 3) / 4;
|
||||
|
||||
while ((hptxsts.b.ptxfspcavail > len_words)&&
|
||||
(pdev->host.hc[hptxsts.b.chnum].xfer_len != 0))
|
||||
{
|
||||
|
||||
len = hptxsts.b.ptxfspcavail * 4;
|
||||
|
||||
if (len > pdev->host.hc[hptxsts.b.chnum].xfer_len)
|
||||
{
|
||||
len = pdev->host.hc[hptxsts.b.chnum].xfer_len;
|
||||
/* Last packet */
|
||||
intmsk.d32 = 0;
|
||||
intmsk.b.ptxfempty = 1;
|
||||
USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0);
|
||||
}
|
||||
|
||||
len_words = (pdev->host.hc[hptxsts.b.chnum].xfer_len + 3) / 4;
|
||||
|
||||
USB_OTG_WritePacket (pdev , pdev->host.hc[hptxsts.b.chnum].xfer_buff, hptxsts.b.chnum, len);
|
||||
|
||||
pdev->host.hc[hptxsts.b.chnum].xfer_buff += len;
|
||||
pdev->host.hc[hptxsts.b.chnum].xfer_len -= len;
|
||||
pdev->host.hc[hptxsts.b.chnum].xfer_count += len;
|
||||
|
||||
hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS);
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_port_ISR
|
||||
* This function determines which interrupt conditions have occurred
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t USB_OTG_USBH_handle_port_ISR (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_HPRT0_TypeDef hprt0;
|
||||
USB_OTG_HPRT0_TypeDef hprt0_dup;
|
||||
USB_OTG_HCFG_TypeDef hcfg;
|
||||
uint32_t do_reset = 0;
|
||||
uint32_t retval = 0;
|
||||
|
||||
hcfg.d32 = 0;
|
||||
hprt0.d32 = 0;
|
||||
hprt0_dup.d32 = 0;
|
||||
|
||||
hprt0.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0);
|
||||
hprt0_dup.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0);
|
||||
|
||||
/* Clear the interrupt bits in GINTSTS */
|
||||
|
||||
hprt0_dup.b.prtena = 0;
|
||||
hprt0_dup.b.prtconndet = 0;
|
||||
hprt0_dup.b.prtenchng = 0;
|
||||
hprt0_dup.b.prtovrcurrchng = 0;
|
||||
|
||||
/* Port Connect Detected */
|
||||
if (hprt0.b.prtconndet)
|
||||
{
|
||||
pdev->host.port_cb->Connect(pdev);
|
||||
hprt0_dup.b.prtconndet = 1;
|
||||
do_reset = 1;
|
||||
retval |= 1;
|
||||
}
|
||||
|
||||
/* Port Enable Changed */
|
||||
if (hprt0.b.prtenchng)
|
||||
{
|
||||
hprt0_dup.b.prtenchng = 1;
|
||||
if (hprt0.b.prtena == 1)
|
||||
{
|
||||
pdev->host.ConnSts = 1;
|
||||
|
||||
if ((hprt0.b.prtspd == HPRT0_PRTSPD_LOW_SPEED) ||
|
||||
(hprt0.b.prtspd == HPRT0_PRTSPD_FULL_SPEED))
|
||||
{
|
||||
|
||||
hcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HCFG);
|
||||
|
||||
if (hprt0.b.prtspd == HPRT0_PRTSPD_LOW_SPEED)
|
||||
{
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 6000 );
|
||||
if (hcfg.b.fslspclksel != HCFG_6_MHZ)
|
||||
{
|
||||
if(pdev->cfg.coreID == USB_OTG_FS_CORE_ID)
|
||||
{
|
||||
USB_OTG_InitFSLSPClkSel(pdev ,HCFG_6_MHZ );
|
||||
}
|
||||
do_reset = 1;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 48000 );
|
||||
if (hcfg.b.fslspclksel != HCFG_48_MHZ)
|
||||
{
|
||||
USB_OTG_InitFSLSPClkSel(pdev ,HCFG_48_MHZ );
|
||||
do_reset = 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
do_reset = 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
/* Overcurrent Change Interrupt */
|
||||
if (hprt0.b.prtovrcurrchng)
|
||||
{
|
||||
hprt0_dup.b.prtovrcurrchng = 1;
|
||||
retval |= 1;
|
||||
}
|
||||
if (do_reset)
|
||||
{
|
||||
USB_OTG_ResetPort(pdev);
|
||||
|
||||
}
|
||||
/* Clear Port Interrupts */
|
||||
USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0_dup.d32);
|
||||
|
||||
return retval;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_hc_n_Out_ISR
|
||||
* Handles interrupt for a specific Host Channel
|
||||
* @param pdev: Selected device
|
||||
* @param hc_num: Channel number
|
||||
* @retval status
|
||||
*/
|
||||
uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t num)
|
||||
{
|
||||
|
||||
USB_OTG_HCINTn_TypeDef hcint;
|
||||
USB_OTG_HCGINTMSK_TypeDef hcintmsk;
|
||||
USB_OTG_HC_REGS *hcreg;
|
||||
USB_OTG_HCCHAR_TypeDef hcchar;
|
||||
|
||||
hcreg = pdev->regs.HC_REGS[num];
|
||||
hcint.d32 = USB_OTG_READ_REG32(&hcreg->HCINT);
|
||||
hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCGINTMSK);
|
||||
hcint.d32 = hcint.d32 & hcintmsk.d32;
|
||||
|
||||
hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCCHAR);
|
||||
|
||||
if (hcint.b.ahberr)
|
||||
{
|
||||
CLEAR_HC_INT(hcreg ,ahberr);
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
}
|
||||
else if (hcint.b.ack)
|
||||
{
|
||||
CLEAR_HC_INT(hcreg , ack);
|
||||
}
|
||||
|
||||
else if (hcint.b.xfercompl)
|
||||
{
|
||||
pdev->host.ErrCnt[num] = 0;
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
CLEAR_HC_INT(hcreg , xfercompl);
|
||||
pdev->host.HC_Status[num] = HC_XFRC;
|
||||
}
|
||||
|
||||
else if (hcint.b.stall)
|
||||
{
|
||||
CLEAR_HC_INT(hcreg , stall);
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
pdev->host.HC_Status[num] = HC_STALL;
|
||||
}
|
||||
|
||||
else if (hcint.b.nak)
|
||||
{
|
||||
pdev->host.ErrCnt[num] = 0;
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
CLEAR_HC_INT(hcreg , nak);
|
||||
pdev->host.HC_Status[num] = HC_NAK;
|
||||
}
|
||||
|
||||
else if (hcint.b.xacterr)
|
||||
{
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
pdev->host.ErrCnt[num] ++;
|
||||
pdev->host.HC_Status[num] = HC_XACTERR;
|
||||
CLEAR_HC_INT(hcreg , xacterr);
|
||||
}
|
||||
else if (hcint.b.nyet)
|
||||
{
|
||||
pdev->host.ErrCnt[num] = 0;
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
CLEAR_HC_INT(hcreg , nyet);
|
||||
pdev->host.HC_Status[num] = HC_NYET;
|
||||
}
|
||||
else if (hcint.b.datatglerr)
|
||||
{
|
||||
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
CLEAR_HC_INT(hcreg , nak);
|
||||
pdev->host.HC_Status[num] = HC_DATATGLERR;
|
||||
|
||||
CLEAR_HC_INT(hcreg , datatglerr);
|
||||
}
|
||||
else if (hcint.b.chhltd)
|
||||
{
|
||||
MASK_HOST_INT_CHH (num);
|
||||
|
||||
if(pdev->host.HC_Status[num] == HC_XFRC)
|
||||
{
|
||||
pdev->host.URB_State[num] = URB_DONE;
|
||||
|
||||
if (hcchar.b.eptype == EP_TYPE_BULK)
|
||||
{
|
||||
pdev->host.hc[num].toggle_out ^= 1;
|
||||
}
|
||||
}
|
||||
else if(pdev->host.HC_Status[num] == HC_NAK)
|
||||
{
|
||||
pdev->host.URB_State[num] = URB_NOTREADY;
|
||||
}
|
||||
else if(pdev->host.HC_Status[num] == HC_NYET)
|
||||
{
|
||||
if(pdev->host.hc[num].do_ping == 1)
|
||||
{
|
||||
USB_OTG_HC_DoPing(pdev, num);
|
||||
}
|
||||
pdev->host.URB_State[num] = URB_NOTREADY;
|
||||
}
|
||||
else if(pdev->host.HC_Status[num] == HC_STALL)
|
||||
{
|
||||
pdev->host.URB_State[num] = URB_STALL;
|
||||
}
|
||||
else if(pdev->host.HC_Status[num] == HC_XACTERR)
|
||||
{
|
||||
if (pdev->host.ErrCnt[num] == 3)
|
||||
{
|
||||
pdev->host.URB_State[num] = URB_ERROR;
|
||||
pdev->host.ErrCnt[num] = 0;
|
||||
}
|
||||
}
|
||||
CLEAR_HC_INT(hcreg , chhltd);
|
||||
}
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_hc_n_In_ISR
|
||||
* Handles interrupt for a specific Host Channel
|
||||
* @param pdev: Selected device
|
||||
* @param hc_num: Channel number
|
||||
* @retval status
|
||||
*/
|
||||
uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t num)
|
||||
{
|
||||
USB_OTG_HCINTn_TypeDef hcint;
|
||||
USB_OTG_HCGINTMSK_TypeDef hcintmsk;
|
||||
USB_OTG_HCCHAR_TypeDef hcchar;
|
||||
USB_OTG_HCTSIZn_TypeDef hctsiz;
|
||||
USB_OTG_HC_REGS *hcreg;
|
||||
|
||||
|
||||
hcreg = pdev->regs.HC_REGS[num];
|
||||
hcint.d32 = USB_OTG_READ_REG32(&hcreg->HCINT);
|
||||
hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCGINTMSK);
|
||||
hcint.d32 = hcint.d32 & hcintmsk.d32;
|
||||
hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCCHAR);
|
||||
hcintmsk.d32 = 0;
|
||||
|
||||
|
||||
if (hcint.b.ahberr)
|
||||
{
|
||||
CLEAR_HC_INT(hcreg ,ahberr);
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
}
|
||||
else if (hcint.b.ack)
|
||||
{
|
||||
CLEAR_HC_INT(hcreg ,ack);
|
||||
}
|
||||
|
||||
else if (hcint.b.stall)
|
||||
{
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
pdev->host.HC_Status[num] = HC_STALL;
|
||||
CLEAR_HC_INT(hcreg , nak); /* Clear the NAK Condition */
|
||||
CLEAR_HC_INT(hcreg , stall); /* Clear the STALL Condition */
|
||||
hcint.b.nak = 0; /* NOTE: When there is a 'stall', reset also nak,
|
||||
else, the pdev->host.HC_Status = HC_STALL
|
||||
will be overwritten by 'nak' in code below */
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
}
|
||||
else if (hcint.b.datatglerr)
|
||||
{
|
||||
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
CLEAR_HC_INT(hcreg , nak);
|
||||
pdev->host.HC_Status[num] = HC_DATATGLERR;
|
||||
CLEAR_HC_INT(hcreg , datatglerr);
|
||||
}
|
||||
|
||||
if (hcint.b.frmovrun)
|
||||
{
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
CLEAR_HC_INT(hcreg ,frmovrun);
|
||||
}
|
||||
|
||||
else if (hcint.b.xfercompl)
|
||||
{
|
||||
|
||||
if (pdev->cfg.dma_enable == 1)
|
||||
{
|
||||
hctsiz.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCTSIZ);
|
||||
pdev->host.XferCnt[num] = pdev->host.hc[num].xfer_len - hctsiz.b.xfersize;
|
||||
}
|
||||
|
||||
pdev->host.HC_Status[num] = HC_XFRC;
|
||||
pdev->host.ErrCnt [num]= 0;
|
||||
CLEAR_HC_INT(hcreg , xfercompl);
|
||||
|
||||
if ((hcchar.b.eptype == EP_TYPE_CTRL)||
|
||||
(hcchar.b.eptype == EP_TYPE_BULK))
|
||||
{
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
CLEAR_HC_INT(hcreg , nak);
|
||||
pdev->host.hc[num].toggle_in ^= 1;
|
||||
|
||||
}
|
||||
else if(hcchar.b.eptype == EP_TYPE_INTR)
|
||||
{
|
||||
hcchar.b.oddfrm = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[num]->HCCHAR, hcchar.d32);
|
||||
pdev->host.URB_State[num] = URB_DONE;
|
||||
}
|
||||
|
||||
}
|
||||
else if (hcint.b.chhltd)
|
||||
{
|
||||
MASK_HOST_INT_CHH (num);
|
||||
|
||||
if(pdev->host.HC_Status[num] == HC_XFRC)
|
||||
{
|
||||
pdev->host.URB_State[num] = URB_DONE;
|
||||
}
|
||||
|
||||
else if (pdev->host.HC_Status[num] == HC_STALL)
|
||||
{
|
||||
pdev->host.URB_State[num] = URB_STALL;
|
||||
}
|
||||
|
||||
else if((pdev->host.HC_Status[num] == HC_XACTERR) ||
|
||||
(pdev->host.HC_Status[num] == HC_DATATGLERR))
|
||||
{
|
||||
pdev->host.ErrCnt[num] = 0;
|
||||
pdev->host.URB_State[num] = URB_ERROR;
|
||||
|
||||
}
|
||||
else if(hcchar.b.eptype == EP_TYPE_INTR)
|
||||
{
|
||||
pdev->host.hc[num].toggle_in ^= 1;
|
||||
}
|
||||
|
||||
CLEAR_HC_INT(hcreg , chhltd);
|
||||
|
||||
}
|
||||
else if (hcint.b.xacterr)
|
||||
{
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
pdev->host.ErrCnt[num] ++;
|
||||
pdev->host.HC_Status[num] = HC_XACTERR;
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
CLEAR_HC_INT(hcreg , xacterr);
|
||||
|
||||
}
|
||||
else if (hcint.b.nak)
|
||||
{
|
||||
if(hcchar.b.eptype == EP_TYPE_INTR)
|
||||
{
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
CLEAR_HC_INT(hcreg , nak);
|
||||
}
|
||||
else if ((hcchar.b.eptype == EP_TYPE_CTRL)||
|
||||
(hcchar.b.eptype == EP_TYPE_BULK))
|
||||
{
|
||||
/* re-activate the channel */
|
||||
hcchar.b.chen = 1;
|
||||
hcchar.b.chdis = 0;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[num]->HCCHAR, hcchar.d32);
|
||||
}
|
||||
pdev->host.HC_Status[num] = HC_NAK;
|
||||
}
|
||||
|
||||
|
||||
return 1;
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_rx_qlvl_ISR
|
||||
* Handles the Rx Status Queue Level Interrupt
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
|
||||
static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GRXFSTS_TypeDef grxsts;
|
||||
USB_OTG_GINTMSK_TypeDef intmsk;
|
||||
USB_OTG_HCTSIZn_TypeDef hctsiz;
|
||||
USB_OTG_HCCHAR_TypeDef hcchar;
|
||||
__IO uint8_t channelnum =0;
|
||||
uint32_t count;
|
||||
|
||||
/* Disable the Rx Status Queue Level interrupt */
|
||||
intmsk.d32 = 0;
|
||||
intmsk.b.rxstsqlvl = 1;
|
||||
USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0);
|
||||
|
||||
grxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GRXSTSP);
|
||||
channelnum = grxsts.b.chnum;
|
||||
hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[channelnum]->HCCHAR);
|
||||
|
||||
switch (grxsts.b.pktsts)
|
||||
{
|
||||
case GRXSTS_PKTSTS_IN:
|
||||
/* Read the data into the host buffer. */
|
||||
if ((grxsts.b.bcnt > 0) && (pdev->host.hc[channelnum].xfer_buff != (void *)0))
|
||||
{
|
||||
|
||||
USB_OTG_ReadPacket(pdev, pdev->host.hc[channelnum].xfer_buff, grxsts.b.bcnt);
|
||||
/*manage multiple Xfer */
|
||||
pdev->host.hc[grxsts.b.chnum].xfer_buff += grxsts.b.bcnt;
|
||||
pdev->host.hc[grxsts.b.chnum].xfer_count += grxsts.b.bcnt;
|
||||
|
||||
|
||||
count = pdev->host.hc[channelnum].xfer_count;
|
||||
pdev->host.XferCnt[channelnum] = count;
|
||||
|
||||
hctsiz.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[channelnum]->HCTSIZ);
|
||||
if(hctsiz.b.pktcnt > 0)
|
||||
{
|
||||
/* re-activate the channel when more packets are expected */
|
||||
hcchar.b.chen = 1;
|
||||
hcchar.b.chdis = 0;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[channelnum]->HCCHAR, hcchar.d32);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case GRXSTS_PKTSTS_IN_XFER_COMP:
|
||||
|
||||
case GRXSTS_PKTSTS_DATA_TOGGLE_ERR:
|
||||
case GRXSTS_PKTSTS_CH_HALTED:
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
/* Enable the Rx Status Queue Level interrupt */
|
||||
intmsk.b.rxstsqlvl = 1;
|
||||
USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, 0, intmsk.d32);
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR
|
||||
* Handles the incomplete Periodic transfer Interrupt
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
static uint32_t USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
USB_OTG_HCCHAR_TypeDef hcchar;
|
||||
|
||||
|
||||
|
||||
|
||||
hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[0]->HCCHAR);
|
||||
hcchar.b.chen = 1;
|
||||
hcchar.b.chdis = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[0]->HCCHAR, hcchar.d32);
|
||||
|
||||
gintsts.d32 = 0;
|
||||
/* Clear interrupt */
|
||||
gintsts.b.incomplisoout = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
||||
|
175
lib/main/STM32_USB_OTG_Driver/src/usb_otg.c
Normal file
175
lib/main/STM32_USB_OTG_Driver/src/usb_otg.c
Normal file
|
@ -0,0 +1,175 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usb_otg.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief OTG Core Layer
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usb_defines.h"
|
||||
#include "usb_regs.h"
|
||||
#include "usb_core.h"
|
||||
#include "usb_otg.h"
|
||||
|
||||
/** @addtogroup USB_OTG_DRIVER
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup USB_OTG
|
||||
* @brief This file is the interface between EFSL ans Host mass-storage class
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_OTG_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_OTG_Private_TypesDefinitions
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/** @defgroup USB_OTG_Private_Macros
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_OTG_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_OTG_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
|
||||
static uint32_t USB_OTG_Read_itr(USB_OTG_CORE_HANDLE *pdev);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USB_OTG_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/* OTG Interrupt Handler */
|
||||
|
||||
|
||||
/**
|
||||
* @brief STM32_USBO_OTG_ISR_Handler
|
||||
*
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
uint32_t STM32_USBO_OTG_ISR_Handler(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
uint32_t retval = 0;
|
||||
USB_OTG_GINTSTS_TypeDef gintsts ;
|
||||
gintsts.d32 = 0;
|
||||
|
||||
gintsts.d32 = USB_OTG_Read_itr(pdev);
|
||||
if (gintsts.d32 == 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
if (gintsts.b.otgintr)
|
||||
{
|
||||
retval |= 1;//USB_OTG_HandleOTG_ISR(pdev);
|
||||
}
|
||||
if (gintsts.b.conidstschng)
|
||||
{
|
||||
retval |= 2;//USB_OTG_HandleConnectorIDStatusChange_ISR(pdev);
|
||||
}
|
||||
if (gintsts.b.sessreqintr)
|
||||
{
|
||||
retval |= 3;//USB_OTG_HandleSessionRequest_ISR(pdev);
|
||||
}
|
||||
return retval;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_Read_itr
|
||||
* returns the Core Interrupt register
|
||||
* @param None
|
||||
* @retval : status
|
||||
*/
|
||||
static uint32_t USB_OTG_Read_itr(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
USB_OTG_GINTMSK_TypeDef gintmsk;
|
||||
USB_OTG_GINTMSK_TypeDef gintmsk_common;
|
||||
|
||||
|
||||
gintsts.d32 = 0;
|
||||
gintmsk.d32 = 0;
|
||||
gintmsk_common.d32 = 0;
|
||||
|
||||
/* OTG interrupts */
|
||||
gintmsk_common.b.sessreqintr = 1;
|
||||
gintmsk_common.b.conidstschng = 1;
|
||||
gintmsk_common.b.otgintr = 1;
|
||||
|
||||
gintsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTSTS);
|
||||
gintmsk.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTMSK);
|
||||
return ((gintsts.d32 & gintmsk.d32 ) & gintmsk_common.d32);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_GetCurrentState
|
||||
* Return current OTG State
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
uint32_t USB_OTG_GetCurrentState (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
return pdev->otg.OTG_State;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
Loading…
Add table
Add a link
Reference in a new issue