Merge pull request #11198 from SteveCEvans/sce_rc2
[betaflight.git] / lib / main / STM32F4 / Drivers / STM32F4xx_HAL_Driver / Src / stm32f4xx_hal_pcd.c
blob446583afe511b06e65faefe5817cfa3cebb0d76d
1 /**
2 ******************************************************************************
3 * @file stm32f4xx_hal_pcd.c
4 * @author MCD Application Team
5 * @version V1.7.1
6 * @date 14-April-2017
7 * @brief PCD HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the USB Peripheral Controller:
10 * + Initialization and de-initialization functions
11 * + IO operation functions
12 * + Peripheral Control functions
13 * + Peripheral State functions
15 @verbatim
16 ==============================================================================
17 ##### How to use this driver #####
18 ==============================================================================
19 [..]
20 The PCD HAL driver can be used as follows:
22 (#) Declare a PCD_HandleTypeDef handle structure, for example:
23 PCD_HandleTypeDef hpcd;
25 (#) Fill parameters of Init structure in HCD handle
27 (#) Call HAL_PCD_Init() API to initialize the PCD peripheral (Core, Device core, ...)
29 (#) Initialize the PCD low level resources through the HAL_PCD_MspInit() API:
30 (##) Enable the PCD/USB Low Level interface clock using
31 (+++) __HAL_RCC_USB_OTG_FS_CLK_ENABLE();
32 (+++) __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); (For High Speed Mode)
34 (##) Initialize the related GPIO clocks
35 (##) Configure PCD pin-out
36 (##) Configure PCD NVIC interrupt
38 (#)Associate the Upper USB device stack to the HAL PCD Driver:
39 (##) hpcd.pData = pdev;
41 (#)Enable PCD transmission and reception:
42 (##) HAL_PCD_Start();
44 @endverbatim
45 ******************************************************************************
46 * @attention
48 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
50 * Redistribution and use in source and binary forms, with or without modification,
51 * are permitted provided that the following conditions are met:
52 * 1. Redistributions of source code must retain the above copyright notice,
53 * this list of conditions and the following disclaimer.
54 * 2. Redistributions in binary form must reproduce the above copyright notice,
55 * this list of conditions and the following disclaimer in the documentation
56 * and/or other materials provided with the distribution.
57 * 3. Neither the name of STMicroelectronics nor the names of its contributors
58 * may be used to endorse or promote products derived from this software
59 * without specific prior written permission.
61 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
62 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
63 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
64 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
65 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
66 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
67 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
68 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
69 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
70 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
72 ******************************************************************************
73 */
75 /* Includes ------------------------------------------------------------------*/
76 #include "stm32f4xx_hal.h"
78 /** @addtogroup STM32F4xx_HAL_Driver
79 * @{
82 /** @defgroup PCD PCD
83 * @brief PCD HAL module driver
84 * @{
87 #ifdef HAL_PCD_MODULE_ENABLED
88 #if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \
89 defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \
90 defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \
91 defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \
92 defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx)
93 /* Private types -------------------------------------------------------------*/
94 /* Private variables ---------------------------------------------------------*/
95 /* Private constants ---------------------------------------------------------*/
96 /* Private macros ------------------------------------------------------------*/
97 /** @defgroup PCD_Private_Macros PCD Private Macros
98 * @{
99 */
100 #define PCD_MIN(a, b) (((a) < (b)) ? (a) : (b))
101 #define PCD_MAX(a, b) (((a) > (b)) ? (a) : (b))
103 * @}
106 /* Private functions prototypes ----------------------------------------------*/
107 /** @defgroup PCD_Private_Functions PCD Private Functions
108 * @{
110 static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t epnum);
112 * @}
115 /* Exported functions --------------------------------------------------------*/
116 /** @defgroup PCD_Exported_Functions PCD Exported Functions
117 * @{
120 /** @defgroup PCD_Exported_Functions_Group1 Initialization and de-initialization functions
121 * @brief Initialization and Configuration functions
123 @verbatim
124 ===============================================================================
125 ##### Initialization and de-initialization functions #####
126 ===============================================================================
127 [..] This section provides functions allowing to:
129 @endverbatim
130 * @{
134 * @brief Initializes the PCD according to the specified
135 * parameters in the PCD_InitTypeDef and initialize the associated handle.
136 * @param hpcd: PCD handle
137 * @retval HAL status
139 HAL_StatusTypeDef HAL_PCD_Init(PCD_HandleTypeDef *hpcd)
141 uint32_t i = 0U;
143 /* Check the PCD handle allocation */
144 if(hpcd == NULL)
146 return HAL_ERROR;
149 /* Check the parameters */
150 assert_param(IS_PCD_ALL_INSTANCE(hpcd->Instance));
152 hpcd->State = HAL_PCD_STATE_BUSY;
154 /* Init the low level hardware : GPIO, CLOCK, NVIC... */
155 HAL_PCD_MspInit(hpcd);
157 /* Disable the Interrupts */
158 __HAL_PCD_DISABLE(hpcd);
160 /*Init the Core (common init.) */
161 USB_CoreInit(hpcd->Instance, hpcd->Init);
163 /* Force Device Mode*/
164 USB_SetCurrentMode(hpcd->Instance , USB_OTG_DEVICE_MODE);
166 /* Init endpoints structures */
167 for (i = 0U; i < 15U; i++)
169 /* Init ep structure */
170 hpcd->IN_ep[i].is_in = 1U;
171 hpcd->IN_ep[i].num = i;
172 hpcd->IN_ep[i].tx_fifo_num = i;
173 /* Control until ep is activated */
174 hpcd->IN_ep[i].type = EP_TYPE_CTRL;
175 hpcd->IN_ep[i].maxpacket = 0U;
176 hpcd->IN_ep[i].xfer_buff = 0U;
177 hpcd->IN_ep[i].xfer_len = 0U;
180 for (i = 0U; i < 15U; i++)
182 hpcd->OUT_ep[i].is_in = 0U;
183 hpcd->OUT_ep[i].num = i;
184 hpcd->IN_ep[i].tx_fifo_num = i;
185 /* Control until ep is activated */
186 hpcd->OUT_ep[i].type = EP_TYPE_CTRL;
187 hpcd->OUT_ep[i].maxpacket = 0U;
188 hpcd->OUT_ep[i].xfer_buff = 0U;
189 hpcd->OUT_ep[i].xfer_len = 0U;
191 hpcd->Instance->DIEPTXF[i] = 0U;
194 /* Init Device */
195 USB_DevInit(hpcd->Instance, hpcd->Init);
197 hpcd->State= HAL_PCD_STATE_READY;
199 #ifdef USB_OTG_GLPMCFG_LPMEN
200 /* Activate LPM */
201 if (hpcd->Init.lpm_enable == 1U)
203 HAL_PCDEx_ActivateLPM(hpcd);
205 #endif /* USB_OTG_GLPMCFG_LPMEN */
207 #ifdef USB_OTG_GCCFG_BCDEN
208 /* Activate Battery charging */
209 if (hpcd->Init.battery_charging_enable == 1U)
211 HAL_PCDEx_ActivateBCD(hpcd);
213 #endif /* USB_OTG_GCCFG_BCDEN */
215 USB_DevDisconnect (hpcd->Instance);
216 return HAL_OK;
220 * @brief DeInitializes the PCD peripheral.
221 * @param hpcd: PCD handle
222 * @retval HAL status
224 HAL_StatusTypeDef HAL_PCD_DeInit(PCD_HandleTypeDef *hpcd)
226 /* Check the PCD handle allocation */
227 if(hpcd == NULL)
229 return HAL_ERROR;
232 hpcd->State = HAL_PCD_STATE_BUSY;
234 /* Stop Device */
235 HAL_PCD_Stop(hpcd);
237 /* DeInit the low level hardware */
238 HAL_PCD_MspDeInit(hpcd);
240 hpcd->State = HAL_PCD_STATE_RESET;
242 return HAL_OK;
246 * @brief Initializes the PCD MSP.
247 * @param hpcd: PCD handle
248 * @retval None
250 __weak void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
252 /* Prevent unused argument(s) compilation warning */
253 UNUSED(hpcd);
254 /* NOTE : This function Should not be modified, when the callback is needed,
255 the HAL_PCD_MspInit could be implemented in the user file
260 * @brief DeInitializes PCD MSP.
261 * @param hpcd: PCD handle
262 * @retval None
264 __weak void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd)
266 /* Prevent unused argument(s) compilation warning */
267 UNUSED(hpcd);
268 /* NOTE : This function Should not be modified, when the callback is needed,
269 the HAL_PCD_MspDeInit could be implemented in the user file
274 * @}
277 /** @defgroup PCD_Exported_Functions_Group2 Input and Output operation functions
278 * @brief Data transfers functions
280 @verbatim
281 ===============================================================================
282 ##### IO operation functions #####
283 ===============================================================================
284 [..]
285 This subsection provides a set of functions allowing to manage the PCD data
286 transfers.
288 @endverbatim
289 * @{
293 * @brief Start The USB OTG Device.
294 * @param hpcd: PCD handle
295 * @retval HAL status
297 HAL_StatusTypeDef HAL_PCD_Start(PCD_HandleTypeDef *hpcd)
299 __HAL_LOCK(hpcd);
300 USB_DevConnect (hpcd->Instance);
301 __HAL_PCD_ENABLE(hpcd);
302 __HAL_UNLOCK(hpcd);
303 return HAL_OK;
307 * @brief Stop The USB OTG Device.
308 * @param hpcd: PCD handle
309 * @retval HAL status
311 HAL_StatusTypeDef HAL_PCD_Stop(PCD_HandleTypeDef *hpcd)
313 __HAL_LOCK(hpcd);
314 __HAL_PCD_DISABLE(hpcd);
315 USB_StopDevice(hpcd->Instance);
316 USB_DevDisconnect(hpcd->Instance);
317 __HAL_UNLOCK(hpcd);
318 return HAL_OK;
322 * @brief Handles PCD interrupt request.
323 * @param hpcd: PCD handle
324 * @retval HAL status
326 void HAL_PCD_IRQHandler(PCD_HandleTypeDef *hpcd)
328 USB_OTG_GlobalTypeDef *USBx = hpcd->Instance;
329 uint32_t i = 0U, ep_intr = 0U, epint = 0U, epnum = 0U;
330 uint32_t fifoemptymsk = 0U, temp = 0U;
331 USB_OTG_EPTypeDef *ep;
332 uint32_t hclk = 180000000U;
334 /* ensure that we are in device mode */
335 if (USB_GetMode(hpcd->Instance) == USB_OTG_MODE_DEVICE)
337 /* avoid spurious interrupt */
338 if(__HAL_PCD_IS_INVALID_INTERRUPT(hpcd))
340 return;
343 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_MMIS))
345 /* incorrect mode, acknowledge the interrupt */
346 __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_MMIS);
349 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_OEPINT))
351 epnum = 0U;
353 /* Read in the device interrupt bits */
354 ep_intr = USB_ReadDevAllOutEpInterrupt(hpcd->Instance);
356 while ( ep_intr )
358 if (ep_intr & 0x1U)
360 epint = USB_ReadDevOutEPInterrupt(hpcd->Instance, epnum);
362 if(( epint & USB_OTG_DOEPINT_XFRC) == USB_OTG_DOEPINT_XFRC)
364 CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_XFRC);
366 if(hpcd->Init.dma_enable == 1U)
368 hpcd->OUT_ep[epnum].xfer_count = hpcd->OUT_ep[epnum].maxpacket- (USBx_OUTEP(epnum)->DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ);
369 hpcd->OUT_ep[epnum].xfer_buff += hpcd->OUT_ep[epnum].maxpacket;
372 HAL_PCD_DataOutStageCallback(hpcd, epnum);
373 if(hpcd->Init.dma_enable == 1U)
375 if((epnum == 0U) && (hpcd->OUT_ep[epnum].xfer_len == 0U))
377 /* this is ZLP, so prepare EP0 for next setup */
378 USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup);
383 if(( epint & USB_OTG_DOEPINT_STUP) == USB_OTG_DOEPINT_STUP)
385 /* Inform the upper layer that a setup packet is available */
386 HAL_PCD_SetupStageCallback(hpcd);
387 CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STUP);
390 if(( epint & USB_OTG_DOEPINT_OTEPDIS) == USB_OTG_DOEPINT_OTEPDIS)
392 CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPDIS);
395 #ifdef USB_OTG_DOEPINT_OTEPSPR
396 /* Clear Status Phase Received interrupt */
397 if(( epint & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR)
399 CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR);
401 #endif /* USB_OTG_DOEPINT_OTEPSPR */
403 epnum++;
404 ep_intr >>= 1U;
408 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_IEPINT))
410 /* Read in the device interrupt bits */
411 ep_intr = USB_ReadDevAllInEpInterrupt(hpcd->Instance);
413 epnum = 0U;
415 while ( ep_intr )
417 if (ep_intr & 0x1U) /* In ITR */
419 epint = USB_ReadDevInEPInterrupt(hpcd->Instance, epnum);
421 if(( epint & USB_OTG_DIEPINT_XFRC) == USB_OTG_DIEPINT_XFRC)
423 fifoemptymsk = 0x1U << epnum;
424 USBx_DEVICE->DIEPEMPMSK &= ~fifoemptymsk;
426 CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_XFRC);
428 if (hpcd->Init.dma_enable == 1U)
430 hpcd->IN_ep[epnum].xfer_buff += hpcd->IN_ep[epnum].maxpacket;
433 HAL_PCD_DataInStageCallback(hpcd, epnum);
435 if (hpcd->Init.dma_enable == 1U)
437 /* this is ZLP, so prepare EP0 for next setup */
438 if((epnum == 0U) && (hpcd->IN_ep[epnum].xfer_len == 0U))
440 /* prepare to rx more setup packets */
441 USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup);
445 if(( epint & USB_OTG_DIEPINT_TOC) == USB_OTG_DIEPINT_TOC)
447 CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_TOC);
449 if(( epint & USB_OTG_DIEPINT_ITTXFE) == USB_OTG_DIEPINT_ITTXFE)
451 CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_ITTXFE);
453 if(( epint & USB_OTG_DIEPINT_INEPNE) == USB_OTG_DIEPINT_INEPNE)
455 CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_INEPNE);
457 if(( epint & USB_OTG_DIEPINT_EPDISD) == USB_OTG_DIEPINT_EPDISD)
459 CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_EPDISD);
461 if(( epint & USB_OTG_DIEPINT_TXFE) == USB_OTG_DIEPINT_TXFE)
463 PCD_WriteEmptyTxFifo(hpcd , epnum);
466 epnum++;
467 ep_intr >>= 1U;
471 /* Handle Resume Interrupt */
472 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_WKUINT))
474 /* Clear the Remote Wake-up Signaling */
475 USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_RWUSIG;
477 #ifdef USB_OTG_GLPMCFG_LPMEN
478 if(hpcd->LPM_State == LPM_L1)
480 hpcd->LPM_State = LPM_L0;
481 HAL_PCDEx_LPM_Callback(hpcd, PCD_LPM_L0_ACTIVE);
483 else
484 #endif /* USB_OTG_GLPMCFG_LPMEN */
486 HAL_PCD_ResumeCallback(hpcd);
489 __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_WKUINT);
492 /* Handle Suspend Interrupt */
493 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_USBSUSP))
495 if((USBx_DEVICE->DSTS & USB_OTG_DSTS_SUSPSTS) == USB_OTG_DSTS_SUSPSTS)
498 HAL_PCD_SuspendCallback(hpcd);
500 __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_USBSUSP);
503 #ifdef USB_OTG_GLPMCFG_LPMEN
504 /* Handle LPM Interrupt */
505 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_LPMINT))
507 __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_LPMINT);
508 if( hpcd->LPM_State == LPM_L0)
510 hpcd->LPM_State = LPM_L1;
511 hpcd->BESL = (hpcd->Instance->GLPMCFG & USB_OTG_GLPMCFG_BESL) >> 2U;
512 HAL_PCDEx_LPM_Callback(hpcd, PCD_LPM_L1_ACTIVE);
514 else
516 HAL_PCD_SuspendCallback(hpcd);
519 #endif /* USB_OTG_GLPMCFG_LPMEN */
521 /* Handle Reset Interrupt */
522 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_USBRST))
524 USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_RWUSIG;
525 USB_FlushTxFifo(hpcd->Instance , 0x10U);
527 for (i = 0U; i < hpcd->Init.dev_endpoints; i++)
529 USBx_INEP(i)->DIEPINT = 0xFFU;
530 USBx_OUTEP(i)->DOEPINT = 0xFFU;
532 USBx_DEVICE->DAINT = 0xFFFFFFFFU;
533 USBx_DEVICE->DAINTMSK |= 0x10001U;
535 if(hpcd->Init.use_dedicated_ep1)
537 USBx_DEVICE->DOUTEP1MSK |= (USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM | USB_OTG_DOEPMSK_EPDM);
538 USBx_DEVICE->DINEP1MSK |= (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM);
540 else
542 #ifdef USB_OTG_DOEPINT_OTEPSPR
543 USBx_DEVICE->DOEPMSK |= (USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM | USB_OTG_DOEPMSK_EPDM | USB_OTG_DOEPMSK_OTEPSPRM);
544 #else
545 USBx_DEVICE->DOEPMSK |= (USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM | USB_OTG_DOEPMSK_EPDM);
546 #endif /* USB_OTG_DOEPINT_OTEPSPR */
547 USBx_DEVICE->DIEPMSK |= (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM);
550 /* Set Default Address to 0 */
551 USBx_DEVICE->DCFG &= ~USB_OTG_DCFG_DAD;
553 /* setup EP0 to receive SETUP packets */
554 USB_EP0_OutStart(hpcd->Instance, hpcd->Init.dma_enable, (uint8_t *)hpcd->Setup);
556 __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_USBRST);
559 /* Handle Enumeration done Interrupt */
560 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_ENUMDNE))
562 USB_ActivateSetup(hpcd->Instance);
563 hpcd->Instance->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT;
565 if ( USB_GetDevSpeed(hpcd->Instance) == USB_OTG_SPEED_HIGH)
567 hpcd->Init.speed = USB_OTG_SPEED_HIGH;
568 hpcd->Init.ep0_mps = USB_OTG_HS_MAX_PACKET_SIZE ;
569 hpcd->Instance->GUSBCFG |= (uint32_t)((USBD_HS_TRDT_VALUE << 10U) & USB_OTG_GUSBCFG_TRDT);
571 else
573 hpcd->Init.speed = USB_OTG_SPEED_FULL;
574 hpcd->Init.ep0_mps = USB_OTG_FS_MAX_PACKET_SIZE ;
576 /* The USBTRD is configured according to the tables below, depending on AHB frequency
577 used by application. In the low AHB frequency range it is used to stretch enough the USB response
578 time to IN tokens, the USB turnaround time, so to compensate for the longer AHB read access
579 latency to the Data FIFO */
581 /* Get hclk frequency value */
582 hclk = HAL_RCC_GetHCLKFreq();
584 if((hclk >= 14200000U)&&(hclk < 15000000U))
586 /* hclk Clock Range between 14.2-15 MHz */
587 hpcd->Instance->GUSBCFG |= (uint32_t)((0xFU << 10U) & USB_OTG_GUSBCFG_TRDT);
590 else if((hclk >= 15000000U)&&(hclk < 16000000U))
592 /* hclk Clock Range between 15-16 MHz */
593 hpcd->Instance->GUSBCFG |= (uint32_t)((0xEU << 10U) & USB_OTG_GUSBCFG_TRDT);
596 else if((hclk >= 16000000U)&&(hclk < 17200000U))
598 /* hclk Clock Range between 16-17.2 MHz */
599 hpcd->Instance->GUSBCFG |= (uint32_t)((0xDU << 10U) & USB_OTG_GUSBCFG_TRDT);
602 else if((hclk >= 17200000U)&&(hclk < 18500000U))
604 /* hclk Clock Range between 17.2-18.5 MHz */
605 hpcd->Instance->GUSBCFG |= (uint32_t)((0xCU << 10U) & USB_OTG_GUSBCFG_TRDT);
608 else if((hclk >= 18500000U)&&(hclk < 20000000U))
610 /* hclk Clock Range between 18.5-20 MHz */
611 hpcd->Instance->GUSBCFG |= (uint32_t)((0xBU << 10U) & USB_OTG_GUSBCFG_TRDT);
614 else if((hclk >= 20000000U)&&(hclk < 21800000U))
616 /* hclk Clock Range between 20-21.8 MHz */
617 hpcd->Instance->GUSBCFG |= (uint32_t)((0xAU << 10U) & USB_OTG_GUSBCFG_TRDT);
620 else if((hclk >= 21800000U)&&(hclk < 24000000U))
622 /* hclk Clock Range between 21.8-24 MHz */
623 hpcd->Instance->GUSBCFG |= (uint32_t)((0x9U << 10U) & USB_OTG_GUSBCFG_TRDT);
626 else if((hclk >= 24000000U)&&(hclk < 27700000U))
628 /* hclk Clock Range between 24-27.7 MHz */
629 hpcd->Instance->GUSBCFG |= (uint32_t)((0x8U << 10U) & USB_OTG_GUSBCFG_TRDT);
632 else if((hclk >= 27700000U)&&(hclk < 32000000U))
634 /* hclk Clock Range between 27.7-32 MHz */
635 hpcd->Instance->GUSBCFG |= (uint32_t)((0x7U << 10U) & USB_OTG_GUSBCFG_TRDT);
638 else /* if(hclk >= 32000000) */
640 /* hclk Clock Range between 32-180 MHz */
641 hpcd->Instance->GUSBCFG |= (uint32_t)((0x6U << 10U) & USB_OTG_GUSBCFG_TRDT);
645 HAL_PCD_ResetCallback(hpcd);
647 __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_ENUMDNE);
650 /* Handle RxQLevel Interrupt */
651 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_RXFLVL))
653 USB_MASK_INTERRUPT(hpcd->Instance, USB_OTG_GINTSTS_RXFLVL);
655 temp = USBx->GRXSTSP;
657 ep = &hpcd->OUT_ep[temp & USB_OTG_GRXSTSP_EPNUM];
659 if(((temp & USB_OTG_GRXSTSP_PKTSTS) >> 17U) == STS_DATA_UPDT)
661 if((temp & USB_OTG_GRXSTSP_BCNT) != 0U)
663 USB_ReadPacket(USBx, ep->xfer_buff, (temp & USB_OTG_GRXSTSP_BCNT) >> 4U);
664 ep->xfer_buff += (temp & USB_OTG_GRXSTSP_BCNT) >> 4U;
665 ep->xfer_count += (temp & USB_OTG_GRXSTSP_BCNT) >> 4U;
668 else if (((temp & USB_OTG_GRXSTSP_PKTSTS) >> 17U) == STS_SETUP_UPDT)
670 USB_ReadPacket(USBx, (uint8_t *)hpcd->Setup, 8U);
671 ep->xfer_count += (temp & USB_OTG_GRXSTSP_BCNT) >> 4U;
673 USB_UNMASK_INTERRUPT(hpcd->Instance, USB_OTG_GINTSTS_RXFLVL);
676 /* Handle SOF Interrupt */
677 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_SOF))
679 HAL_PCD_SOFCallback(hpcd);
680 __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_SOF);
683 /* Handle Incomplete ISO IN Interrupt */
684 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_IISOIXFR))
686 HAL_PCD_ISOINIncompleteCallback(hpcd, epnum);
687 __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_IISOIXFR);
690 /* Handle Incomplete ISO OUT Interrupt */
691 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT))
693 HAL_PCD_ISOOUTIncompleteCallback(hpcd, epnum);
694 __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT);
697 /* Handle Connection event Interrupt */
698 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_SRQINT))
700 HAL_PCD_ConnectCallback(hpcd);
701 __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_SRQINT);
704 /* Handle Disconnection event Interrupt */
705 if(__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_OTGINT))
707 temp = hpcd->Instance->GOTGINT;
709 if((temp & USB_OTG_GOTGINT_SEDET) == USB_OTG_GOTGINT_SEDET)
711 HAL_PCD_DisconnectCallback(hpcd);
713 hpcd->Instance->GOTGINT |= temp;
719 * @brief Data OUT stage callback.
720 * @param hpcd: PCD handle
721 * @param epnum: endpoint number
722 * @retval None
724 __weak void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
726 /* Prevent unused argument(s) compilation warning */
727 UNUSED(hpcd);
728 UNUSED(epnum);
729 /* NOTE : This function Should not be modified, when the callback is needed,
730 the HAL_PCD_DataOutStageCallback could be implemented in the user file
735 * @brief Data IN stage callback.
736 * @param hpcd: PCD handle
737 * @param epnum: endpoint number
738 * @retval None
740 __weak void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
742 /* Prevent unused argument(s) compilation warning */
743 UNUSED(hpcd);
744 UNUSED(epnum);
745 /* NOTE : This function Should not be modified, when the callback is needed,
746 the HAL_PCD_DataInStageCallback could be implemented in the user file
750 * @brief Setup stage callback.
751 * @param hpcd: PCD handle
752 * @retval None
754 __weak void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd)
756 /* Prevent unused argument(s) compilation warning */
757 UNUSED(hpcd);
758 /* NOTE : This function Should not be modified, when the callback is needed,
759 the HAL_PCD_SetupStageCallback could be implemented in the user file
764 * @brief USB Start Of Frame callback.
765 * @param hpcd: PCD handle
766 * @retval None
768 __weak void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd)
770 /* Prevent unused argument(s) compilation warning */
771 UNUSED(hpcd);
772 /* NOTE : This function Should not be modified, when the callback is needed,
773 the HAL_PCD_SOFCallback could be implemented in the user file
778 * @brief USB Reset callback.
779 * @param hpcd: PCD handle
780 * @retval None
782 __weak void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd)
784 /* Prevent unused argument(s) compilation warning */
785 UNUSED(hpcd);
786 /* NOTE : This function Should not be modified, when the callback is needed,
787 the HAL_PCD_ResetCallback could be implemented in the user file
792 * @brief Suspend event callback.
793 * @param hpcd: PCD handle
794 * @retval None
796 __weak void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd)
798 /* Prevent unused argument(s) compilation warning */
799 UNUSED(hpcd);
800 /* NOTE : This function Should not be modified, when the callback is needed,
801 the HAL_PCD_SuspendCallback could be implemented in the user file
806 * @brief Resume event callback.
807 * @param hpcd: PCD handle
808 * @retval None
810 __weak void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd)
812 /* Prevent unused argument(s) compilation warning */
813 UNUSED(hpcd);
814 /* NOTE : This function Should not be modified, when the callback is needed,
815 the HAL_PCD_ResumeCallback could be implemented in the user file
820 * @brief Incomplete ISO OUT callback.
821 * @param hpcd: PCD handle
822 * @param epnum: endpoint number
823 * @retval None
825 __weak void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
827 /* Prevent unused argument(s) compilation warning */
828 UNUSED(hpcd);
829 UNUSED(epnum);
830 /* NOTE : This function Should not be modified, when the callback is needed,
831 the HAL_PCD_ISOOUTIncompleteCallback could be implemented in the user file
836 * @brief Incomplete ISO IN callback.
837 * @param hpcd: PCD handle
838 * @param epnum: endpoint number
839 * @retval None
841 __weak void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
843 /* Prevent unused argument(s) compilation warning */
844 UNUSED(hpcd);
845 UNUSED(epnum);
846 /* NOTE : This function Should not be modified, when the callback is needed,
847 the HAL_PCD_ISOINIncompleteCallback could be implemented in the user file
852 * @brief Connection event callback.
853 * @param hpcd: PCD handle
854 * @retval None
856 __weak void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd)
858 /* Prevent unused argument(s) compilation warning */
859 UNUSED(hpcd);
860 /* NOTE : This function Should not be modified, when the callback is needed,
861 the HAL_PCD_ConnectCallback could be implemented in the user file
866 * @brief Disconnection event callback.
867 * @param hpcd: PCD handle
868 * @retval None
870 __weak void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd)
872 /* Prevent unused argument(s) compilation warning */
873 UNUSED(hpcd);
874 /* NOTE : This function Should not be modified, when the callback is needed,
875 the HAL_PCD_DisconnectCallback could be implemented in the user file
880 * @}
883 /** @defgroup PCD_Exported_Functions_Group3 Peripheral Control functions
884 * @brief management functions
886 @verbatim
887 ===============================================================================
888 ##### Peripheral Control functions #####
889 ===============================================================================
890 [..]
891 This subsection provides a set of functions allowing to control the PCD data
892 transfers.
894 @endverbatim
895 * @{
899 * @brief Connect the USB device.
900 * @param hpcd: PCD handle
901 * @retval HAL status
903 HAL_StatusTypeDef HAL_PCD_DevConnect(PCD_HandleTypeDef *hpcd)
905 __HAL_LOCK(hpcd);
906 USB_DevConnect(hpcd->Instance);
907 __HAL_UNLOCK(hpcd);
908 return HAL_OK;
912 * @brief Disconnect the USB device.
913 * @param hpcd: PCD handle
914 * @retval HAL status
916 HAL_StatusTypeDef HAL_PCD_DevDisconnect(PCD_HandleTypeDef *hpcd)
918 __HAL_LOCK(hpcd);
919 USB_DevDisconnect(hpcd->Instance);
920 __HAL_UNLOCK(hpcd);
921 return HAL_OK;
925 * @brief Set the USB Device address.
926 * @param hpcd: PCD handle
927 * @param address: new device address
928 * @retval HAL status
930 HAL_StatusTypeDef HAL_PCD_SetAddress(PCD_HandleTypeDef *hpcd, uint8_t address)
932 __HAL_LOCK(hpcd);
933 USB_SetDevAddress(hpcd->Instance, address);
934 __HAL_UNLOCK(hpcd);
935 return HAL_OK;
938 * @brief Open and configure an endpoint.
939 * @param hpcd: PCD handle
940 * @param ep_addr: endpoint address
941 * @param ep_mps: endpoint max packet size
942 * @param ep_type: endpoint type
943 * @retval HAL status
945 HAL_StatusTypeDef HAL_PCD_EP_Open(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint16_t ep_mps, uint8_t ep_type)
947 HAL_StatusTypeDef ret = HAL_OK;
948 USB_OTG_EPTypeDef *ep;
950 if ((ep_addr & 0x80) == 0x80)
952 ep = &hpcd->IN_ep[ep_addr & 0x7F];
954 else
956 ep = &hpcd->OUT_ep[ep_addr & 0x7F];
958 ep->num = ep_addr & 0x7F;
960 ep->is_in = (0x80 & ep_addr) != 0;
961 ep->maxpacket = ep_mps;
962 ep->type = ep_type;
963 if (ep->is_in)
965 /* Assign a Tx FIFO */
966 ep->tx_fifo_num = ep->num;
968 /* Set initial data PID. */
969 if (ep_type == EP_TYPE_BULK )
971 ep->data_pid_start = 0U;
974 __HAL_LOCK(hpcd);
975 USB_ActivateEndpoint(hpcd->Instance , ep);
976 __HAL_UNLOCK(hpcd);
977 return ret;
982 * @brief Deactivate an endpoint.
983 * @param hpcd: PCD handle
984 * @param ep_addr: endpoint address
985 * @retval HAL status
987 HAL_StatusTypeDef HAL_PCD_EP_Close(PCD_HandleTypeDef *hpcd, uint8_t ep_addr)
989 USB_OTG_EPTypeDef *ep;
991 if ((ep_addr & 0x80) == 0x80)
993 ep = &hpcd->IN_ep[ep_addr & 0x7F];
995 else
997 ep = &hpcd->OUT_ep[ep_addr & 0x7F];
999 ep->num = ep_addr & 0x7F;
1001 ep->is_in = (0x80 & ep_addr) != 0;
1003 __HAL_LOCK(hpcd);
1004 USB_DeactivateEndpoint(hpcd->Instance , ep);
1005 __HAL_UNLOCK(hpcd);
1006 return HAL_OK;
1011 * @brief Receive an amount of data.
1012 * @param hpcd: PCD handle
1013 * @param ep_addr: endpoint address
1014 * @param pBuf: pointer to the reception buffer
1015 * @param len: amount of data to be received
1016 * @retval HAL status
1018 HAL_StatusTypeDef HAL_PCD_EP_Receive(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len)
1020 USB_OTG_EPTypeDef *ep;
1022 ep = &hpcd->OUT_ep[ep_addr & 0x7F];
1024 /*setup and start the Xfer */
1025 ep->xfer_buff = pBuf;
1026 ep->xfer_len = len;
1027 ep->xfer_count = 0U;
1028 ep->is_in = 0U;
1029 ep->num = ep_addr & 0x7F;
1031 if (hpcd->Init.dma_enable == 1U)
1033 ep->dma_addr = (uint32_t)pBuf;
1036 if ((ep_addr & 0x7F) == 0)
1038 USB_EP0StartXfer(hpcd->Instance , ep, hpcd->Init.dma_enable);
1040 else
1042 USB_EPStartXfer(hpcd->Instance , ep, hpcd->Init.dma_enable);
1045 return HAL_OK;
1049 * @brief Get Received Data Size.
1050 * @param hpcd: PCD handle
1051 * @param ep_addr: endpoint address
1052 * @retval Data Size
1054 uint16_t HAL_PCD_EP_GetRxCount(PCD_HandleTypeDef *hpcd, uint8_t ep_addr)
1056 return hpcd->OUT_ep[ep_addr & 0xF].xfer_count;
1059 * @brief Send an amount of data.
1060 * @param hpcd: PCD handle
1061 * @param ep_addr: endpoint address
1062 * @param pBuf: pointer to the transmission buffer
1063 * @param len: amount of data to be sent
1064 * @retval HAL status
1066 HAL_StatusTypeDef HAL_PCD_EP_Transmit(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len)
1068 USB_OTG_EPTypeDef *ep;
1070 ep = &hpcd->IN_ep[ep_addr & 0x7F];
1072 /*setup and start the Xfer */
1073 ep->xfer_buff = pBuf;
1074 ep->xfer_len = len;
1075 ep->xfer_count = 0U;
1076 ep->is_in = 1U;
1077 ep->num = ep_addr & 0x7F;
1079 if (hpcd->Init.dma_enable == 1U)
1081 ep->dma_addr = (uint32_t)pBuf;
1084 if ((ep_addr & 0x7F) == 0)
1086 USB_EP0StartXfer(hpcd->Instance , ep, hpcd->Init.dma_enable);
1088 else
1090 USB_EPStartXfer(hpcd->Instance , ep, hpcd->Init.dma_enable);
1093 return HAL_OK;
1097 * @brief Set a STALL condition over an endpoint.
1098 * @param hpcd: PCD handle
1099 * @param ep_addr: endpoint address
1100 * @retval HAL status
1102 HAL_StatusTypeDef HAL_PCD_EP_SetStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr)
1104 USB_OTG_EPTypeDef *ep;
1106 if ((0x80 & ep_addr) == 0x80)
1108 ep = &hpcd->IN_ep[ep_addr & 0x7F];
1110 else
1112 ep = &hpcd->OUT_ep[ep_addr];
1115 ep->is_stall = 1U;
1116 ep->num = ep_addr & 0x7F;
1117 ep->is_in = ((ep_addr & 0x80) == 0x80);
1120 __HAL_LOCK(hpcd);
1121 USB_EPSetStall(hpcd->Instance , ep);
1122 if((ep_addr & 0x7F) == 0)
1124 USB_EP0_OutStart(hpcd->Instance, hpcd->Init.dma_enable, (uint8_t *)hpcd->Setup);
1126 __HAL_UNLOCK(hpcd);
1128 return HAL_OK;
1132 * @brief Clear a STALL condition over in an endpoint.
1133 * @param hpcd: PCD handle
1134 * @param ep_addr: endpoint address
1135 * @retval HAL status
1137 HAL_StatusTypeDef HAL_PCD_EP_ClrStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr)
1139 USB_OTG_EPTypeDef *ep;
1141 if ((0x80 & ep_addr) == 0x80)
1143 ep = &hpcd->IN_ep[ep_addr & 0x7F];
1145 else
1147 ep = &hpcd->OUT_ep[ep_addr];
1150 ep->is_stall = 0U;
1151 ep->num = ep_addr & 0x7F;
1152 ep->is_in = ((ep_addr & 0x80) == 0x80);
1154 __HAL_LOCK(hpcd);
1155 USB_EPClearStall(hpcd->Instance , ep);
1156 __HAL_UNLOCK(hpcd);
1158 return HAL_OK;
1162 * @brief Flush an endpoint.
1163 * @param hpcd: PCD handle
1164 * @param ep_addr: endpoint address
1165 * @retval HAL status
1167 HAL_StatusTypeDef HAL_PCD_EP_Flush(PCD_HandleTypeDef *hpcd, uint8_t ep_addr)
1169 __HAL_LOCK(hpcd);
1171 if ((ep_addr & 0x80) == 0x80)
1173 USB_FlushTxFifo(hpcd->Instance, ep_addr & 0x7F);
1175 else
1177 USB_FlushRxFifo(hpcd->Instance);
1180 __HAL_UNLOCK(hpcd);
1182 return HAL_OK;
1186 * @brief Activate remote wakeup signalling.
1187 * @param hpcd: PCD handle
1188 * @retval HAL status
1190 HAL_StatusTypeDef HAL_PCD_ActivateRemoteWakeup(PCD_HandleTypeDef *hpcd)
1192 USB_OTG_GlobalTypeDef *USBx = hpcd->Instance;
1194 if((USBx_DEVICE->DSTS & USB_OTG_DSTS_SUSPSTS) == USB_OTG_DSTS_SUSPSTS)
1196 /* Activate Remote wakeup signaling */
1197 USBx_DEVICE->DCTL |= USB_OTG_DCTL_RWUSIG;
1199 return HAL_OK;
1203 * @brief De-activate remote wakeup signalling.
1204 * @param hpcd: PCD handle
1205 * @retval HAL status
1207 HAL_StatusTypeDef HAL_PCD_DeActivateRemoteWakeup(PCD_HandleTypeDef *hpcd)
1209 USB_OTG_GlobalTypeDef *USBx = hpcd->Instance;
1211 /* De-activate Remote wakeup signaling */
1212 USBx_DEVICE->DCTL &= ~(USB_OTG_DCTL_RWUSIG);
1213 return HAL_OK;
1216 * @}
1219 /** @defgroup PCD_Exported_Functions_Group4 Peripheral State functions
1220 * @brief Peripheral State functions
1222 @verbatim
1223 ===============================================================================
1224 ##### Peripheral State functions #####
1225 ===============================================================================
1226 [..]
1227 This subsection permits to get in run-time the status of the peripheral
1228 and the data flow.
1230 @endverbatim
1231 * @{
1235 * @brief Return the PCD handle state.
1236 * @param hpcd: PCD handle
1237 * @retval HAL state
1239 PCD_StateTypeDef HAL_PCD_GetState(PCD_HandleTypeDef *hpcd)
1241 return hpcd->State;
1244 * @}
1248 * @}
1251 /* Private functions ---------------------------------------------------------*/
1252 /** @addtogroup PCD_Private_Functions
1253 * @{
1257 * @brief Check FIFO for the next packet to be loaded.
1258 * @param hpcd: PCD handle
1259 * @param epnum : endpoint number
1260 * @retval HAL status
1262 static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t epnum)
1264 USB_OTG_GlobalTypeDef *USBx = hpcd->Instance;
1265 USB_OTG_EPTypeDef *ep;
1266 int32_t len = 0U;
1267 uint32_t len32b;
1268 uint32_t fifoemptymsk = 0U;
1270 ep = &hpcd->IN_ep[epnum];
1271 len = ep->xfer_len - ep->xfer_count;
1273 if (len > ep->maxpacket)
1275 len = ep->maxpacket;
1279 len32b = (len + 3U) / 4U;
1281 while (((USBx_INEP(epnum)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) > len32b) &&
1282 (ep->xfer_count < ep->xfer_len) &&
1283 (ep->xfer_len != 0U))
1285 /* Write the FIFO */
1286 len = ep->xfer_len - ep->xfer_count;
1288 if (len > ep->maxpacket)
1290 len = ep->maxpacket;
1292 len32b = (len + 3U) / 4U;
1294 USB_WritePacket(USBx, ep->xfer_buff, epnum, len, hpcd->Init.dma_enable);
1296 ep->xfer_buff += len;
1297 ep->xfer_count += len;
1300 if(len <= 0U)
1302 fifoemptymsk = 0x1U << epnum;
1303 USBx_DEVICE->DIEPEMPMSK &= ~fifoemptymsk;
1307 return HAL_OK;
1311 * @}
1313 #endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx ||
1314 STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Rx ||
1315 STM32F412Vx || STM32F412Cx || STM32F413xx || STM32F423xx */
1316 #endif /* HAL_PCD_MODULE_ENABLED */
1318 * @}
1322 * @}
1325 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/