mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 11:59:58 +03:00
STM32F4: Updating USB Lib
This commit is contained in:
parent
bca73007d6
commit
a5d46fd084
27 changed files with 2407 additions and 1820 deletions
|
@ -2,21 +2,27 @@
|
|||
******************************************************************************
|
||||
* @file usb_bsp.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @version V2.2.0
|
||||
* @date 09-November-2015
|
||||
* @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 2015 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
|
@ -80,7 +86,7 @@
|
|||
|
||||
/**
|
||||
* @brief USB_OTG_BSP_Init
|
||||
* Initilizes BSP configurations
|
||||
* Initializes BSP configurations
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
|
@ -91,7 +97,7 @@ void USB_OTG_BSP_Init(void)
|
|||
}
|
||||
/**
|
||||
* @brief USB_OTG_BSP_EnableInterrupt
|
||||
* Enabele USB Global interrupt
|
||||
* Enable USB Global interrupt
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
|
@ -125,6 +131,7 @@ void USB_OTG_BSP_DriveVBUS(uint32_t speed, uint8_t state)
|
|||
void USB_OTG_BSP_ConfigVBUS(uint32_t speed)
|
||||
{
|
||||
(void)speed;
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -199,4 +206,4 @@ void USB_OTG_BSP_TimerIRQ (void)
|
|||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
|
|
@ -2,20 +2,26 @@
|
|||
******************************************************************************
|
||||
* @file usb_core.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @version V2.2.0
|
||||
* @date 09-November-2015
|
||||
* @brief USB-OTG Core Layer
|
||||
******************************************************************************
|
||||
* @attention
|
||||
* @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 2015 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
|
@ -96,7 +102,7 @@ static void USB_OTG_EnableCommonInt(USB_OTG_CORE_HANDLE *pdev)
|
|||
USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GOTGINT, 0xFFFFFFFF);
|
||||
#endif
|
||||
/* Clear any pending interrupts */
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, 0xFFFFFFFF);
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, 0xBFFFFFFF);
|
||||
/* Enable the interrupts in the INTMSK */
|
||||
int_mask.b.wkupintr = 1;
|
||||
int_mask.b.usbsuspend = 1;
|
||||
|
@ -172,9 +178,10 @@ USB_OTG_STS USB_OTG_WritePacket(USB_OTG_CORE_HANDLE *pdev,
|
|||
|
||||
count32b = (len + 3) / 4;
|
||||
fifo = pdev->regs.DFIFO[ch_ep_num];
|
||||
for (i = 0; i < count32b; i++, src+=4)
|
||||
for (i = 0; i < count32b; i++)
|
||||
{
|
||||
USB_OTG_WRITE_REG32( fifo, *((__packed uint32_t *)src) );
|
||||
src+=4;
|
||||
}
|
||||
}
|
||||
return status;
|
||||
|
@ -197,10 +204,10 @@ void *USB_OTG_ReadPacket(USB_OTG_CORE_HANDLE *pdev,
|
|||
|
||||
__IO uint32_t *fifo = pdev->regs.DFIFO[0];
|
||||
|
||||
for ( i = 0; i < count32b; i++, dest += 4 )
|
||||
for( i = 0; i < count32b; i++)
|
||||
{
|
||||
*(__packed uint32_t *)dest = USB_OTG_READ_REG32(fifo);
|
||||
|
||||
dest += 4 ;
|
||||
}
|
||||
return ((void *)dest);
|
||||
}
|
||||
|
@ -223,7 +230,7 @@ USB_OTG_STS USB_OTG_SelectCore(USB_OTG_CORE_HANDLE *pdev,
|
|||
/* at startup the core is in FS mode */
|
||||
pdev->cfg.speed = USB_OTG_SPEED_FULL;
|
||||
pdev->cfg.mps = USB_OTG_FS_MAX_PACKET_SIZE ;
|
||||
|
||||
|
||||
/* initialize device cfg following its address */
|
||||
if (coreID == USB_OTG_FS_CORE_ID)
|
||||
{
|
||||
|
@ -253,13 +260,9 @@ USB_OTG_STS USB_OTG_SelectCore(USB_OTG_CORE_HANDLE *pdev,
|
|||
#ifdef USB_OTG_ULPI_PHY_ENABLED
|
||||
pdev->cfg.phy_itface = USB_OTG_ULPI_PHY;
|
||||
#else
|
||||
#ifdef USB_OTG_EMBEDDED_PHY_ENABLED
|
||||
#ifdef USB_OTG_EMBEDDED_PHY_ENABLED
|
||||
pdev->cfg.phy_itface = USB_OTG_EMBEDDED_PHY;
|
||||
#else
|
||||
#ifdef USB_OTG_I2C_PHY_ENABLED
|
||||
pdev->cfg.phy_itface = USB_OTG_I2C_PHY;
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
|
||||
|
@ -276,6 +279,11 @@ USB_OTG_STS USB_OTG_SelectCore(USB_OTG_CORE_HANDLE *pdev,
|
|||
|
||||
}
|
||||
|
||||
else
|
||||
{
|
||||
/* Do Nothing */
|
||||
}
|
||||
|
||||
pdev->regs.GREGS = (USB_OTG_GREGS *)(baseAddress + \
|
||||
USB_OTG_CORE_GLOBAL_REGS_OFFSET);
|
||||
pdev->regs.DREGS = (USB_OTG_DREGS *) (baseAddress + \
|
||||
|
@ -323,15 +331,14 @@ USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev)
|
|||
USB_OTG_STS status = USB_OTG_OK;
|
||||
USB_OTG_GUSBCFG_TypeDef usbcfg;
|
||||
USB_OTG_GCCFG_TypeDef gccfg;
|
||||
USB_OTG_GI2CCTL_TypeDef i2cctl;
|
||||
USB_OTG_GAHBCFG_TypeDef ahbcfg;
|
||||
|
||||
#if defined (STM32F446xx) || defined (STM32F469_479xx)
|
||||
USB_OTG_DCTL_TypeDef dctl;
|
||||
#endif
|
||||
usbcfg.d32 = 0;
|
||||
gccfg.d32 = 0;
|
||||
ahbcfg.d32 = 0;
|
||||
|
||||
|
||||
|
||||
if (pdev->cfg.phy_itface == USB_OTG_ULPI_PHY)
|
||||
{
|
||||
gccfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GCCFG);
|
||||
|
@ -351,15 +358,11 @@ USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev)
|
|||
#ifdef USB_OTG_INTERNAL_VBUS_ENABLED
|
||||
usbcfg.b.ulpi_ext_vbus_drv = 0; /* Use internal VBUS */
|
||||
#else
|
||||
#ifdef USB_OTG_EXTERNAL_VBUS_ENABLED
|
||||
#ifdef USB_OTG_EXTERNAL_VBUS_ENABLED
|
||||
usbcfg.b.ulpi_ext_vbus_drv = 1; /* Use external VBUS */
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
usbcfg.b.term_sel_dl_pulse = 0; /* Data line pulsing using utmi_txvalid */
|
||||
usbcfg.b.ulpi_utmi_sel = 1; /* ULPI seleInterfacect */
|
||||
|
||||
usbcfg.b.phyif = 0; /* 8 bits */
|
||||
usbcfg.b.ddrsel = 0; /* single data rate */
|
||||
|
||||
usbcfg.b.ulpi_fsls = 0;
|
||||
usbcfg.b.ulpi_clk_sus_m = 0;
|
||||
|
@ -377,7 +380,7 @@ USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev)
|
|||
|
||||
}
|
||||
}
|
||||
else /* FS interface (embedded Phy or I2C Phy) */
|
||||
else /* FS interface (embedded Phy) */
|
||||
{
|
||||
|
||||
usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);;
|
||||
|
@ -385,16 +388,12 @@ USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev)
|
|||
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GUSBCFG, usbcfg.d32);
|
||||
/* Reset after a PHY select and set Host mode */
|
||||
USB_OTG_CoreReset(pdev);
|
||||
/* Enable the I2C interface and deactivate the power down*/
|
||||
/* Deactivate the power down*/
|
||||
gccfg.d32 = 0;
|
||||
gccfg.b.pwdn = 1;
|
||||
|
||||
if(pdev->cfg.phy_itface == USB_OTG_I2C_PHY)
|
||||
{
|
||||
gccfg.b.i2cifen = 1;
|
||||
}
|
||||
gccfg.b.vbussensingA = 1 ;
|
||||
gccfg.b.vbussensingB = 1 ;
|
||||
gccfg.b.vbussensingB = 1 ;
|
||||
|
||||
#ifndef VBUS_SENSING_ENABLED
|
||||
gccfg.b.disablevbussensing = 1;
|
||||
#endif
|
||||
|
@ -406,32 +405,6 @@ USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev)
|
|||
|
||||
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GCCFG, gccfg.d32);
|
||||
USB_OTG_BSP_mDelay(20);
|
||||
/* Program GUSBCFG.OtgUtmifsSel to I2C*/
|
||||
usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);
|
||||
|
||||
if(pdev->cfg.phy_itface == USB_OTG_I2C_PHY)
|
||||
{
|
||||
usbcfg.b.otgutmifssel = 1;
|
||||
}
|
||||
|
||||
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GUSBCFG, usbcfg.d32);
|
||||
|
||||
if(pdev->cfg.phy_itface == USB_OTG_I2C_PHY)
|
||||
{
|
||||
/*Program GI2CCTL.I2CEn*/
|
||||
i2cctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GI2CCTL);
|
||||
i2cctl.b.i2cdevaddr = 1;
|
||||
i2cctl.b.i2cen = 0;
|
||||
i2cctl.b.dat_se0 = 1;
|
||||
i2cctl.b.addr = 0x2D;
|
||||
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GI2CCTL, i2cctl.d32);
|
||||
|
||||
USB_OTG_BSP_mDelay(200);
|
||||
|
||||
i2cctl.b.i2cen = 1;
|
||||
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GI2CCTL, i2cctl.d32);
|
||||
USB_OTG_BSP_mDelay(200);
|
||||
}
|
||||
}
|
||||
/* case the HS core is working in FS mode */
|
||||
if(pdev->cfg.dma_enable == 1)
|
||||
|
@ -451,6 +424,20 @@ USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev)
|
|||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, usbcfg.d32);
|
||||
USB_OTG_EnableCommonInt(pdev);
|
||||
#endif
|
||||
|
||||
#if defined (STM32F446xx) || defined (STM32F469_479xx)
|
||||
usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);
|
||||
usbcfg.b.srpcap = 1;
|
||||
/*clear sdis bit in 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);
|
||||
dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL);
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, usbcfg.d32);
|
||||
USB_OTG_EnableCommonInt(pdev);
|
||||
#endif
|
||||
|
||||
return status;
|
||||
}
|
||||
/**
|
||||
|
@ -573,6 +560,11 @@ USB_OTG_STS USB_OTG_SetCurrentMode(USB_OTG_CORE_HANDLE *pdev , uint8_t mode)
|
|||
usbcfg.b.force_dev = 1;
|
||||
}
|
||||
|
||||
else
|
||||
{
|
||||
/* Do Nothing */
|
||||
}
|
||||
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, usbcfg.d32);
|
||||
USB_OTG_BSP_mDelay(50);
|
||||
return status;
|
||||
|
@ -670,7 +662,15 @@ USB_OTG_STS USB_OTG_CoreInitHost(USB_OTG_CORE_HANDLE *pdev)
|
|||
USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, 0);
|
||||
|
||||
/* Initialize Host Configuration Register */
|
||||
USB_OTG_InitFSLSPClkSel(pdev , HCFG_48_MHZ); /* in init phase */
|
||||
if (pdev->cfg.phy_itface == USB_OTG_ULPI_PHY)
|
||||
{
|
||||
USB_OTG_InitFSLSPClkSel(pdev , HCFG_30_60_MHZ);
|
||||
}
|
||||
else
|
||||
{
|
||||
USB_OTG_InitFSLSPClkSel(pdev , HCFG_48_MHZ);
|
||||
}
|
||||
USB_OTG_ResetPort(pdev);
|
||||
|
||||
hcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HCFG);
|
||||
hcfg.b.fslssupp = 0;
|
||||
|
@ -693,9 +693,9 @@ USB_OTG_STS USB_OTG_CoreInitHost(USB_OTG_CORE_HANDLE *pdev)
|
|||
}
|
||||
#endif
|
||||
#ifdef USB_OTG_HS_CORE
|
||||
if (pdev->cfg.coreID == USB_OTG_HS_CORE_ID)
|
||||
if (pdev->cfg.coreID == USB_OTG_HS_CORE_ID)
|
||||
{
|
||||
/* set Rx FIFO size */
|
||||
/* set Rx FIFO size */
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GRXFSIZ, RX_FIFO_HS_SIZE);
|
||||
nptxfifosize.b.startaddr = RX_FIFO_HS_SIZE;
|
||||
nptxfifosize.b.depth = TXH_NP_HS_FIFOSIZ;
|
||||
|
@ -722,7 +722,7 @@ USB_OTG_STS USB_OTG_CoreInitHost(USB_OTG_CORE_HANDLE *pdev)
|
|||
for (i = 0; i < pdev->cfg.host_channels; i++)
|
||||
{
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.HC_REGS[i]->HCINT, 0xFFFFFFFF );
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.HC_REGS[i]->HCGINTMSK, 0 );
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.HC_REGS[i]->HCINTMSK, 0 );
|
||||
}
|
||||
#ifndef USE_OTG_MODE
|
||||
USB_OTG_DriveVbus(pdev, 1);
|
||||
|
@ -796,12 +796,19 @@ USB_OTG_STS USB_OTG_EnableHostInt(USB_OTG_CORE_HANDLE *pdev)
|
|||
{
|
||||
intmsk.b.rxstsqlvl = 1;
|
||||
}
|
||||
intmsk.b.portintr = 1;
|
||||
intmsk.b.hcintr = 1;
|
||||
intmsk.b.disconnect = 1;
|
||||
intmsk.b.sofintr = 1;
|
||||
intmsk.b.incomplisoout = 1;
|
||||
|
||||
|
||||
intmsk.b.incomplisoout = 1;
|
||||
intmsk.b.hcintr = 1;
|
||||
intmsk.b.portintr = 1;
|
||||
USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, intmsk.d32, intmsk.d32);
|
||||
|
||||
intmsk.d32 = 0;
|
||||
|
||||
intmsk.b.disconnect = 1;
|
||||
|
||||
intmsk.b.sofintr = 1;
|
||||
USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, intmsk.d32, 0);
|
||||
return status;
|
||||
}
|
||||
|
||||
|
@ -865,7 +872,7 @@ uint32_t USB_OTG_ResetPort(USB_OTG_CORE_HANDLE *pdev)
|
|||
hprt0.d32 = USB_OTG_ReadHPRT0(pdev);
|
||||
hprt0.b.prtrst = 1;
|
||||
USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32);
|
||||
USB_OTG_BSP_mDelay (10); /* See Note #1 */
|
||||
USB_OTG_BSP_mDelay (100); /* See Note #1 */
|
||||
hprt0.b.prtrst = 0;
|
||||
USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32);
|
||||
USB_OTG_BSP_mDelay (20);
|
||||
|
@ -883,7 +890,7 @@ USB_OTG_STS USB_OTG_HC_Init(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
|
|||
{
|
||||
USB_OTG_STS status = USB_OTG_OK;
|
||||
uint32_t intr_enable = 0;
|
||||
USB_OTG_HCGINTMSK_TypeDef hcintmsk;
|
||||
USB_OTG_HCINTMSK_TypeDef hcintmsk;
|
||||
USB_OTG_GINTMSK_TypeDef gintmsk;
|
||||
USB_OTG_HCCHAR_TypeDef hcchar;
|
||||
USB_OTG_HCINTn_TypeDef hcint;
|
||||
|
@ -955,7 +962,7 @@ USB_OTG_STS USB_OTG_HC_Init(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
|
|||
}
|
||||
|
||||
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCGINTMSK, hcintmsk.d32);
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, hcintmsk.d32);
|
||||
|
||||
|
||||
/* Enable the top level host channel interrupt. */
|
||||
|
@ -1048,11 +1055,11 @@ USB_OTG_STS USB_OTG_HC_StartXfer(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
|
|||
hcchar.b.chen = 1;
|
||||
hcchar.b.chdis = 0;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32);
|
||||
|
||||
|
||||
if (pdev->cfg.dma_enable == 0) /* Slave mode */
|
||||
{
|
||||
if((pdev->host.hc[hc_num].ep_is_in == 0) &&
|
||||
(pdev->host.hc[hc_num].xfer_len > 0))
|
||||
(pdev->host.hc[hc_num].xfer_len > 0))
|
||||
{
|
||||
switch(pdev->host.hc[hc_num].ep_type)
|
||||
{
|
||||
|
@ -1116,7 +1123,7 @@ USB_OTG_STS USB_OTG_HC_Halt(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
|
|||
nptxsts.d32 = 0;
|
||||
hptxsts.d32 = 0;
|
||||
hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR);
|
||||
hcchar.b.chen = 1;
|
||||
|
||||
hcchar.b.chdis = 1;
|
||||
|
||||
/* Check for space in the request queue to issue the halt. */
|
||||
|
@ -1126,6 +1133,7 @@ USB_OTG_STS USB_OTG_HC_Halt(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
|
|||
if (nptxsts.b.nptxqspcavail == 0)
|
||||
{
|
||||
hcchar.b.chen = 0;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32);
|
||||
}
|
||||
}
|
||||
else
|
||||
|
@ -1134,8 +1142,10 @@ USB_OTG_STS USB_OTG_HC_Halt(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
|
|||
if (hptxsts.b.ptxqspcavail == 0)
|
||||
{
|
||||
hcchar.b.chen = 0;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32);
|
||||
}
|
||||
}
|
||||
hcchar.b.chen = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32);
|
||||
return status;
|
||||
}
|
||||
|
@ -1150,7 +1160,7 @@ USB_OTG_STS USB_OTG_HC_DoPing(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
|
|||
USB_OTG_STS status = USB_OTG_OK;
|
||||
USB_OTG_HCCHAR_TypeDef hcchar;
|
||||
USB_OTG_HCTSIZn_TypeDef hctsiz;
|
||||
|
||||
|
||||
hctsiz.d32 = 0;
|
||||
hctsiz.b.dopng = 1;
|
||||
hctsiz.b.pktcnt = 1;
|
||||
|
@ -1282,7 +1292,7 @@ USB_OTG_STS USB_OTG_CoreInitDev (USB_OTG_CORE_HANDLE *pdev)
|
|||
|
||||
if(pdev->cfg.phy_itface == USB_OTG_ULPI_PHY)
|
||||
{
|
||||
USB_OTG_InitDevSpeed (pdev , USB_OTG_SPEED_PARAM_HIGH);
|
||||
USB_OTG_InitDevSpeed (pdev , USB_OTG_SPEED_PARAM_HIGH);
|
||||
}
|
||||
else /* set High speed phy in Full speed mode */
|
||||
{
|
||||
|
@ -1405,7 +1415,7 @@ USB_OTG_STS USB_OTG_EnableDevInt(USB_OTG_CORE_HANDLE *pdev)
|
|||
/* Disable all interrupts. */
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTMSK, 0);
|
||||
/* Clear any pending interrupts */
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, 0xFFFFFFFF);
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, 0xBFFFFFFF);
|
||||
/* Enable the common interrupts */
|
||||
USB_OTG_EnableCommonInt(pdev);
|
||||
|
||||
|
@ -1421,7 +1431,7 @@ USB_OTG_STS USB_OTG_EnableDevInt(USB_OTG_CORE_HANDLE *pdev)
|
|||
intmsk.b.inepintr = 1;
|
||||
intmsk.b.outepintr = 1;
|
||||
intmsk.b.sofintr = 1;
|
||||
|
||||
|
||||
intmsk.b.incomplisoin = 1;
|
||||
intmsk.b.incomplisoout = 1;
|
||||
#ifdef VBUS_SENSING_ENABLED
|
||||
|
@ -1460,10 +1470,14 @@ enum USB_OTG_SPEED USB_OTG_GetDeviceSpeed (USB_OTG_CORE_HANDLE *pdev)
|
|||
case DSTS_ENUMSPD_LS_PHY_6MHZ:
|
||||
speed = USB_SPEED_LOW;
|
||||
break;
|
||||
default:
|
||||
speed = USB_SPEED_FULL;
|
||||
break;
|
||||
}
|
||||
|
||||
return speed;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief enables EP0 OUT to receive SETUP packets and configures EP0
|
||||
* for transmitting packets
|
||||
|
@ -1492,6 +1506,9 @@ USB_OTG_STS USB_OTG_EP0Activate(USB_OTG_CORE_HANDLE *pdev)
|
|||
case DSTS_ENUMSPD_LS_PHY_6MHZ:
|
||||
diepctl.b.mps = DEP0CTL_MPS_8;
|
||||
break;
|
||||
default:
|
||||
diepctl.b.mps = DEP0CTL_MPS_64;
|
||||
break;
|
||||
}
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[0]->DIEPCTL, diepctl.d32);
|
||||
dctl.b.cgnpinnak = 1;
|
||||
|
@ -1628,7 +1645,7 @@ USB_OTG_STS USB_OTG_EPStartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep)
|
|||
*/
|
||||
deptsiz.b.xfersize = ep->xfer_len;
|
||||
deptsiz.b.pktcnt = (ep->xfer_len - 1 + ep->maxpacket) / ep->maxpacket;
|
||||
|
||||
|
||||
if (ep->type == EP_TYPE_ISOC)
|
||||
{
|
||||
deptsiz.b.mc = 1;
|
||||
|
@ -1672,7 +1689,7 @@ USB_OTG_STS USB_OTG_EPStartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep)
|
|||
depctl.b.cnak = 1;
|
||||
depctl.b.epena = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[ep->num]->DIEPCTL, depctl.d32);
|
||||
|
||||
|
||||
if (ep->type == EP_TYPE_ISOC)
|
||||
{
|
||||
USB_OTG_WritePacket(pdev, ep->xfer_buff, ep->num, ep->xfer_len);
|
||||
|
@ -1696,6 +1713,7 @@ USB_OTG_STS USB_OTG_EPStartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep)
|
|||
{
|
||||
deptsiz.b.pktcnt = (ep->xfer_len + (ep->maxpacket - 1)) / ep->maxpacket;
|
||||
deptsiz.b.xfersize = deptsiz.b.pktcnt * ep->maxpacket;
|
||||
ep->xfer_len = deptsiz.b.xfersize ;
|
||||
}
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPTSIZ, deptsiz.d32);
|
||||
|
||||
|
@ -2039,13 +2057,13 @@ void USB_OTG_StopDevice(USB_OTG_CORE_HANDLE *pdev)
|
|||
uint32_t i;
|
||||
|
||||
pdev->dev.device_status = 1;
|
||||
|
||||
|
||||
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->DIEPMSK, 0 );
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOEPMSK, 0 );
|
||||
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINTMSK, 0 );
|
||||
|
@ -2075,24 +2093,35 @@ uint32_t USB_OTG_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,USB_OTG_EP *ep)
|
|||
depctl_addr = &(pdev->regs.INEP_REGS[ep->num]->DIEPCTL);
|
||||
depctl.d32 = USB_OTG_READ_REG32(depctl_addr);
|
||||
|
||||
if (depctl.b.stall == 1)
|
||||
if (depctl.b.stall == 1)
|
||||
{
|
||||
Status = USB_OTG_EP_TX_STALL;
|
||||
}
|
||||
else if (depctl.b.naksts == 1)
|
||||
{
|
||||
Status = USB_OTG_EP_TX_NAK;
|
||||
}
|
||||
else
|
||||
{
|
||||
Status = USB_OTG_EP_TX_VALID;
|
||||
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
depctl_addr = &(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL);
|
||||
depctl.d32 = USB_OTG_READ_REG32(depctl_addr);
|
||||
if (depctl.b.stall == 1)
|
||||
if (depctl.b.stall == 1)
|
||||
{
|
||||
Status = USB_OTG_EP_RX_STALL;
|
||||
}
|
||||
else if (depctl.b.naksts == 1)
|
||||
{
|
||||
Status = USB_OTG_EP_RX_NAK;
|
||||
}
|
||||
else
|
||||
{
|
||||
Status = USB_OTG_EP_RX_VALID;
|
||||
}
|
||||
}
|
||||
|
||||
/* Return the current status */
|
||||
|
@ -2112,7 +2141,7 @@ void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t
|
|||
__IO uint32_t *depctl_addr;
|
||||
|
||||
depctl.d32 = 0;
|
||||
|
||||
|
||||
/* Process for IN endpoint */
|
||||
if (ep->is_in == 1)
|
||||
{
|
||||
|
@ -2124,7 +2153,9 @@ void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t
|
|||
USB_OTG_EPSetStall(pdev, ep); return;
|
||||
}
|
||||
else if (Status == USB_OTG_EP_TX_NAK)
|
||||
{
|
||||
depctl.b.snak = 1;
|
||||
}
|
||||
else if (Status == USB_OTG_EP_TX_VALID)
|
||||
{
|
||||
if (depctl.b.stall == 1)
|
||||
|
@ -2138,7 +2169,14 @@ void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t
|
|||
depctl.b.epena = 1;
|
||||
}
|
||||
else if (Status == USB_OTG_EP_TX_DIS)
|
||||
{
|
||||
depctl.b.usbactep = 0;
|
||||
}
|
||||
|
||||
else
|
||||
{
|
||||
/* Do Nothing */
|
||||
}
|
||||
}
|
||||
else /* Process for OUT endpoint */
|
||||
{
|
||||
|
@ -2149,7 +2187,9 @@ void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t
|
|||
depctl.b.stall = 1;
|
||||
}
|
||||
else if (Status == USB_OTG_EP_RX_NAK)
|
||||
{
|
||||
depctl.b.snak = 1;
|
||||
}
|
||||
else if (Status == USB_OTG_EP_RX_VALID)
|
||||
{
|
||||
if (depctl.b.stall == 1)
|
||||
|
@ -2166,8 +2206,13 @@ void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t
|
|||
{
|
||||
depctl.b.usbactep = 0;
|
||||
}
|
||||
|
||||
else
|
||||
{
|
||||
/* Do Nothing */
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
USB_OTG_WRITE_REG32(depctl_addr, depctl.d32);
|
||||
}
|
||||
|
||||
|
@ -2184,4 +2229,4 @@ void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t
|
|||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
|
|
@ -2,20 +2,26 @@
|
|||
******************************************************************************
|
||||
* @file usb_dcd.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @version V2.2.0
|
||||
* @date 09-November-2015
|
||||
* @brief Peripheral Device Interface Layer
|
||||
******************************************************************************
|
||||
* @attention
|
||||
* @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 2015 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
|
@ -101,7 +107,7 @@ void DCD_Init(USB_OTG_CORE_HANDLE *pdev ,
|
|||
ep->is_in = 1;
|
||||
ep->num = i;
|
||||
ep->tx_fifo_num = i;
|
||||
/* Control until ep is actvated */
|
||||
/* Control until ep is activated */
|
||||
ep->type = EP_TYPE_CTRL;
|
||||
ep->maxpacket = USB_OTG_MAX_EP0_SIZE;
|
||||
ep->xfer_buff = 0;
|
||||
|
@ -123,18 +129,28 @@ void DCD_Init(USB_OTG_CORE_HANDLE *pdev ,
|
|||
}
|
||||
|
||||
USB_OTG_DisableGlobalInt(pdev);
|
||||
|
||||
#if defined (STM32F446xx) || defined (STM32F469_479xx)
|
||||
|
||||
/* Force Device Mode*/
|
||||
USB_OTG_SetCurrentMode(pdev, DEVICE_MODE);
|
||||
|
||||
/*Init the Core (common init.) */
|
||||
USB_OTG_CoreInit(pdev);
|
||||
|
||||
#else
|
||||
|
||||
/*Init the Core (common init.) */
|
||||
USB_OTG_CoreInit(pdev);
|
||||
|
||||
/* Force Device Mode*/
|
||||
USB_OTG_SetCurrentMode(pdev, DEVICE_MODE);
|
||||
|
||||
#endif
|
||||
|
||||
/* Init Device */
|
||||
USB_OTG_CoreInitDev(pdev);
|
||||
|
||||
|
||||
/* Enable USB Global interrupt */
|
||||
USB_OTG_EnableGlobalInt(pdev);
|
||||
}
|
||||
|
@ -469,4 +485,4 @@ void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum , uint32_t Statu
|
|||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
|
|
@ -2,20 +2,26 @@
|
|||
******************************************************************************
|
||||
* @file usb_dcd_int.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @version V2.2.0
|
||||
* @date 09-November-2015
|
||||
* @brief Peripheral Device interrupt subroutines
|
||||
******************************************************************************
|
||||
* @attention
|
||||
* @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 2015 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
|
@ -124,8 +130,7 @@ uint32_t USBD_OTG_EP1OUT_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
|
|||
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 - \
|
||||
pdev->dev.out_ep[1].xfer_count = pdev->dev.out_ep[1].xfer_len- \
|
||||
deptsiz.b.xfersize;
|
||||
}
|
||||
/* Inform upper layer: data ready */
|
||||
|
@ -140,11 +145,7 @@ uint32_t USBD_OTG_EP1OUT_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
|
|||
/* 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;
|
||||
}
|
||||
|
||||
|
@ -173,10 +174,6 @@ uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
|
|||
/* 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);
|
||||
|
@ -189,10 +186,6 @@ uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
|
|||
{
|
||||
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);
|
||||
|
@ -200,7 +193,6 @@ uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
|
|||
if (diepint.b.emptyintr)
|
||||
{
|
||||
DCD_WriteEmptyTxFifo(pdev , 1);
|
||||
CLEAR_IN_EP_INTR(1, emptyintr);
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
@ -390,7 +382,9 @@ 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;
|
||||
__IO uint8_t prev_status = 0;
|
||||
|
||||
prev_status = pdev->dev.device_status;
|
||||
USBD_DCD_INT_fops->Suspend (pdev);
|
||||
|
||||
dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS);
|
||||
|
@ -400,7 +394,9 @@ static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev)
|
|||
gintsts.b.usbsuspend = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
|
||||
if((pdev->cfg.low_power) && (dsts.b.suspsts == 1))
|
||||
if((pdev->cfg.low_power) && (dsts.b.suspsts == 1) &&
|
||||
(pdev->dev.connection_status == 1) &&
|
||||
(prev_status == USB_OTG_CONFIGURED))
|
||||
{
|
||||
/* switch-off the clocks */
|
||||
power.d32 = 0;
|
||||
|
@ -434,7 +430,7 @@ static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev)
|
|||
|
||||
while ( ep_intr )
|
||||
{
|
||||
if (ep_intr&0x1) /* In ITR */
|
||||
if ((ep_intr & 0x1) == 0x01) /* In ITR */
|
||||
{
|
||||
diepint.d32 = DCD_ReadDevInEP(pdev , epnum); /* Get In ITR status */
|
||||
if ( diepint.b.xfercompl )
|
||||
|
@ -454,10 +450,6 @@ static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev)
|
|||
}
|
||||
}
|
||||
}
|
||||
if ( diepint.b.ahberr )
|
||||
{
|
||||
CLEAR_IN_EP_INTR(epnum, ahberr);
|
||||
}
|
||||
if ( diepint.b.timeout )
|
||||
{
|
||||
CLEAR_IN_EP_INTR(epnum, timeout);
|
||||
|
@ -466,10 +458,6 @@ static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev)
|
|||
{
|
||||
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);
|
||||
|
@ -480,10 +468,7 @@ static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev)
|
|||
}
|
||||
if (diepint.b.emptyintr)
|
||||
{
|
||||
|
||||
DCD_WriteEmptyTxFifo(pdev , epnum);
|
||||
|
||||
CLEAR_IN_EP_INTR(epnum, emptyintr);
|
||||
}
|
||||
}
|
||||
epnum++;
|
||||
|
@ -549,11 +534,6 @@ static uint32_t DCD_HandleOutEP_ISR(USB_OTG_CORE_HANDLE *pdev)
|
|||
/* 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 )
|
||||
{
|
||||
|
@ -657,6 +637,7 @@ static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev, uint32_t epnum)
|
|||
uint32_t len = 0;
|
||||
uint32_t len32b;
|
||||
txstatus.d32 = 0;
|
||||
uint32_t fifoemptymsk;
|
||||
|
||||
ep = &pdev->dev.in_ep[epnum];
|
||||
|
||||
|
@ -670,8 +651,6 @@ static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev, uint32_t epnum)
|
|||
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)
|
||||
|
@ -691,6 +670,14 @@ static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev, uint32_t epnum)
|
|||
ep->xfer_count += len;
|
||||
|
||||
txstatus.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[epnum]->DTXFSTS);
|
||||
|
||||
/* Mask the TxFIFOEmpty interrupt */
|
||||
if (ep->xfer_len == ep->xfer_count)
|
||||
{
|
||||
fifoemptymsk = 0x1 << ep->num;
|
||||
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK,
|
||||
fifoemptymsk, 0);
|
||||
}
|
||||
}
|
||||
|
||||
return 1;
|
||||
|
@ -739,7 +726,6 @@ static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev)
|
|||
|
||||
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
|
||||
|
@ -748,8 +734,7 @@ static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev)
|
|||
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 );
|
||||
|
@ -781,28 +766,102 @@ static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev)
|
|||
*/
|
||||
static uint32_t DCD_HandleEnumDone_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
uint32_t hclk = 168000000;
|
||||
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
USB_OTG_GUSBCFG_TypeDef gusbcfg;
|
||||
|
||||
RCC_ClocksTypeDef RCC_Clocks;
|
||||
USB_OTG_EP0Activate(pdev);
|
||||
|
||||
/* Set USB turn-around time based on device speed and PHY interface. */
|
||||
/* Get HCLK frequency */
|
||||
RCC_GetClocksFreq(&RCC_Clocks);
|
||||
hclk = RCC_Clocks.HCLK_Frequency;
|
||||
|
||||
/* Clear default TRDT value and Set USB turn-around time based on device speed and PHY interface. */
|
||||
gusbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);
|
||||
gusbcfg.b.usbtrdtim = 0;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, gusbcfg.d32);
|
||||
|
||||
/* 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 ;
|
||||
|
||||
/*USBTRD min For HS device*/
|
||||
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;
|
||||
pdev->cfg.mps = USB_OTG_FS_MAX_PACKET_SIZE ;
|
||||
|
||||
/* The USBTRD is configured according to the tables below, depending on AHB frequency
|
||||
used by application. In the low AHB frequency range it is used to stretch enough the USB response
|
||||
time to IN tokens, the USB turnaround time, so to compensate for the longer AHB read access
|
||||
latency to the Data FIFO */
|
||||
|
||||
if((hclk >= 15000000)&&(hclk < 16000000))
|
||||
{
|
||||
/* hclk Clock Range between 15-16 MHz */
|
||||
gusbcfg.b.usbtrdtim = 0xE;
|
||||
}
|
||||
|
||||
else if((hclk >= 16000000)&&(hclk < 17100000))
|
||||
{
|
||||
/* hclk Clock Range between 16-17.1 MHz */
|
||||
gusbcfg.b.usbtrdtim = 0xD;
|
||||
}
|
||||
|
||||
else if((hclk >= 17100000)&&(hclk < 18400000))
|
||||
{
|
||||
/* hclk Clock Range between 17-18.4 MHz */
|
||||
gusbcfg.b.usbtrdtim = 0xC;
|
||||
}
|
||||
|
||||
else if((hclk >= 18400000)&&(hclk < 20000000))
|
||||
{
|
||||
/* hclk Clock Range between 18.4-20 MHz */
|
||||
gusbcfg.b.usbtrdtim = 0xB;
|
||||
}
|
||||
|
||||
else if((hclk >= 20000000)&&(hclk < 21800000))
|
||||
{
|
||||
/* hclk Clock Range between 20-21.8 MHz */
|
||||
gusbcfg.b.usbtrdtim = 0xA;
|
||||
}
|
||||
|
||||
else if((hclk >= 21800000)&&(hclk < 24000000))
|
||||
{
|
||||
/* hclk Clock Range between 21.8-24 MHz */
|
||||
gusbcfg.b.usbtrdtim = 0x9;
|
||||
}
|
||||
|
||||
else if((hclk >= 24000000)&&(hclk < 26600000))
|
||||
{
|
||||
/* hclk Clock Range between 24-26.6 MHz */
|
||||
gusbcfg.b.usbtrdtim = 0x8;
|
||||
}
|
||||
|
||||
else if((hclk >= 26600000)&&(hclk < 30000000))
|
||||
{
|
||||
/* hclk Clock Range between 26.6-30 MHz */
|
||||
gusbcfg.b.usbtrdtim = 0x7;
|
||||
}
|
||||
|
||||
else if((hclk >= 30000000)&&(hclk < 34300000))
|
||||
{
|
||||
/* hclk Clock Range between 30-34.3 MHz */
|
||||
gusbcfg.b.usbtrdtim= 0x6;
|
||||
}
|
||||
|
||||
else /* if(hclk >= 34300000) */
|
||||
{
|
||||
/* hclk Clock Range between 34.3-168 MHz */
|
||||
gusbcfg.b.usbtrdtim = 0x5;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, gusbcfg.d32);
|
||||
|
||||
/* Clear interrupt */
|
||||
|
@ -869,8 +928,6 @@ static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
|
|||
return v;
|
||||
}
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
@ -883,4 +940,4 @@ static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
|
|||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
|
|
@ -2,20 +2,26 @@
|
|||
******************************************************************************
|
||||
* @file usb_hcd.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @version V2.2.0
|
||||
* @date 09-November-2015
|
||||
* @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 2015 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
|
@ -142,8 +148,8 @@ 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
|
||||
interrupt triggered by the denounce done bit (DBCDNE bit in OTG_FS_GOTGINT),
|
||||
which indicates that the bus is stable again after the electrical denounce
|
||||
caused by the attachment of a pull-up resistor on DP (FS) or DM (LS).
|
||||
*/
|
||||
|
||||
|
@ -163,6 +169,19 @@ uint32_t HCD_IsDeviceConnected(USB_OTG_CORE_HANDLE *pdev)
|
|||
return (pdev->host.ConnSts);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief HCD_IsPortEnabled
|
||||
* This function checks if port is enabled
|
||||
* @param pdev : Selected device
|
||||
* @retval Frame number
|
||||
*
|
||||
*/
|
||||
uint32_t HCD_IsPortEnabled(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
return (pdev->host.PortEnabled);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief HCD_GetCurrentFrame
|
||||
* This function returns the frame number for sof packet
|
||||
|
@ -253,4 +272,4 @@ uint32_t HCD_SubmitRequest (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
|
|||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
|
|
@ -2,20 +2,26 @@
|
|||
******************************************************************************
|
||||
* @file usb_hcd_int.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @version V2.2.0
|
||||
* @date 09-November-2015
|
||||
* @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 2015 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
|
@ -25,62 +31,60 @@
|
|||
#include "usb_hcd_int.h"
|
||||
|
||||
#if defined (__CC_ARM) /*!< ARM Compiler */
|
||||
#pragma O0
|
||||
#elif defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma O0
|
||||
#pragma O0
|
||||
#elif defined (__GNUC__) /*!< GNU Compiler */
|
||||
#pragma GCC optimize ("O0")
|
||||
#pragma GCC optimize ("O0")
|
||||
#elif defined (__TASKING__) /*!< TASKING Compiler */
|
||||
#pragma optimize=0
|
||||
#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.
|
||||
* @{
|
||||
*/
|
||||
* @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);
|
||||
|
@ -96,20 +100,20 @@ 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
|
||||
*/
|
||||
* @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)
|
||||
{
|
||||
|
@ -163,22 +167,22 @@ uint32_t USBH_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
|
|||
|
||||
}
|
||||
|
||||
if (gintsts.b.incomplisoout)
|
||||
{
|
||||
retval |= USB_OTG_USBH_handle_IncompletePeriodicXfer_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
|
||||
*/
|
||||
* @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;
|
||||
|
@ -212,17 +216,18 @@ static uint32_t USB_OTG_USBH_handle_hc_ISR (USB_OTG_CORE_HANDLE *pdev)
|
|||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_otg_hcd_handle_sof_intr
|
||||
* Handles the start-of-frame interrupt in host mode.
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
* @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;
|
||||
|
||||
USBH_HCD_INT_fops->SOF(pdev);
|
||||
|
||||
/* Clear interrupt */
|
||||
gintsts.b.sofintr = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
|
@ -231,19 +236,18 @@ static uint32_t USB_OTG_USBH_handle_sof_ISR (USB_OTG_CORE_HANDLE *pdev)
|
|||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_Disconnect_ISR
|
||||
* Handles disconnect event.
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
* @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);
|
||||
USBH_HCD_INT_fops->DevDisconnected(pdev);
|
||||
|
||||
/* Clear interrupt */
|
||||
gintsts.b.disconnect = 1;
|
||||
|
@ -251,13 +255,15 @@ static uint32_t USB_OTG_USBH_handle_Disconnect_ISR (USB_OTG_CORE_HANDLE *pdev)
|
|||
|
||||
return 1;
|
||||
}
|
||||
|
||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma optimize = none
|
||||
#endif /* __CC_ARM */
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_nptxfempty_ISR
|
||||
* Handles non periodic tx fifo empty.
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
* @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;
|
||||
|
@ -266,44 +272,46 @@ static uint32_t USB_OTG_USBH_handle_nptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev)
|
|||
|
||||
hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS);
|
||||
|
||||
len_words = (pdev->host.hc[hnptxsts.b.chnum].xfer_len + 3) / 4;
|
||||
len_words = (pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len + 3) / 4;
|
||||
|
||||
while ((hnptxsts.b.nptxfspcavail > len_words)&&
|
||||
(pdev->host.hc[hnptxsts.b.chnum].xfer_len != 0))
|
||||
(pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len != 0))
|
||||
{
|
||||
|
||||
len = hnptxsts.b.nptxfspcavail * 4;
|
||||
|
||||
if (len > pdev->host.hc[hnptxsts.b.chnum].xfer_len)
|
||||
if (len > pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len)
|
||||
{
|
||||
/* Last packet */
|
||||
len = pdev->host.hc[hnptxsts.b.chnum].xfer_len;
|
||||
len = pdev->host.hc[hnptxsts.b.nptxqtop.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;
|
||||
len_words = (pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len + 3) / 4;
|
||||
|
||||
USB_OTG_WritePacket (pdev , pdev->host.hc[hnptxsts.b.chnum].xfer_buff, hnptxsts.b.chnum, len);
|
||||
USB_OTG_WritePacket (pdev , pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_buff, hnptxsts.b.nptxqtop.chnum, len);
|
||||
|
||||
pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_buff += len;
|
||||
pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len -= len;
|
||||
pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_count += 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;
|
||||
}
|
||||
|
||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma optimize = none
|
||||
#endif /* __CC_ARM */
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_ptxfempty_ISR
|
||||
* Handles periodic tx fifo empty
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
* @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;
|
||||
|
@ -312,31 +320,31 @@ static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev)
|
|||
|
||||
hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS);
|
||||
|
||||
len_words = (pdev->host.hc[hptxsts.b.chnum].xfer_len + 3) / 4;
|
||||
len_words = (pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len + 3) / 4;
|
||||
|
||||
while ((hptxsts.b.ptxfspcavail > len_words)&&
|
||||
(pdev->host.hc[hptxsts.b.chnum].xfer_len != 0))
|
||||
(pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len != 0))
|
||||
{
|
||||
|
||||
len = hptxsts.b.ptxfspcavail * 4;
|
||||
|
||||
if (len > pdev->host.hc[hptxsts.b.chnum].xfer_len)
|
||||
if (len > pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len)
|
||||
{
|
||||
len = pdev->host.hc[hptxsts.b.chnum].xfer_len;
|
||||
len = pdev->host.hc[hptxsts.b.ptxqtop.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;
|
||||
len_words = (pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len + 3) / 4;
|
||||
|
||||
USB_OTG_WritePacket (pdev , pdev->host.hc[hptxsts.b.chnum].xfer_buff, hptxsts.b.chnum, len);
|
||||
USB_OTG_WritePacket (pdev , pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_buff, hptxsts.b.ptxqtop.chnum, len);
|
||||
|
||||
pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_buff += len;
|
||||
pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len -= len;
|
||||
pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_count += 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);
|
||||
}
|
||||
|
||||
|
@ -344,19 +352,23 @@ static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev)
|
|||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_port_ISR
|
||||
* This function determines which interrupt conditions have occurred
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
* @brief USB_OTG_USBH_handle_port_ISR
|
||||
* This function determines which interrupt conditions have occurred
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma optimize = none
|
||||
#endif /* __CC_ARM */
|
||||
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;
|
||||
USB_OTG_GINTMSK_TypeDef intmsk;
|
||||
|
||||
intmsk.d32 = 0;
|
||||
hcfg.d32 = 0;
|
||||
hprt0.d32 = 0;
|
||||
hprt0_dup.d32 = 0;
|
||||
|
@ -374,24 +386,21 @@ static uint32_t USB_OTG_USBH_handle_port_ISR (USB_OTG_CORE_HANDLE *pdev)
|
|||
/* Port Connect Detected */
|
||||
if (hprt0.b.prtconndet)
|
||||
{
|
||||
pdev->host.port_cb->Connect(pdev);
|
||||
hprt0_dup.b.prtconndet = 1;
|
||||
do_reset = 1;
|
||||
retval |= 1;
|
||||
USBH_HCD_INT_fops->DevConnected(pdev);
|
||||
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)
|
||||
|
@ -399,65 +408,70 @@ static uint32_t USB_OTG_USBH_handle_port_ISR (USB_OTG_CORE_HANDLE *pdev)
|
|||
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;
|
||||
if(pdev->cfg.phy_itface == USB_OTG_EMBEDDED_PHY)
|
||||
{
|
||||
USB_OTG_InitFSLSPClkSel(pdev , HCFG_6_MHZ);
|
||||
}
|
||||
|
||||
else
|
||||
{
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 48000 );
|
||||
if (hcfg.b.fslspclksel != HCFG_48_MHZ)
|
||||
{
|
||||
USB_OTG_InitFSLSPClkSel(pdev ,HCFG_48_MHZ );
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
do_reset = 1;
|
||||
}
|
||||
|
||||
USBH_HCD_INT_fops->DevPortEnabled(pdev);
|
||||
|
||||
/*unmask disconnect interrupt */
|
||||
intmsk.d32 = 0;
|
||||
intmsk.b.disconnect = 1;
|
||||
USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, intmsk.d32, intmsk.d32);
|
||||
}
|
||||
else
|
||||
{
|
||||
USBH_HCD_INT_fops->DevPortDisabled(pdev);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
/* 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;
|
||||
}
|
||||
|
||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma optimize = none
|
||||
#endif /* __CC_ARM */
|
||||
/**
|
||||
* @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
|
||||
*/
|
||||
* @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_HCINTMSK_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);
|
||||
hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCINTMSK);
|
||||
hcint.d32 = hcint.d32 & hcintmsk.d32;
|
||||
|
||||
hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCCHAR);
|
||||
|
@ -471,7 +485,12 @@ uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t
|
|||
{
|
||||
CLEAR_HC_INT(hcreg , ack);
|
||||
}
|
||||
|
||||
else 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)
|
||||
{
|
||||
pdev->host.ErrCnt[num] = 0;
|
||||
|
@ -493,7 +512,10 @@ uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t
|
|||
{
|
||||
pdev->host.ErrCnt[num] = 0;
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
if (pdev->cfg.dma_enable == 0)
|
||||
{
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
}
|
||||
CLEAR_HC_INT(hcreg , nak);
|
||||
pdev->host.HC_Status[num] = HC_NAK;
|
||||
}
|
||||
|
@ -502,7 +524,6 @@ uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t
|
|||
{
|
||||
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);
|
||||
}
|
||||
|
@ -510,13 +531,15 @@ uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t
|
|||
{
|
||||
pdev->host.ErrCnt[num] = 0;
|
||||
UNMASK_HOST_INT_CHH (num);
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
if (pdev->cfg.dma_enable == 0)
|
||||
{
|
||||
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);
|
||||
|
@ -555,43 +578,41 @@ uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t
|
|||
}
|
||||
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;
|
||||
}
|
||||
|
||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma optimize = none
|
||||
#endif /* __CC_ARM */
|
||||
/**
|
||||
* @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
|
||||
*/
|
||||
* @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_HCINTMSK_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);
|
||||
hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCINTMSK);
|
||||
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);
|
||||
|
@ -610,16 +631,15 @@ uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t n
|
|||
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 */
|
||||
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;
|
||||
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);
|
||||
}
|
||||
|
||||
|
@ -632,13 +652,12 @@ uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t n
|
|||
|
||||
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);
|
||||
|
@ -650,15 +669,14 @@ uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t n
|
|||
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)
|
||||
{
|
||||
|
@ -671,15 +689,15 @@ uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t n
|
|||
|
||||
else if (pdev->host.HC_Status[num] == HC_STALL)
|
||||
{
|
||||
pdev->host.URB_State[num] = URB_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;
|
||||
|
||||
pdev->host.ErrCnt[num] = 0;
|
||||
pdev->host.URB_State[num] = URB_ERROR;
|
||||
|
||||
}
|
||||
else if(hcchar.b.eptype == EP_TYPE_INTR)
|
||||
{
|
||||
|
@ -692,43 +710,48 @@ uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t n
|
|||
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);
|
||||
if (pdev->cfg.dma_enable == 0)
|
||||
{
|
||||
USB_OTG_HC_Halt(pdev, num);
|
||||
}
|
||||
}
|
||||
else if ((hcchar.b.eptype == EP_TYPE_CTRL)||
|
||||
(hcchar.b.eptype == EP_TYPE_BULK))
|
||||
|
||||
pdev->host.HC_Status[num] = HC_NAK;
|
||||
CLEAR_HC_INT(hcreg , nak);
|
||||
|
||||
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
|
||||
*/
|
||||
|
||||
* @brief USB_OTG_USBH_handle_rx_qlvl_ISR
|
||||
* Handles the Rx Status Queue Level Interrupt
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma optimize = none
|
||||
#endif /* __CC_ARM */
|
||||
static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GRXFSTS_TypeDef grxsts;
|
||||
|
@ -759,7 +782,7 @@ static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev)
|
|||
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;
|
||||
|
||||
|
@ -774,9 +797,9 @@ static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev)
|
|||
}
|
||||
break;
|
||||
|
||||
case GRXSTS_PKTSTS_IN_XFER_COMP:
|
||||
|
||||
case GRXSTS_PKTSTS_DATA_TOGGLE_ERR:
|
||||
case GRXSTS_PKTSTS_IN_XFER_COMP:
|
||||
|
||||
case GRXSTS_PKTSTS_DATA_TOGGLE_ERR:
|
||||
case GRXSTS_PKTSTS_CH_HALTED:
|
||||
default:
|
||||
break;
|
||||
|
@ -789,31 +812,34 @@ static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev)
|
|||
}
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR
|
||||
* Handles the incomplete Periodic transfer Interrupt
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
* @brief USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR
|
||||
* Handles the incomplete Periodic transfer Interrupt
|
||||
* @param pdev: Selected device
|
||||
* @retval status
|
||||
*/
|
||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma optimize = none
|
||||
#endif /* __CC_ARM */
|
||||
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;
|
||||
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;
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -828,5 +854,5 @@ static uint32_t USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (USB_OTG_CORE_HAN
|
|||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
||||
|
|
|
@ -2,20 +2,26 @@
|
|||
******************************************************************************
|
||||
* @file usb_otg.c
|
||||
* @author MCD Application Team
|
||||
* @version V2.0.0
|
||||
* @date 22-July-2011
|
||||
* @version V2.2.0
|
||||
* @date 09-November-2015
|
||||
* @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 2015 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
|
@ -72,6 +78,10 @@
|
|||
* @{
|
||||
*/
|
||||
|
||||
uint32_t USB_OTG_HandleOTG_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
|
||||
static uint32_t USB_OTG_HandleConnectorIDStatusChange_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t USB_OTG_HandleSessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev);
|
||||
static uint32_t USB_OTG_Read_itr(USB_OTG_CORE_HANDLE *pdev);
|
||||
|
||||
/**
|
||||
|
@ -106,15 +116,15 @@ uint32_t STM32_USBO_OTG_ISR_Handler(USB_OTG_CORE_HANDLE *pdev)
|
|||
}
|
||||
if (gintsts.b.otgintr)
|
||||
{
|
||||
retval |= 1;//USB_OTG_HandleOTG_ISR(pdev);
|
||||
retval |= USB_OTG_HandleOTG_ISR(pdev);
|
||||
}
|
||||
if (gintsts.b.conidstschng)
|
||||
{
|
||||
retval |= 2;//USB_OTG_HandleConnectorIDStatusChange_ISR(pdev);
|
||||
retval |= USB_OTG_HandleConnectorIDStatusChange_ISR(pdev);
|
||||
}
|
||||
if (gintsts.b.sessreqintr)
|
||||
{
|
||||
retval |= 3;//USB_OTG_HandleSessionRequest_ISR(pdev);
|
||||
retval |= USB_OTG_HandleSessionRequest_ISR(pdev);
|
||||
}
|
||||
return retval;
|
||||
}
|
||||
|
@ -148,6 +158,239 @@ static uint32_t USB_OTG_Read_itr(USB_OTG_CORE_HANDLE *pdev)
|
|||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_HandleOTG_ISR
|
||||
* handles the OTG Interrupts
|
||||
* @param None
|
||||
* @retval : status
|
||||
*/
|
||||
static uint32_t USB_OTG_HandleOTG_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GOTGINT_TypeDef gotgint;
|
||||
USB_OTG_GOTGCTL_TypeDef gotgctl;
|
||||
|
||||
|
||||
gotgint.d32 = 0;
|
||||
gotgctl.d32 = 0;
|
||||
|
||||
gotgint.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGINT);
|
||||
gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
|
||||
|
||||
if (gotgint.b.sesenddet)
|
||||
{
|
||||
gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
|
||||
|
||||
|
||||
if (USB_OTG_IsDeviceMode(pdev))
|
||||
{
|
||||
|
||||
}
|
||||
else if (USB_OTG_IsHostMode(pdev))
|
||||
{
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
/* ----> SRP SUCCESS or FAILURE INTERRUPT <---- */
|
||||
if (gotgint.b.sesreqsucstschng)
|
||||
{
|
||||
gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
|
||||
if (gotgctl.b.sesreqscs) /* Session request success */
|
||||
{
|
||||
if (USB_OTG_IsDeviceMode(pdev))
|
||||
{
|
||||
|
||||
}
|
||||
/* Clear Session Request */
|
||||
gotgctl.d32 = 0;
|
||||
gotgctl.b.sesreq = 1;
|
||||
USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GOTGCTL, gotgctl.d32, 0);
|
||||
}
|
||||
else /* Session request failure */
|
||||
{
|
||||
if (USB_OTG_IsDeviceMode(pdev))
|
||||
{
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
/* ----> HNP SUCCESS or FAILURE INTERRUPT <---- */
|
||||
if (gotgint.b.hstnegsucstschng)
|
||||
{
|
||||
gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
|
||||
|
||||
if (gotgctl.b.hstnegscs) /* Host negotiation success */
|
||||
{
|
||||
if (USB_OTG_IsHostMode(pdev)) /* The core AUTOMATICALLY sets the Host mode */
|
||||
{
|
||||
|
||||
}
|
||||
}
|
||||
else /* Host negotiation failure */
|
||||
{
|
||||
|
||||
}
|
||||
gotgint.b.hstnegsucstschng = 1; /* Ack "Host Negotiation Success Status Change" interrupt. */
|
||||
}
|
||||
/* ----> HOST NEGOTIATION DETECTED INTERRUPT <---- */
|
||||
if (gotgint.b.hstnegdet)
|
||||
{
|
||||
if (USB_OTG_IsDeviceMode(pdev)) /* The core AUTOMATICALLY sets the Host mode */
|
||||
{
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
}
|
||||
}
|
||||
if (gotgint.b.adevtoutchng)
|
||||
{}
|
||||
if (gotgint.b.debdone)
|
||||
{
|
||||
USB_OTG_ResetPort(pdev);
|
||||
}
|
||||
/* Clear OTG INT */
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGINT, gotgint.d32);
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_HandleConnectorIDStatusChange_ISR
|
||||
* handles the Connector ID Status Change Interrupt
|
||||
* @param None
|
||||
* @retval : status
|
||||
*/
|
||||
static uint32_t USB_OTG_HandleConnectorIDStatusChange_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTMSK_TypeDef gintmsk;
|
||||
USB_OTG_GOTGCTL_TypeDef gotgctl;
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
|
||||
gintsts.d32 = 0 ;
|
||||
gintmsk.d32 = 0 ;
|
||||
gotgctl.d32 = 0 ;
|
||||
gintmsk.b.sofintr = 1;
|
||||
|
||||
USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, gintmsk.d32, 0);
|
||||
gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
|
||||
|
||||
/* B-Device connector (Device Mode) */
|
||||
if (gotgctl.b.conidsts)
|
||||
{
|
||||
USB_OTG_DisableGlobalInt(pdev);
|
||||
USB_OTG_CoreInitDev(pdev);
|
||||
USB_OTG_EnableGlobalInt(pdev);
|
||||
pdev->otg.OTG_State = B_PERIPHERAL;
|
||||
}
|
||||
else
|
||||
{
|
||||
USB_OTG_DisableGlobalInt(pdev);
|
||||
USB_OTG_CoreInitHost(pdev);
|
||||
USB_OTG_EnableGlobalInt(pdev);
|
||||
pdev->otg.OTG_State = A_HOST;
|
||||
}
|
||||
/* Set flag and clear interrupt */
|
||||
gintsts.b.conidstschng = 1;
|
||||
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_HandleSessionRequest_ISR
|
||||
* Initiating the Session Request Protocol
|
||||
* @param None
|
||||
* @retval : status
|
||||
*/
|
||||
static uint32_t USB_OTG_HandleSessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintsts;
|
||||
USB_OTG_GOTGCTL_TypeDef gotgctl;
|
||||
|
||||
|
||||
gotgctl.d32 = 0;
|
||||
gintsts.d32 = 0;
|
||||
|
||||
gotgctl.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GOTGCTL );
|
||||
if (USB_OTG_IsDeviceMode(pdev) && (gotgctl.b.bsesvld))
|
||||
{
|
||||
|
||||
}
|
||||
else if (gotgctl.b.asesvld)
|
||||
{
|
||||
}
|
||||
/* Clear interrupt */
|
||||
gintsts.d32 = 0;
|
||||
gintsts.b.sessreqintr = 1;
|
||||
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_InitiateSRP
|
||||
* Initiate an srp session
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
void USB_OTG_InitiateSRP(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
USB_OTG_GOTGCTL_TypeDef otgctl;
|
||||
|
||||
otgctl.d32 = 0;
|
||||
|
||||
otgctl.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GOTGCTL );
|
||||
if (otgctl.b.sesreq)
|
||||
{
|
||||
return; /* SRP in progress */
|
||||
}
|
||||
otgctl.b.sesreq = 1;
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGCTL, otgctl.d32);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_InitiateHNP
|
||||
* Initiate HNP
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
void USB_OTG_InitiateHNP(USB_OTG_CORE_HANDLE *pdev , uint8_t state, uint8_t mode)
|
||||
{
|
||||
USB_OTG_GOTGCTL_TypeDef otgctl;
|
||||
USB_OTG_HPRT0_TypeDef hprt0;
|
||||
|
||||
otgctl.d32 = 0;
|
||||
hprt0.d32 = 0;
|
||||
|
||||
otgctl.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GOTGCTL );
|
||||
if (mode)
|
||||
{ /* Device mode */
|
||||
if (state)
|
||||
{
|
||||
|
||||
otgctl.b.devhnpen = 1; /* B-Dev has been enabled to perform HNP */
|
||||
otgctl.b.hnpreq = 1; /* Initiate an HNP req. to the connected USB host*/
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGCTL, otgctl.d32);
|
||||
}
|
||||
}
|
||||
else
|
||||
{ /* Host mode */
|
||||
if (state)
|
||||
{
|
||||
otgctl.b.hstsethnpen = 1; /* A-Dev has enabled B-device for HNP */
|
||||
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGCTL, otgctl.d32);
|
||||
/* Suspend the bus so that B-dev will disconnect indicating the initial condition for HNP to DWC_Core */
|
||||
hprt0.d32 = USB_OTG_ReadHPRT0(pdev);
|
||||
hprt0.b.prtsusp = 1; /* The core clear this bit when disconnect interrupt generated (GINTSTS.DisconnInt = '1') */
|
||||
USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief USB_OTG_GetCurrentState
|
||||
* Return current OTG State
|
||||
|
@ -172,4 +415,4 @@ uint32_t USB_OTG_GetCurrentState (USB_OTG_CORE_HANDLE *pdev)
|
|||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue