Create release.yml
[betaflight.git] / lib / main / STM32H7 / Drivers / STM32H7xx_HAL_Driver / Src / stm32h7xx_ll_usb.c
blob726f4f181f693761f677fb5a09aef6324ce9f97e
1 /**
2 ******************************************************************************
3 * @file stm32h7xx_ll_usb.c
4 * @author MCD Application Team
5 * @brief USB Low Layer HAL module driver.
7 * This file provides firmware functions to manage the following
8 * functionalities of the USB Peripheral Controller:
9 * + Initialization/de-initialization functions
10 * + I/O operation functions
11 * + Peripheral Control functions
12 * + Peripheral State functions
14 @verbatim
15 ==============================================================================
16 ##### How to use this driver #####
17 ==============================================================================
18 [..]
19 (#) Fill parameters of Init structure in USB_OTG_CfgTypeDef structure.
21 (#) Call USB_CoreInit() API to initialize the USB Core peripheral.
23 (#) The upper HAL HCD/PCD driver will call the right routines for its internal processes.
25 @endverbatim
26 ******************************************************************************
27 * @attention
29 * <h2><center>&copy; Copyright (c) 2017 STMicroelectronics.
30 * All rights reserved.</center></h2>
32 * This software component is licensed by ST under BSD 3-Clause license,
33 * the "License"; You may not use this file except in compliance with the
34 * License. You may obtain a copy of the License at:
35 * opensource.org/licenses/BSD-3-Clause
37 ******************************************************************************
40 /* Includes ------------------------------------------------------------------*/
41 #include "stm32h7xx_hal.h"
43 /** @addtogroup STM32H7xx_LL_USB_DRIVER
44 * @{
47 #if defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED)
48 #if defined (USB_OTG_FS) || defined (USB_OTG_HS)
49 /* Private typedef -----------------------------------------------------------*/
50 /* Private define ------------------------------------------------------------*/
51 /* Private macro -------------------------------------------------------------*/
53 /** @defgroup USB_OTG_GRSTCTL_AHBIDL_TIMEOUT_MS AHB master idle timeout
54 * @{
56 #define USB_OTG_GRSTCTL_AHBIDL_TIMEOUT_MS ((uint32_t)50U)
58 /** @defgroup USB_OTG_GRSTCTL_CSRST_TIMEOUT_MS Core soft reset timeout
59 * @{
61 #define USB_OTG_GRSTCTL_CSRST_TIMEOUT_MS ((uint32_t)10U)
63 /** @defgroup USB_OTG_GRSTCTL_TXFFLSH_TIMEOUT_MS Tx FIFO flush timeout
64 * @{
66 #define USB_OTG_GRSTCTL_TXFFLSH_TIMEOUT_MS ((uint32_t)5U)
68 /** @defgroup USB_OTG_GRSTCTL_RXFFLSH_TIMEOUT_MS Rx FIFO flush timeout
69 * @{
71 #define USB_OTG_GRSTCTL_RXFFLSH_TIMEOUT_MS ((uint32_t)5U)
73 /* Private variables ---------------------------------------------------------*/
74 /* Private function prototypes -----------------------------------------------*/
75 /* Private functions ---------------------------------------------------------*/
76 #if defined (USB_OTG_FS) || defined (USB_OTG_HS)
77 static HAL_StatusTypeDef USB_CoreReset(USB_OTG_GlobalTypeDef *USBx);
79 /* Exported functions --------------------------------------------------------*/
80 /** @defgroup USB_LL_Exported_Functions USB Low Layer Exported Functions
81 * @{
84 /** @defgroup USB_LL_Exported_Functions_Group1 Initialization/de-initialization functions
85 * @brief Initialization and Configuration functions
87 @verbatim
88 ===============================================================================
89 ##### Initialization/de-initialization functions #####
90 ===============================================================================
92 @endverbatim
93 * @{
96 /**
97 * @brief Initializes the USB Core
98 * @param USBx USB Instance
99 * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains
100 * the configuration information for the specified USBx peripheral.
101 * @retval HAL status
103 HAL_StatusTypeDef USB_CoreInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg)
105 HAL_StatusTypeDef ret;
107 if (cfg.phy_itface == USB_OTG_ULPI_PHY)
109 USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN);
111 /* Init The ULPI Interface */
112 USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL);
114 /* Select vbus source */
115 USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI);
116 if (cfg.use_external_vbus == 1U)
118 USBx->GUSBCFG |= USB_OTG_GUSBCFG_ULPIEVBUSD;
120 /* Reset after a PHY select */
121 ret = USB_CoreReset(USBx);
123 else /* FS interface (embedded Phy) */
125 /* Select FS Embedded PHY */
126 USBx->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL;
128 /* Reset after a PHY select and set Host mode */
129 ret = USB_CoreReset(USBx);
131 if (cfg.battery_charging_enable == 0U)
133 /* Activate the USB Transceiver */
134 USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN;
136 else
138 /* Deactivate the USB Transceiver */
139 USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN);
143 if (cfg.dma_enable == 1U)
145 USBx->GAHBCFG |= USB_OTG_GAHBCFG_HBSTLEN_2;
146 USBx->GAHBCFG |= USB_OTG_GAHBCFG_DMAEN;
149 return ret;
154 * @brief Set the USB turnaround time
155 * @param USBx USB Instance
156 * @param hclk: AHB clock frequency
157 * @retval USB turnaround time In PHY Clocks number
159 HAL_StatusTypeDef USB_SetTurnaroundTime(USB_OTG_GlobalTypeDef *USBx,
160 uint32_t hclk, uint8_t speed)
162 uint32_t UsbTrd;
164 /* The USBTRD is configured according to the tables below, depending on AHB frequency
165 used by application. In the low AHB frequency range it is used to stretch enough the USB response
166 time to IN tokens, the USB turnaround time, so to compensate for the longer AHB read access
167 latency to the Data FIFO */
168 if (speed == USBD_FS_SPEED)
170 if ((hclk >= 14200000U) && (hclk < 15000000U))
172 /* hclk Clock Range between 14.2-15 MHz */
173 UsbTrd = 0xFU;
175 else if ((hclk >= 15000000U) && (hclk < 16000000U))
177 /* hclk Clock Range between 15-16 MHz */
178 UsbTrd = 0xEU;
180 else if ((hclk >= 16000000U) && (hclk < 17200000U))
182 /* hclk Clock Range between 16-17.2 MHz */
183 UsbTrd = 0xDU;
185 else if ((hclk >= 17200000U) && (hclk < 18500000U))
187 /* hclk Clock Range between 17.2-18.5 MHz */
188 UsbTrd = 0xCU;
190 else if ((hclk >= 18500000U) && (hclk < 20000000U))
192 /* hclk Clock Range between 18.5-20 MHz */
193 UsbTrd = 0xBU;
195 else if ((hclk >= 20000000U) && (hclk < 21800000U))
197 /* hclk Clock Range between 20-21.8 MHz */
198 UsbTrd = 0xAU;
200 else if ((hclk >= 21800000U) && (hclk < 24000000U))
202 /* hclk Clock Range between 21.8-24 MHz */
203 UsbTrd = 0x9U;
205 else if ((hclk >= 24000000U) && (hclk < 27700000U))
207 /* hclk Clock Range between 24-27.7 MHz */
208 UsbTrd = 0x8U;
210 else if ((hclk >= 27700000U) && (hclk < 32000000U))
212 /* hclk Clock Range between 27.7-32 MHz */
213 UsbTrd = 0x7U;
215 else /* if(hclk >= 32000000) */
217 /* hclk Clock Range between 32-200 MHz */
218 UsbTrd = 0x6U;
221 else if (speed == USBD_HS_SPEED)
223 UsbTrd = USBD_HS_TRDT_VALUE;
225 else
227 UsbTrd = USBD_DEFAULT_TRDT_VALUE;
230 USBx->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT;
231 USBx->GUSBCFG |= (uint32_t)((UsbTrd << 10) & USB_OTG_GUSBCFG_TRDT);
233 return HAL_OK;
237 * @brief USB_EnableGlobalInt
238 * Enables the controller's Global Int in the AHB Config reg
239 * @param USBx Selected device
240 * @retval HAL status
242 HAL_StatusTypeDef USB_EnableGlobalInt(USB_OTG_GlobalTypeDef *USBx)
244 USBx->GAHBCFG |= USB_OTG_GAHBCFG_GINT;
245 return HAL_OK;
249 * @brief USB_DisableGlobalInt
250 * Disable the controller's Global Int in the AHB Config reg
251 * @param USBx Selected device
252 * @retval HAL status
254 HAL_StatusTypeDef USB_DisableGlobalInt(USB_OTG_GlobalTypeDef *USBx)
256 USBx->GAHBCFG &= ~USB_OTG_GAHBCFG_GINT;
257 return HAL_OK;
261 * @brief USB_SetCurrentMode : Set functional mode
262 * @param USBx Selected device
263 * @param mode current core mode
264 * This parameter can be one of these values:
265 * @arg USB_DEVICE_MODE: Peripheral mode
266 * @arg USB_HOST_MODE: Host mode
267 * @arg USB_DRD_MODE: Dual Role Device mode
268 * @retval HAL status
270 HAL_StatusTypeDef USB_SetCurrentMode(USB_OTG_GlobalTypeDef *USBx, USB_OTG_ModeTypeDef mode)
272 USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_FHMOD | USB_OTG_GUSBCFG_FDMOD);
274 if (mode == USB_HOST_MODE)
276 USBx->GUSBCFG |= USB_OTG_GUSBCFG_FHMOD;
278 else if (mode == USB_DEVICE_MODE)
280 USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD;
282 else
284 return HAL_ERROR;
286 HAL_Delay(50U);
288 return HAL_OK;
292 * @brief USB_DevInit : Initializes the USB_OTG controller registers
293 * for device mode
294 * @param USBx Selected device
295 * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains
296 * the configuration information for the specified USBx peripheral.
297 * @retval HAL status
299 HAL_StatusTypeDef USB_DevInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg)
301 HAL_StatusTypeDef ret = HAL_OK;
302 uint32_t USBx_BASE = (uint32_t)USBx;
303 uint32_t i;
305 for (i = 0U; i < 15U; i++)
307 USBx->DIEPTXF[i] = 0U;
310 /* VBUS Sensing setup */
311 if (cfg.vbus_sensing_enable == 0U)
313 USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS;
315 /* Deactivate VBUS Sensing B */
316 USBx->GCCFG &= ~USB_OTG_GCCFG_VBDEN;
318 /* B-peripheral session valid override enable */
319 USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN;
320 USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL;
322 else
324 /* Enable HW VBUS sensing */
325 USBx->GCCFG |= USB_OTG_GCCFG_VBDEN;
328 /* Restart the Phy Clock */
329 USBx_PCGCCTL = 0U;
331 /* Device mode configuration */
332 USBx_DEVICE->DCFG |= DCFG_FRAME_INTERVAL_80;
334 if (cfg.phy_itface == USB_OTG_ULPI_PHY)
336 if (cfg.speed == USBD_HS_SPEED)
338 /* Set Core speed to High speed mode */
339 (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_HIGH);
341 else
343 /* Set Core speed to Full speed mode */
344 (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_HIGH_IN_FULL);
347 else
349 /* Set Core speed to Full speed mode */
350 (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_FULL);
353 /* Flush the FIFOs */
354 if (USB_FlushTxFifo(USBx, 0x10U) != HAL_OK) /* all Tx FIFOs */
356 ret = HAL_ERROR;
359 if (USB_FlushRxFifo(USBx) != HAL_OK)
361 ret = HAL_ERROR;
364 /* Clear all pending Device Interrupts */
365 USBx_DEVICE->DIEPMSK = 0U;
366 USBx_DEVICE->DOEPMSK = 0U;
367 USBx_DEVICE->DAINTMSK = 0U;
369 for (i = 0U; i < cfg.dev_endpoints; i++)
371 if ((USBx_INEP(i)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA)
373 if (i == 0U)
375 USBx_INEP(i)->DIEPCTL = USB_OTG_DIEPCTL_SNAK;
377 else
379 USBx_INEP(i)->DIEPCTL = USB_OTG_DIEPCTL_EPDIS | USB_OTG_DIEPCTL_SNAK;
382 else
384 USBx_INEP(i)->DIEPCTL = 0U;
387 USBx_INEP(i)->DIEPTSIZ = 0U;
388 USBx_INEP(i)->DIEPINT = 0xFB7FU;
391 for (i = 0U; i < cfg.dev_endpoints; i++)
393 if ((USBx_OUTEP(i)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA)
395 if (i == 0U)
397 USBx_OUTEP(i)->DOEPCTL = USB_OTG_DOEPCTL_SNAK;
399 else
401 USBx_OUTEP(i)->DOEPCTL = USB_OTG_DOEPCTL_EPDIS | USB_OTG_DOEPCTL_SNAK;
404 else
406 USBx_OUTEP(i)->DOEPCTL = 0U;
409 USBx_OUTEP(i)->DOEPTSIZ = 0U;
410 USBx_OUTEP(i)->DOEPINT = 0xFB7FU;
413 USBx_DEVICE->DIEPMSK &= ~(USB_OTG_DIEPMSK_TXFURM);
415 /* Disable all interrupts. */
416 USBx->GINTMSK = 0U;
418 /* Clear any pending interrupts */
419 USBx->GINTSTS = 0xBFFFFFFFU;
421 /* Enable the common interrupts */
422 if (cfg.dma_enable == 0U)
424 USBx->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM;
427 /* Enable interrupts matching to the Device mode ONLY */
428 USBx->GINTMSK |= USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_USBRST |
429 USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_IEPINT |
430 USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IISOIXFRM |
431 USB_OTG_GINTMSK_PXFRM_IISOOXFRM | USB_OTG_GINTMSK_WUIM;
433 if (cfg.Sof_enable != 0U)
435 USBx->GINTMSK |= USB_OTG_GINTMSK_SOFM;
438 if (cfg.vbus_sensing_enable == 1U)
440 USBx->GINTMSK |= (USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_OTGINT);
443 return ret;
447 * @brief USB_OTG_FlushTxFifo : Flush a Tx FIFO
448 * @param USBx Selected device
449 * @param num FIFO number
450 * This parameter can be a value from 1 to 15
451 15 means Flush all Tx FIFOs
452 * @retval HAL status
454 HAL_StatusTypeDef USB_FlushTxFifo(USB_OTG_GlobalTypeDef *USBx, uint32_t num)
456 uint32_t tickstart;
458 USBx->GRSTCTL = (USB_OTG_GRSTCTL_TXFFLSH | (num << 6));
460 /* Get tick */
461 tickstart = HAL_GetTick();
463 /* Wait for AHB master IDLE state. */
464 while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH)
466 if ((HAL_GetTick() - tickstart) > USB_OTG_GRSTCTL_TXFFLSH_TIMEOUT_MS)
468 return HAL_TIMEOUT;
472 return HAL_OK;
476 * @brief USB_FlushRxFifo : Flush Rx FIFO
477 * @param USBx Selected device
478 * @retval HAL status
480 HAL_StatusTypeDef USB_FlushRxFifo(USB_OTG_GlobalTypeDef *USBx)
482 uint32_t tickstart;
484 USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH;
486 /* Get tick */
487 tickstart = HAL_GetTick();
489 /* Wait for AHB master IDLE state. */
490 while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH)
492 if ((HAL_GetTick() - tickstart) > USB_OTG_GRSTCTL_RXFFLSH_TIMEOUT_MS)
494 return HAL_TIMEOUT;
498 return HAL_OK;
502 * @brief USB_SetDevSpeed Initializes the DevSpd field of DCFG register
503 * depending the PHY type and the enumeration speed of the device.
504 * @param USBx Selected device
505 * @param speed device speed
506 * This parameter can be one of these values:
507 * @arg USB_OTG_SPEED_HIGH: High speed mode
508 * @arg USB_OTG_SPEED_HIGH_IN_FULL: High speed core in Full Speed mode
509 * @arg USB_OTG_SPEED_FULL: Full speed mode
510 * @retval Hal status
512 HAL_StatusTypeDef USB_SetDevSpeed(USB_OTG_GlobalTypeDef *USBx, uint8_t speed)
514 uint32_t USBx_BASE = (uint32_t)USBx;
516 USBx_DEVICE->DCFG |= speed;
517 return HAL_OK;
521 * @brief USB_GetDevSpeed Return the Dev Speed
522 * @param USBx Selected device
523 * @retval speed device speed
524 * This parameter can be one of these values:
525 * @arg PCD_SPEED_HIGH: High speed mode
526 * @arg PCD_SPEED_FULL: Full speed mode
528 uint8_t USB_GetDevSpeed(USB_OTG_GlobalTypeDef *USBx)
530 uint32_t USBx_BASE = (uint32_t)USBx;
531 uint8_t speed;
532 uint32_t DevEnumSpeed = USBx_DEVICE->DSTS & USB_OTG_DSTS_ENUMSPD;
534 if (DevEnumSpeed == DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ)
536 speed = USBD_HS_SPEED;
538 else if ((DevEnumSpeed == DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ) ||
539 (DevEnumSpeed == DSTS_ENUMSPD_FS_PHY_48MHZ))
541 speed = USBD_FS_SPEED;
543 else
545 speed = 0xFU;
548 return speed;
552 * @brief Activate and configure an endpoint
553 * @param USBx Selected device
554 * @param ep pointer to endpoint structure
555 * @retval HAL status
557 HAL_StatusTypeDef USB_ActivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep)
559 uint32_t USBx_BASE = (uint32_t)USBx;
560 uint32_t epnum = (uint32_t)ep->num;
562 if (ep->is_in == 1U)
564 USBx_DEVICE->DAINTMSK |= USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK));
566 if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_USBAEP) == 0U)
568 USBx_INEP(epnum)->DIEPCTL |= (ep->maxpacket & USB_OTG_DIEPCTL_MPSIZ) |
569 ((uint32_t)ep->type << 18) | (epnum << 22) |
570 USB_OTG_DIEPCTL_SD0PID_SEVNFRM |
571 USB_OTG_DIEPCTL_USBAEP;
574 else
576 USBx_DEVICE->DAINTMSK |= USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16);
578 if (((USBx_OUTEP(epnum)->DOEPCTL) & USB_OTG_DOEPCTL_USBAEP) == 0U)
580 USBx_OUTEP(epnum)->DOEPCTL |= (ep->maxpacket & USB_OTG_DOEPCTL_MPSIZ) |
581 ((uint32_t)ep->type << 18) |
582 USB_OTG_DIEPCTL_SD0PID_SEVNFRM |
583 USB_OTG_DOEPCTL_USBAEP;
586 return HAL_OK;
590 * @brief Activate and configure a dedicated endpoint
591 * @param USBx Selected device
592 * @param ep pointer to endpoint structure
593 * @retval HAL status
595 HAL_StatusTypeDef USB_ActivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep)
597 uint32_t USBx_BASE = (uint32_t)USBx;
598 uint32_t epnum = (uint32_t)ep->num;
600 /* Read DEPCTLn register */
601 if (ep->is_in == 1U)
603 if (((USBx_INEP(epnum)->DIEPCTL) & USB_OTG_DIEPCTL_USBAEP) == 0U)
605 USBx_INEP(epnum)->DIEPCTL |= (ep->maxpacket & USB_OTG_DIEPCTL_MPSIZ) |
606 ((uint32_t)ep->type << 18) | (epnum << 22) |
607 USB_OTG_DIEPCTL_SD0PID_SEVNFRM |
608 USB_OTG_DIEPCTL_USBAEP;
611 USBx_DEVICE->DEACHMSK |= USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK));
613 else
615 if (((USBx_OUTEP(epnum)->DOEPCTL) & USB_OTG_DOEPCTL_USBAEP) == 0U)
617 USBx_OUTEP(epnum)->DOEPCTL |= (ep->maxpacket & USB_OTG_DOEPCTL_MPSIZ) |
618 ((uint32_t)ep->type << 18) | (epnum << 22) |
619 USB_OTG_DOEPCTL_USBAEP;
622 USBx_DEVICE->DEACHMSK |= USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16);
625 return HAL_OK;
629 * @brief De-activate and de-initialize an endpoint
630 * @param USBx Selected device
631 * @param ep pointer to endpoint structure
632 * @retval HAL status
634 HAL_StatusTypeDef USB_DeactivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep)
636 uint32_t USBx_BASE = (uint32_t)USBx;
637 uint32_t epnum = (uint32_t)ep->num;
639 /* Read DEPCTLn register */
640 if (ep->is_in == 1U)
642 if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA)
644 USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SNAK;
645 USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_EPDIS;
648 USBx_DEVICE->DEACHMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK)));
649 USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK)));
650 USBx_INEP(epnum)->DIEPCTL &= ~(USB_OTG_DIEPCTL_USBAEP |
651 USB_OTG_DIEPCTL_MPSIZ |
652 USB_OTG_DIEPCTL_TXFNUM |
653 USB_OTG_DIEPCTL_SD0PID_SEVNFRM |
654 USB_OTG_DIEPCTL_EPTYP);
656 else
658 if ((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA)
660 USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK;
661 USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_EPDIS;
664 USBx_DEVICE->DEACHMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16));
665 USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16));
666 USBx_OUTEP(epnum)->DOEPCTL &= ~(USB_OTG_DOEPCTL_USBAEP |
667 USB_OTG_DOEPCTL_MPSIZ |
668 USB_OTG_DOEPCTL_SD0PID_SEVNFRM |
669 USB_OTG_DOEPCTL_EPTYP);
672 return HAL_OK;
676 * @brief De-activate and de-initialize a dedicated endpoint
677 * @param USBx Selected device
678 * @param ep pointer to endpoint structure
679 * @retval HAL status
681 HAL_StatusTypeDef USB_DeactivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep)
683 uint32_t USBx_BASE = (uint32_t)USBx;
684 uint32_t epnum = (uint32_t)ep->num;
686 /* Read DEPCTLn register */
687 if (ep->is_in == 1U)
689 if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA)
691 USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SNAK;
692 USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_EPDIS;
695 USBx_INEP(epnum)->DIEPCTL &= ~ USB_OTG_DIEPCTL_USBAEP;
696 USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK)));
698 else
700 if ((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA)
702 USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK;
703 USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_EPDIS;
706 USBx_OUTEP(epnum)->DOEPCTL &= ~USB_OTG_DOEPCTL_USBAEP;
707 USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16));
710 return HAL_OK;
714 * @brief USB_EPStartXfer : setup and starts a transfer over an EP
715 * @param USBx Selected device
716 * @param ep pointer to endpoint structure
717 * @param dma USB dma enabled or disabled
718 * This parameter can be one of these values:
719 * 0 : DMA feature not used
720 * 1 : DMA feature used
721 * @retval HAL status
723 HAL_StatusTypeDef USB_EPStartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma)
725 uint32_t USBx_BASE = (uint32_t)USBx;
726 uint32_t epnum = (uint32_t)ep->num;
727 uint16_t pktcnt;
729 /* IN endpoint */
730 if (ep->is_in == 1U)
732 /* Zero Length Packet? */
733 if (ep->xfer_len == 0U)
735 USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT);
736 USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19));
737 USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ);
739 else
741 /* Program the transfer size and packet count
742 * as follows: xfersize = N * maxpacket +
743 * short_packet pktcnt = N + (short_packet
744 * exist ? 1 : 0)
746 USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ);
747 USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT);
748 USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (((ep->xfer_len + ep->maxpacket - 1U) / ep->maxpacket) << 19));
749 USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_XFRSIZ & ep->xfer_len);
751 if (ep->type == EP_TYPE_ISOC)
753 USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_MULCNT);
754 USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_MULCNT & (1U << 29));
758 if (dma == 1U)
760 if ((uint32_t)ep->dma_addr != 0U)
762 USBx_INEP(epnum)->DIEPDMA = (uint32_t)(ep->dma_addr);
765 if (ep->type == EP_TYPE_ISOC)
767 if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U)
769 USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SODDFRM;
771 else
773 USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM;
777 /* EP enable, IN data in FIFO */
778 USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA);
780 else
782 /* EP enable, IN data in FIFO */
783 USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA);
785 if (ep->type != EP_TYPE_ISOC)
787 /* Enable the Tx FIFO Empty Interrupt for this EP */
788 if (ep->xfer_len > 0U)
790 USBx_DEVICE->DIEPEMPMSK |= 1UL << (ep->num & EP_ADDR_MSK);
793 else
795 if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U)
797 USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SODDFRM;
799 else
801 USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM;
804 (void)USB_WritePacket(USBx, ep->xfer_buff, ep->num, (uint16_t)ep->xfer_len, dma);
808 else /* OUT endpoint */
810 /* Program the transfer size and packet count as follows:
811 * pktcnt = N
812 * xfersize = N * maxpacket
814 USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_XFRSIZ);
815 USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT);
817 if (ep->xfer_len == 0U)
819 USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_XFRSIZ & ep->maxpacket);
820 USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19));
822 else
824 pktcnt = (uint16_t)((ep->xfer_len + ep->maxpacket - 1U) / ep->maxpacket);
825 USBx_OUTEP(epnum)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_PKTCNT & ((uint32_t)pktcnt << 19);
826 USBx_OUTEP(epnum)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_XFRSIZ & (ep->maxpacket * pktcnt);
829 if (dma == 1U)
831 if ((uint32_t)ep->xfer_buff != 0U)
833 USBx_OUTEP(epnum)->DOEPDMA = (uint32_t)(ep->xfer_buff);
837 if (ep->type == EP_TYPE_ISOC)
839 if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U)
841 USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SODDFRM;
843 else
845 USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM;
848 /* EP enable */
849 USBx_OUTEP(epnum)->DOEPCTL |= (USB_OTG_DOEPCTL_CNAK | USB_OTG_DOEPCTL_EPENA);
852 return HAL_OK;
856 * @brief USB_EP0StartXfer : setup and starts a transfer over the EP 0
857 * @param USBx Selected device
858 * @param ep pointer to endpoint structure
859 * @param dma USB dma enabled or disabled
860 * This parameter can be one of these values:
861 * 0 : DMA feature not used
862 * 1 : DMA feature used
863 * @retval HAL status
865 HAL_StatusTypeDef USB_EP0StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma)
867 uint32_t USBx_BASE = (uint32_t)USBx;
868 uint32_t epnum = (uint32_t)ep->num;
870 /* IN endpoint */
871 if (ep->is_in == 1U)
873 /* Zero Length Packet? */
874 if (ep->xfer_len == 0U)
876 USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT);
877 USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19));
878 USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ);
880 else
882 /* Program the transfer size and packet count
883 * as follows: xfersize = N * maxpacket +
884 * short_packet pktcnt = N + (short_packet
885 * exist ? 1 : 0)
887 USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ);
888 USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT);
890 if (ep->xfer_len > ep->maxpacket)
892 ep->xfer_len = ep->maxpacket;
894 USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19));
895 USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_XFRSIZ & ep->xfer_len);
898 if (dma == 1U)
900 if ((uint32_t)ep->dma_addr != 0U)
902 USBx_INEP(epnum)->DIEPDMA = (uint32_t)(ep->dma_addr);
905 /* EP enable, IN data in FIFO */
906 USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA);
908 else
910 /* EP enable, IN data in FIFO */
911 USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA);
913 /* Enable the Tx FIFO Empty Interrupt for this EP */
914 if (ep->xfer_len > 0U)
916 USBx_DEVICE->DIEPEMPMSK |= 1UL << (ep->num & EP_ADDR_MSK);
920 else /* OUT endpoint */
922 /* Program the transfer size and packet count as follows:
923 * pktcnt = N
924 * xfersize = N * maxpacket
926 USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_XFRSIZ);
927 USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT);
929 if (ep->xfer_len > 0U)
931 ep->xfer_len = ep->maxpacket;
934 USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19));
935 USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_XFRSIZ & (ep->maxpacket));
937 if (dma == 1U)
939 if ((uint32_t)ep->xfer_buff != 0U)
941 USBx_OUTEP(epnum)->DOEPDMA = (uint32_t)(ep->xfer_buff);
945 /* EP enable */
946 USBx_OUTEP(epnum)->DOEPCTL |= (USB_OTG_DOEPCTL_CNAK | USB_OTG_DOEPCTL_EPENA);
949 return HAL_OK;
953 * @brief USB_WritePacket : Writes a packet into the Tx FIFO associated
954 * with the EP/channel
955 * @param USBx Selected device
956 * @param src pointer to source buffer
957 * @param ch_ep_num endpoint or host channel number
958 * @param len Number of bytes to write
959 * @param dma USB dma enabled or disabled
960 * This parameter can be one of these values:
961 * 0 : DMA feature not used
962 * 1 : DMA feature used
963 * @retval HAL status
965 HAL_StatusTypeDef USB_WritePacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *src, uint8_t ch_ep_num, uint16_t len, uint8_t dma)
967 uint32_t USBx_BASE = (uint32_t)USBx;
968 uint32_t *pSrc = (uint32_t *)src;
969 uint32_t count32b, i;
971 if (dma == 0U)
973 count32b = ((uint32_t)len + 3U) / 4U;
974 for (i = 0U; i < count32b; i++)
976 USBx_DFIFO((uint32_t)ch_ep_num) = __UNALIGNED_UINT32_READ(pSrc);
977 pSrc++;
981 return HAL_OK;
985 * @brief USB_ReadPacket : read a packet from the RX FIFO
986 * @param USBx Selected device
987 * @param dest source pointer
988 * @param len Number of bytes to read
989 * @retval pointer to destination buffer
991 void *USB_ReadPacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *dest, uint16_t len)
993 uint32_t USBx_BASE = (uint32_t)USBx;
994 uint32_t *pDest = (uint32_t *)dest;
995 uint32_t i;
996 uint32_t count32b = ((uint32_t)len + 3U) / 4U;
998 for (i = 0U; i < count32b; i++)
1000 __UNALIGNED_UINT32_WRITE(pDest, USBx_DFIFO(0U));
1001 pDest++;
1004 return ((void *)pDest);
1008 * @brief USB_EPSetStall : set a stall condition over an EP
1009 * @param USBx Selected device
1010 * @param ep pointer to endpoint structure
1011 * @retval HAL status
1013 HAL_StatusTypeDef USB_EPSetStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep)
1015 uint32_t USBx_BASE = (uint32_t)USBx;
1016 uint32_t epnum = (uint32_t)ep->num;
1018 if (ep->is_in == 1U)
1020 if (((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == 0U) && (epnum != 0U))
1022 USBx_INEP(epnum)->DIEPCTL &= ~(USB_OTG_DIEPCTL_EPDIS);
1024 USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_STALL;
1026 else
1028 if (((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == 0U) && (epnum != 0U))
1030 USBx_OUTEP(epnum)->DOEPCTL &= ~(USB_OTG_DOEPCTL_EPDIS);
1032 USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_STALL;
1035 return HAL_OK;
1039 * @brief USB_EPClearStall : Clear a stall condition over an EP
1040 * @param USBx Selected device
1041 * @param ep pointer to endpoint structure
1042 * @retval HAL status
1044 HAL_StatusTypeDef USB_EPClearStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep)
1046 uint32_t USBx_BASE = (uint32_t)USBx;
1047 uint32_t epnum = (uint32_t)ep->num;
1049 if (ep->is_in == 1U)
1051 USBx_INEP(epnum)->DIEPCTL &= ~USB_OTG_DIEPCTL_STALL;
1052 if ((ep->type == EP_TYPE_INTR) || (ep->type == EP_TYPE_BULK))
1054 USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; /* DATA0 */
1057 else
1059 USBx_OUTEP(epnum)->DOEPCTL &= ~USB_OTG_DOEPCTL_STALL;
1060 if ((ep->type == EP_TYPE_INTR) || (ep->type == EP_TYPE_BULK))
1062 USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; /* DATA0 */
1065 return HAL_OK;
1069 * @brief USB_StopDevice : Stop the usb device mode
1070 * @param USBx Selected device
1071 * @retval HAL status
1073 HAL_StatusTypeDef USB_StopDevice(USB_OTG_GlobalTypeDef *USBx)
1075 HAL_StatusTypeDef ret;
1076 uint32_t USBx_BASE = (uint32_t)USBx;
1077 uint32_t i;
1079 /* Clear Pending interrupt */
1080 for (i = 0U; i < 15U; i++)
1082 USBx_INEP(i)->DIEPINT = 0xFB7FU;
1083 USBx_OUTEP(i)->DOEPINT = 0xFB7FU;
1086 /* Clear interrupt masks */
1087 USBx_DEVICE->DIEPMSK = 0U;
1088 USBx_DEVICE->DOEPMSK = 0U;
1089 USBx_DEVICE->DAINTMSK = 0U;
1091 /* Flush the FIFO */
1092 ret = USB_FlushRxFifo(USBx);
1093 if (ret != HAL_OK)
1095 return ret;
1098 ret = USB_FlushTxFifo(USBx, 0x10U);
1099 if (ret != HAL_OK)
1101 return ret;
1104 return ret;
1108 * @brief USB_SetDevAddress : Stop the usb device mode
1109 * @param USBx Selected device
1110 * @param address new device address to be assigned
1111 * This parameter can be a value from 0 to 255
1112 * @retval HAL status
1114 HAL_StatusTypeDef USB_SetDevAddress(USB_OTG_GlobalTypeDef *USBx, uint8_t address)
1116 uint32_t USBx_BASE = (uint32_t)USBx;
1118 USBx_DEVICE->DCFG &= ~(USB_OTG_DCFG_DAD);
1119 USBx_DEVICE->DCFG |= ((uint32_t)address << 4) & USB_OTG_DCFG_DAD;
1121 return HAL_OK;
1125 * @brief USB_DevConnect : Connect the USB device by enabling the pull-up/pull-down
1126 * @param USBx Selected device
1127 * @retval HAL status
1129 HAL_StatusTypeDef USB_DevConnect(USB_OTG_GlobalTypeDef *USBx)
1131 uint32_t USBx_BASE = (uint32_t)USBx;
1133 USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_SDIS;
1134 HAL_Delay(3U);
1136 return HAL_OK;
1140 * @brief USB_DevDisconnect : Disconnect the USB device by disabling the pull-up/pull-down
1141 * @param USBx Selected device
1142 * @retval HAL status
1144 HAL_StatusTypeDef USB_DevDisconnect(USB_OTG_GlobalTypeDef *USBx)
1146 uint32_t USBx_BASE = (uint32_t)USBx;
1148 USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS;
1149 HAL_Delay(3U);
1151 return HAL_OK;
1155 * @brief USB_ReadInterrupts: return the global USB interrupt status
1156 * @param USBx Selected device
1157 * @retval HAL status
1159 uint32_t USB_ReadInterrupts(USB_OTG_GlobalTypeDef *USBx)
1161 uint32_t tmpreg;
1163 tmpreg = USBx->GINTSTS;
1164 tmpreg &= USBx->GINTMSK;
1166 return tmpreg;
1170 * @brief USB_ReadDevAllOutEpInterrupt: return the USB device OUT endpoints interrupt status
1171 * @param USBx Selected device
1172 * @retval HAL status
1174 uint32_t USB_ReadDevAllOutEpInterrupt(USB_OTG_GlobalTypeDef *USBx)
1176 uint32_t USBx_BASE = (uint32_t)USBx;
1177 uint32_t tmpreg;
1179 tmpreg = USBx_DEVICE->DAINT;
1180 tmpreg &= USBx_DEVICE->DAINTMSK;
1182 return ((tmpreg & 0xffff0000U) >> 16);
1186 * @brief USB_ReadDevAllInEpInterrupt: return the USB device IN endpoints interrupt status
1187 * @param USBx Selected device
1188 * @retval HAL status
1190 uint32_t USB_ReadDevAllInEpInterrupt(USB_OTG_GlobalTypeDef *USBx)
1192 uint32_t USBx_BASE = (uint32_t)USBx;
1193 uint32_t tmpreg;
1195 tmpreg = USBx_DEVICE->DAINT;
1196 tmpreg &= USBx_DEVICE->DAINTMSK;
1198 return ((tmpreg & 0xFFFFU));
1202 * @brief Returns Device OUT EP Interrupt register
1203 * @param USBx Selected device
1204 * @param epnum endpoint number
1205 * This parameter can be a value from 0 to 15
1206 * @retval Device OUT EP Interrupt register
1208 uint32_t USB_ReadDevOutEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum)
1210 uint32_t USBx_BASE = (uint32_t)USBx;
1211 uint32_t tmpreg;
1213 tmpreg = USBx_OUTEP((uint32_t)epnum)->DOEPINT;
1214 tmpreg &= USBx_DEVICE->DOEPMSK;
1216 return tmpreg;
1220 * @brief Returns Device IN EP Interrupt register
1221 * @param USBx Selected device
1222 * @param epnum endpoint number
1223 * This parameter can be a value from 0 to 15
1224 * @retval Device IN EP Interrupt register
1226 uint32_t USB_ReadDevInEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum)
1228 uint32_t USBx_BASE = (uint32_t)USBx;
1229 uint32_t tmpreg, msk, emp;
1231 msk = USBx_DEVICE->DIEPMSK;
1232 emp = USBx_DEVICE->DIEPEMPMSK;
1233 msk |= ((emp >> (epnum & EP_ADDR_MSK)) & 0x1U) << 7;
1234 tmpreg = USBx_INEP((uint32_t)epnum)->DIEPINT & msk;
1236 return tmpreg;
1240 * @brief USB_ClearInterrupts: clear a USB interrupt
1241 * @param USBx Selected device
1242 * @param interrupt interrupt flag
1243 * @retval None
1245 void USB_ClearInterrupts(USB_OTG_GlobalTypeDef *USBx, uint32_t interrupt)
1247 USBx->GINTSTS |= interrupt;
1251 * @brief Returns USB core mode
1252 * @param USBx Selected device
1253 * @retval return core mode : Host or Device
1254 * This parameter can be one of these values:
1255 * 0 : Host
1256 * 1 : Device
1258 uint32_t USB_GetMode(USB_OTG_GlobalTypeDef *USBx)
1260 return ((USBx->GINTSTS) & 0x1U);
1264 * @brief Activate EP0 for Setup transactions
1265 * @param USBx Selected device
1266 * @retval HAL status
1268 HAL_StatusTypeDef USB_ActivateSetup(USB_OTG_GlobalTypeDef *USBx)
1270 uint32_t USBx_BASE = (uint32_t)USBx;
1272 /* Set the MPS of the IN EP0 to 64 bytes */
1273 USBx_INEP(0U)->DIEPCTL &= ~USB_OTG_DIEPCTL_MPSIZ;
1275 USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK;
1277 return HAL_OK;
1281 * @brief Prepare the EP0 to start the first control setup
1282 * @param USBx Selected device
1283 * @param dma USB dma enabled or disabled
1284 * This parameter can be one of these values:
1285 * 0 : DMA feature not used
1286 * 1 : DMA feature used
1287 * @param psetup pointer to setup packet
1288 * @retval HAL status
1290 HAL_StatusTypeDef USB_EP0_OutStart(USB_OTG_GlobalTypeDef *USBx, uint8_t dma, uint8_t *psetup)
1292 uint32_t USBx_BASE = (uint32_t)USBx;
1293 uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U);
1295 if (gSNPSiD > USB_OTG_CORE_ID_300A)
1297 if ((USBx_OUTEP(0U)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA)
1299 return HAL_OK;
1303 USBx_OUTEP(0U)->DOEPTSIZ = 0U;
1304 USBx_OUTEP(0U)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19));
1305 USBx_OUTEP(0U)->DOEPTSIZ |= (3U * 8U);
1306 USBx_OUTEP(0U)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_STUPCNT;
1308 if (dma == 1U)
1310 USBx_OUTEP(0U)->DOEPDMA = (uint32_t)psetup;
1311 /* EP enable */
1312 USBx_OUTEP(0U)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_USBAEP;
1315 return HAL_OK;
1319 * @brief Reset the USB Core (needed after USB clock settings change)
1320 * @param USBx Selected device
1321 * @retval HAL status
1323 static HAL_StatusTypeDef USB_CoreReset(USB_OTG_GlobalTypeDef *USBx)
1325 uint32_t tickstart;
1327 /* Get tick */
1328 tickstart = HAL_GetTick();
1330 /* Wait for AHB master IDLE state. */
1331 while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U)
1333 if ((HAL_GetTick() - tickstart) > USB_OTG_GRSTCTL_AHBIDL_TIMEOUT_MS)
1335 return HAL_TIMEOUT;
1339 /* Core Soft Reset */
1340 USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST;
1342 /* Get tick */
1343 tickstart = HAL_GetTick();
1345 while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST)
1347 if ((HAL_GetTick() - tickstart) > USB_OTG_GRSTCTL_CSRST_TIMEOUT_MS)
1349 return HAL_TIMEOUT;
1353 return HAL_OK;
1357 * @brief USB_HostInit : Initializes the USB OTG controller registers
1358 * for Host mode
1359 * @param USBx Selected device
1360 * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains
1361 * the configuration information for the specified USBx peripheral.
1362 * @retval HAL status
1364 HAL_StatusTypeDef USB_HostInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg)
1366 uint32_t USBx_BASE = (uint32_t)USBx;
1367 uint32_t i;
1369 /* Restart the Phy Clock */
1370 USBx_PCGCCTL = 0U;
1372 /* Disable VBUS sensing */
1373 USBx->GCCFG &= ~(USB_OTG_GCCFG_VBDEN);
1375 /* Disable Battery chargin detector */
1376 USBx->GCCFG &= ~(USB_OTG_GCCFG_BCDEN);
1379 if ((USBx->CID & (0x1U << 8)) != 0U)
1381 if (cfg.speed == USBH_FSLS_SPEED)
1383 /* Force Device Enumeration to FS/LS mode only */
1384 USBx_HOST->HCFG |= USB_OTG_HCFG_FSLSS;
1386 else
1388 /* Set default Max speed support */
1389 USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSS);
1392 else
1394 /* Set default Max speed support */
1395 USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSS);
1398 /* Make sure the FIFOs are flushed. */
1399 (void)USB_FlushTxFifo(USBx, 0x10U); /* all Tx FIFOs */
1400 (void)USB_FlushRxFifo(USBx);
1402 /* Clear all pending HC Interrupts */
1403 for (i = 0U; i < cfg.Host_channels; i++)
1405 USBx_HC(i)->HCINT = 0xFFFFFFFFU;
1406 USBx_HC(i)->HCINTMSK = 0U;
1409 /* Enable VBUS driving */
1410 (void)USB_DriveVbus(USBx, 1U);
1412 HAL_Delay(200U);
1414 /* Disable all interrupts. */
1415 USBx->GINTMSK = 0U;
1417 /* Clear any pending interrupts */
1418 USBx->GINTSTS = 0xFFFFFFFFU;
1420 if ((USBx->CID & (0x1U << 8)) != 0U)
1422 /* set Rx FIFO size */
1423 USBx->GRXFSIZ = 0x200U;
1424 USBx->DIEPTXF0_HNPTXFSIZ = (uint32_t)(((0x100U << 16) & USB_OTG_NPTXFD) | 0x200U);
1425 USBx->HPTXFSIZ = (uint32_t)(((0xE0U << 16) & USB_OTG_HPTXFSIZ_PTXFD) | 0x300U);
1427 else
1429 /* set Rx FIFO size */
1430 USBx->GRXFSIZ = 0x80U;
1431 USBx->DIEPTXF0_HNPTXFSIZ = (uint32_t)(((0x60U << 16) & USB_OTG_NPTXFD) | 0x80U);
1432 USBx->HPTXFSIZ = (uint32_t)(((0x40U << 16)& USB_OTG_HPTXFSIZ_PTXFD) | 0xE0U);
1435 /* Enable the common interrupts */
1436 if (cfg.dma_enable == 0U)
1438 USBx->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM;
1441 /* Enable interrupts matching to the Host mode ONLY */
1442 USBx->GINTMSK |= (USB_OTG_GINTMSK_PRTIM | USB_OTG_GINTMSK_HCIM | \
1443 USB_OTG_GINTMSK_SOFM | USB_OTG_GINTSTS_DISCINT | \
1444 USB_OTG_GINTMSK_PXFRM_IISOOXFRM | USB_OTG_GINTMSK_WUIM);
1446 return HAL_OK;
1450 * @brief USB_InitFSLSPClkSel : Initializes the FSLSPClkSel field of the
1451 * HCFG register on the PHY type and set the right frame interval
1452 * @param USBx Selected device
1453 * @param freq clock frequency
1454 * This parameter can be one of these values:
1455 * HCFG_48_MHZ : Full Speed 48 MHz Clock
1456 * HCFG_6_MHZ : Low Speed 6 MHz Clock
1457 * @retval HAL status
1459 HAL_StatusTypeDef USB_InitFSLSPClkSel(USB_OTG_GlobalTypeDef *USBx, uint8_t freq)
1461 uint32_t USBx_BASE = (uint32_t)USBx;
1463 USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSPCS);
1464 USBx_HOST->HCFG |= (uint32_t)freq & USB_OTG_HCFG_FSLSPCS;
1466 if (freq == HCFG_48_MHZ)
1468 USBx_HOST->HFIR = 48000U;
1470 else if (freq == HCFG_6_MHZ)
1472 USBx_HOST->HFIR = 6000U;
1474 else
1476 /* ... */
1479 return HAL_OK;
1483 * @brief USB_OTG_ResetPort : Reset Host Port
1484 * @param USBx Selected device
1485 * @retval HAL status
1486 * @note (1)The application must wait at least 10 ms
1487 * before clearing the reset bit.
1489 HAL_StatusTypeDef USB_ResetPort(USB_OTG_GlobalTypeDef *USBx)
1491 uint32_t USBx_BASE = (uint32_t)USBx;
1493 __IO uint32_t hprt0 = 0U;
1495 hprt0 = USBx_HPRT0;
1497 hprt0 &= ~(USB_OTG_HPRT_PENA | USB_OTG_HPRT_PCDET |
1498 USB_OTG_HPRT_PENCHNG | USB_OTG_HPRT_POCCHNG);
1500 USBx_HPRT0 = (USB_OTG_HPRT_PRST | hprt0);
1501 HAL_Delay(100U); /* See Note #1 */
1502 USBx_HPRT0 = ((~USB_OTG_HPRT_PRST) & hprt0);
1503 HAL_Delay(10U);
1505 return HAL_OK;
1509 * @brief USB_DriveVbus : activate or de-activate vbus
1510 * @param state VBUS state
1511 * This parameter can be one of these values:
1512 * 0 : VBUS Active
1513 * 1 : VBUS Inactive
1514 * @retval HAL status
1516 HAL_StatusTypeDef USB_DriveVbus(USB_OTG_GlobalTypeDef *USBx, uint8_t state)
1518 uint32_t USBx_BASE = (uint32_t)USBx;
1519 __IO uint32_t hprt0 = 0U;
1521 hprt0 = USBx_HPRT0;
1523 hprt0 &= ~(USB_OTG_HPRT_PENA | USB_OTG_HPRT_PCDET |
1524 USB_OTG_HPRT_PENCHNG | USB_OTG_HPRT_POCCHNG);
1526 if (((hprt0 & USB_OTG_HPRT_PPWR) == 0U) && (state == 1U))
1528 USBx_HPRT0 = (USB_OTG_HPRT_PPWR | hprt0);
1530 if (((hprt0 & USB_OTG_HPRT_PPWR) == USB_OTG_HPRT_PPWR) && (state == 0U))
1532 USBx_HPRT0 = ((~USB_OTG_HPRT_PPWR) & hprt0);
1534 return HAL_OK;
1538 * @brief Return Host Core speed
1539 * @param USBx Selected device
1540 * @retval speed : Host speed
1541 * This parameter can be one of these values:
1542 * @arg HCD_SPEED_HIGH: High speed mode
1543 * @arg HCD_SPEED_FULL: Full speed mode
1544 * @arg HCD_SPEED_LOW: Low speed mode
1546 uint32_t USB_GetHostSpeed(USB_OTG_GlobalTypeDef *USBx)
1548 uint32_t USBx_BASE = (uint32_t)USBx;
1549 __IO uint32_t hprt0 = 0U;
1551 hprt0 = USBx_HPRT0;
1552 return ((hprt0 & USB_OTG_HPRT_PSPD) >> 17);
1556 * @brief Return Host Current Frame number
1557 * @param USBx Selected device
1558 * @retval current frame number
1560 uint32_t USB_GetCurrentFrame(USB_OTG_GlobalTypeDef *USBx)
1562 uint32_t USBx_BASE = (uint32_t)USBx;
1564 return (USBx_HOST->HFNUM & USB_OTG_HFNUM_FRNUM);
1568 * @brief Initialize a host channel
1569 * @param USBx Selected device
1570 * @param ch_num Channel number
1571 * This parameter can be a value from 1 to 15
1572 * @param epnum Endpoint number
1573 * This parameter can be a value from 1 to 15
1574 * @param dev_address Current device address
1575 * This parameter can be a value from 0 to 255
1576 * @param speed Current device speed
1577 * This parameter can be one of these values:
1578 * @arg USB_OTG_SPEED_HIGH: High speed mode
1579 * @arg USB_OTG_SPEED_FULL: Full speed mode
1580 * @arg USB_OTG_SPEED_LOW: Low speed mode
1581 * @param ep_type Endpoint Type
1582 * This parameter can be one of these values:
1583 * @arg EP_TYPE_CTRL: Control type
1584 * @arg EP_TYPE_ISOC: Isochronous type
1585 * @arg EP_TYPE_BULK: Bulk type
1586 * @arg EP_TYPE_INTR: Interrupt type
1587 * @param mps Max Packet Size
1588 * This parameter can be a value from 0 to32K
1589 * @retval HAL state
1591 HAL_StatusTypeDef USB_HC_Init(USB_OTG_GlobalTypeDef *USBx,
1592 uint8_t ch_num,
1593 uint8_t epnum,
1594 uint8_t dev_address,
1595 uint8_t speed,
1596 uint8_t ep_type,
1597 uint16_t mps)
1599 HAL_StatusTypeDef ret = HAL_OK;
1600 uint32_t USBx_BASE = (uint32_t)USBx;
1601 uint32_t HCcharEpDir, HCcharLowSpeed;
1603 /* Clear old interrupt conditions for this host channel. */
1604 USBx_HC((uint32_t)ch_num)->HCINT = 0xFFFFFFFFU;
1606 /* Enable channel interrupts required for this transfer. */
1607 switch (ep_type)
1609 case EP_TYPE_CTRL:
1610 case EP_TYPE_BULK:
1611 USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM |
1612 USB_OTG_HCINTMSK_STALLM |
1613 USB_OTG_HCINTMSK_TXERRM |
1614 USB_OTG_HCINTMSK_DTERRM |
1615 USB_OTG_HCINTMSK_AHBERR |
1616 USB_OTG_HCINTMSK_NAKM;
1618 if ((epnum & 0x80U) == 0x80U)
1620 USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_BBERRM;
1622 else
1624 if ((USBx->CID & (0x1U << 8)) != 0U)
1626 USBx_HC((uint32_t)ch_num)->HCINTMSK |= (USB_OTG_HCINTMSK_NYET | USB_OTG_HCINTMSK_ACKM);
1629 break;
1631 case EP_TYPE_INTR:
1632 USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM |
1633 USB_OTG_HCINTMSK_STALLM |
1634 USB_OTG_HCINTMSK_TXERRM |
1635 USB_OTG_HCINTMSK_DTERRM |
1636 USB_OTG_HCINTMSK_NAKM |
1637 USB_OTG_HCINTMSK_AHBERR |
1638 USB_OTG_HCINTMSK_FRMORM;
1640 if ((epnum & 0x80U) == 0x80U)
1642 USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_BBERRM;
1645 break;
1647 case EP_TYPE_ISOC:
1648 USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM |
1649 USB_OTG_HCINTMSK_ACKM |
1650 USB_OTG_HCINTMSK_AHBERR |
1651 USB_OTG_HCINTMSK_FRMORM;
1653 if ((epnum & 0x80U) == 0x80U)
1655 USBx_HC((uint32_t)ch_num)->HCINTMSK |= (USB_OTG_HCINTMSK_TXERRM | USB_OTG_HCINTMSK_BBERRM);
1657 break;
1659 default:
1660 ret = HAL_ERROR;
1661 break;
1664 /* Enable the top level host channel interrupt. */
1665 USBx_HOST->HAINTMSK |= 1UL << (ch_num & 0xFU);
1667 /* Make sure host channel interrupts are enabled. */
1668 USBx->GINTMSK |= USB_OTG_GINTMSK_HCIM;
1670 /* Program the HCCHAR register */
1671 if ((epnum & 0x80U) == 0x80U)
1673 HCcharEpDir = (0x1U << 15) & USB_OTG_HCCHAR_EPDIR;
1675 else
1677 HCcharEpDir = 0U;
1680 if (speed == HPRT0_PRTSPD_LOW_SPEED)
1682 HCcharLowSpeed = (0x1U << 17) & USB_OTG_HCCHAR_LSDEV;
1684 else
1686 HCcharLowSpeed = 0U;
1689 USBx_HC((uint32_t)ch_num)->HCCHAR = (((uint32_t)dev_address << 22) & USB_OTG_HCCHAR_DAD) |
1690 ((((uint32_t)epnum & 0x7FU) << 11) & USB_OTG_HCCHAR_EPNUM) |
1691 (((uint32_t)ep_type << 18) & USB_OTG_HCCHAR_EPTYP) |
1692 ((uint32_t)mps & USB_OTG_HCCHAR_MPSIZ) | HCcharEpDir | HCcharLowSpeed;
1694 if (ep_type == EP_TYPE_INTR)
1696 USBx_HC((uint32_t)ch_num)->HCCHAR |= USB_OTG_HCCHAR_ODDFRM ;
1699 return ret;
1703 * @brief Start a transfer over a host channel
1704 * @param USBx Selected device
1705 * @param hc pointer to host channel structure
1706 * @param dma USB dma enabled or disabled
1707 * This parameter can be one of these values:
1708 * 0 : DMA feature not used
1709 * 1 : DMA feature used
1710 * @retval HAL state
1712 HAL_StatusTypeDef USB_HC_StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_HCTypeDef *hc, uint8_t dma)
1714 uint32_t USBx_BASE = (uint32_t)USBx;
1715 uint32_t ch_num = (uint32_t)hc->ch_num;
1716 static __IO uint32_t tmpreg = 0U;
1717 uint8_t is_oddframe;
1718 uint16_t len_words;
1719 uint16_t num_packets;
1720 uint16_t max_hc_pkt_count = 256U;
1722 if (((USBx->CID & (0x1U << 8)) != 0U) && (hc->speed == USBH_HS_SPEED))
1724 if ((dma == 0U) && (hc->do_ping == 1U))
1726 (void)USB_DoPing(USBx, hc->ch_num);
1727 return HAL_OK;
1729 else if (dma == 1U)
1731 USBx_HC(ch_num)->HCINTMSK &= ~(USB_OTG_HCINTMSK_NYET | USB_OTG_HCINTMSK_ACKM);
1732 hc->do_ping = 0U;
1734 else
1736 /* ... */
1740 /* Compute the expected number of packets associated to the transfer */
1741 if (hc->xfer_len > 0U)
1743 num_packets = (uint16_t)((hc->xfer_len + hc->max_packet - 1U) / hc->max_packet);
1745 if (num_packets > max_hc_pkt_count)
1747 num_packets = max_hc_pkt_count;
1748 hc->xfer_len = (uint32_t)num_packets * hc->max_packet;
1751 else
1753 num_packets = 1U;
1755 if (hc->ep_is_in != 0U)
1757 hc->xfer_len = (uint32_t)num_packets * hc->max_packet;
1760 /* Initialize the HCTSIZn register */
1761 USBx_HC(ch_num)->HCTSIZ = (hc->xfer_len & USB_OTG_HCTSIZ_XFRSIZ) |
1762 (((uint32_t)num_packets << 19) & USB_OTG_HCTSIZ_PKTCNT) |
1763 (((uint32_t)hc->data_pid << 29) & USB_OTG_HCTSIZ_DPID);
1765 if (dma != 0U)
1767 /* xfer_buff MUST be 32-bits aligned */
1768 USBx_HC(ch_num)->HCDMA = (uint32_t)hc->xfer_buff;
1771 is_oddframe = (((uint32_t)USBx_HOST->HFNUM & 0x01U) != 0U) ? 0U : 1U;
1772 USBx_HC(ch_num)->HCCHAR &= ~USB_OTG_HCCHAR_ODDFRM;
1773 USBx_HC(ch_num)->HCCHAR |= (uint32_t)is_oddframe << 29;
1775 /* Set host channel enable */
1776 tmpreg = USBx_HC(ch_num)->HCCHAR;
1777 tmpreg &= ~USB_OTG_HCCHAR_CHDIS;
1779 /* make sure to set the correct ep direction */
1780 if (hc->ep_is_in != 0U)
1782 tmpreg |= USB_OTG_HCCHAR_EPDIR;
1784 else
1786 tmpreg &= ~USB_OTG_HCCHAR_EPDIR;
1788 tmpreg |= USB_OTG_HCCHAR_CHENA;
1789 USBx_HC(ch_num)->HCCHAR = tmpreg;
1791 if (dma == 0U) /* Slave mode */
1793 if ((hc->ep_is_in == 0U) && (hc->xfer_len > 0U))
1795 switch (hc->ep_type)
1797 /* Non periodic transfer */
1798 case EP_TYPE_CTRL:
1799 case EP_TYPE_BULK:
1801 len_words = (uint16_t)((hc->xfer_len + 3U) / 4U);
1803 /* check if there is enough space in FIFO space */
1804 if (len_words > (USBx->HNPTXSTS & 0xFFFFU))
1806 /* need to process data in nptxfempty interrupt */
1807 USBx->GINTMSK |= USB_OTG_GINTMSK_NPTXFEM;
1809 break;
1811 /* Periodic transfer */
1812 case EP_TYPE_INTR:
1813 case EP_TYPE_ISOC:
1814 len_words = (uint16_t)((hc->xfer_len + 3U) / 4U);
1815 /* check if there is enough space in FIFO space */
1816 if (len_words > (USBx_HOST->HPTXSTS & 0xFFFFU)) /* split the transfer */
1818 /* need to process data in ptxfempty interrupt */
1819 USBx->GINTMSK |= USB_OTG_GINTMSK_PTXFEM;
1821 break;
1823 default:
1824 break;
1827 /* Write packet into the Tx FIFO. */
1828 (void)USB_WritePacket(USBx, hc->xfer_buff, hc->ch_num, (uint16_t)hc->xfer_len, 0);
1832 return HAL_OK;
1836 * @brief Read all host channel interrupts status
1837 * @param USBx Selected device
1838 * @retval HAL state
1840 uint32_t USB_HC_ReadInterrupt(USB_OTG_GlobalTypeDef *USBx)
1842 uint32_t USBx_BASE = (uint32_t)USBx;
1844 return ((USBx_HOST->HAINT) & 0xFFFFU);
1848 * @brief Halt a host channel
1849 * @param USBx Selected device
1850 * @param hc_num Host Channel number
1851 * This parameter can be a value from 1 to 15
1852 * @retval HAL state
1854 HAL_StatusTypeDef USB_HC_Halt(USB_OTG_GlobalTypeDef *USBx, uint8_t hc_num)
1856 uint32_t USBx_BASE = (uint32_t)USBx;
1857 uint32_t hcnum = (uint32_t)hc_num;
1858 uint32_t count = 0U;
1859 uint32_t HcEpType = (USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_EPTYP) >> 18;
1861 /* Check for space in the request queue to issue the halt. */
1862 if ((HcEpType == HCCHAR_CTRL) || (HcEpType == HCCHAR_BULK))
1864 USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHDIS;
1866 if ((USBx->HNPTXSTS & (0xFFU << 16)) == 0U)
1868 USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_CHENA;
1869 USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA;
1870 USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_EPDIR;
1873 if (++count > 1000U)
1875 break;
1878 while ((USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA);
1880 else
1882 USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA;
1885 else
1887 USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHDIS;
1889 if ((USBx_HOST->HPTXSTS & (0xFFU << 16)) == 0U)
1891 USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_CHENA;
1892 USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA;
1893 USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_EPDIR;
1896 if (++count > 1000U)
1898 break;
1901 while ((USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA);
1903 else
1905 USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA;
1909 return HAL_OK;
1913 * @brief Initiate Do Ping protocol
1914 * @param USBx Selected device
1915 * @param hc_num Host Channel number
1916 * This parameter can be a value from 1 to 15
1917 * @retval HAL state
1919 HAL_StatusTypeDef USB_DoPing(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num)
1921 uint32_t USBx_BASE = (uint32_t)USBx;
1922 uint32_t chnum = (uint32_t)ch_num;
1923 uint32_t num_packets = 1U;
1924 uint32_t tmpreg;
1926 USBx_HC(chnum)->HCTSIZ = ((num_packets << 19) & USB_OTG_HCTSIZ_PKTCNT) |
1927 USB_OTG_HCTSIZ_DOPING;
1929 /* Set host channel enable */
1930 tmpreg = USBx_HC(chnum)->HCCHAR;
1931 tmpreg &= ~USB_OTG_HCCHAR_CHDIS;
1932 tmpreg |= USB_OTG_HCCHAR_CHENA;
1933 USBx_HC(chnum)->HCCHAR = tmpreg;
1935 return HAL_OK;
1939 * @brief Stop Host Core
1940 * @param USBx Selected device
1941 * @retval HAL state
1943 HAL_StatusTypeDef USB_StopHost(USB_OTG_GlobalTypeDef *USBx)
1945 uint32_t USBx_BASE = (uint32_t)USBx;
1946 uint32_t count = 0U;
1947 uint32_t value;
1948 uint32_t i;
1950 (void)USB_DisableGlobalInt(USBx);
1952 /* Flush FIFO */
1953 (void)USB_FlushTxFifo(USBx, 0x10U);
1954 (void)USB_FlushRxFifo(USBx);
1956 /* Flush out any leftover queued requests. */
1957 for (i = 0U; i <= 15U; i++)
1959 value = USBx_HC(i)->HCCHAR;
1960 value |= USB_OTG_HCCHAR_CHDIS;
1961 value &= ~USB_OTG_HCCHAR_CHENA;
1962 value &= ~USB_OTG_HCCHAR_EPDIR;
1963 USBx_HC(i)->HCCHAR = value;
1966 /* Halt all channels to put them into a known state. */
1967 for (i = 0U; i <= 15U; i++)
1969 value = USBx_HC(i)->HCCHAR;
1970 value |= USB_OTG_HCCHAR_CHDIS;
1971 value |= USB_OTG_HCCHAR_CHENA;
1972 value &= ~USB_OTG_HCCHAR_EPDIR;
1973 USBx_HC(i)->HCCHAR = value;
1977 if (++count > 1000U)
1979 break;
1982 while ((USBx_HC(i)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA);
1985 /* Clear any pending Host interrupts */
1986 USBx_HOST->HAINT = 0xFFFFFFFFU;
1987 USBx->GINTSTS = 0xFFFFFFFFU;
1989 (void)USB_EnableGlobalInt(USBx);
1991 return HAL_OK;
1995 * @brief USB_ActivateRemoteWakeup active remote wakeup signalling
1996 * @param USBx Selected device
1997 * @retval HAL status
1999 HAL_StatusTypeDef USB_ActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx)
2001 uint32_t USBx_BASE = (uint32_t)USBx;
2003 if ((USBx_DEVICE->DSTS & USB_OTG_DSTS_SUSPSTS) == USB_OTG_DSTS_SUSPSTS)
2005 /* active Remote wakeup signalling */
2006 USBx_DEVICE->DCTL |= USB_OTG_DCTL_RWUSIG;
2009 return HAL_OK;
2013 * @brief USB_DeActivateRemoteWakeup de-active remote wakeup signalling
2014 * @param USBx Selected device
2015 * @retval HAL status
2017 HAL_StatusTypeDef USB_DeActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx)
2019 uint32_t USBx_BASE = (uint32_t)USBx;
2021 /* active Remote wakeup signalling */
2022 USBx_DEVICE->DCTL &= ~(USB_OTG_DCTL_RWUSIG);
2024 return HAL_OK;
2026 #endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */
2030 * @}
2034 * @}
2036 #endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */
2037 #endif /* defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED) */
2040 * @}
2043 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/