Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32G4 / Drivers / STM32G4xx_HAL_Driver / Src / stm32g4xx_ll_usb.c
blob76b4e1f348d7889550a0be44f5e236ced61a7b6b
1 /**
2 ******************************************************************************
3 * @file stm32g4xx_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 "stm32g4xx_hal.h"
43 /** @addtogroup STM32G4xx_LL_USB_DRIVER
44 * @{
47 #if defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED)
48 #if defined (USB)
49 /* Private typedef -----------------------------------------------------------*/
50 /* Private define ------------------------------------------------------------*/
51 /* Private macro -------------------------------------------------------------*/
52 /* Private variables ---------------------------------------------------------*/
53 /* Private function prototypes -----------------------------------------------*/
54 /* Private functions ---------------------------------------------------------*/
57 /**
58 * @brief Initializes the USB Core
59 * @param USBx: USB Instance
60 * @param cfg : pointer to a USB_CfgTypeDef structure that contains
61 * the configuration information for the specified USBx peripheral.
62 * @retval HAL status
64 HAL_StatusTypeDef USB_CoreInit(USB_TypeDef *USBx, USB_CfgTypeDef cfg)
66 /* Prevent unused argument(s) compilation warning */
67 UNUSED(USBx);
68 UNUSED(cfg);
70 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
71 only by USB OTG FS peripheral.
72 - This function is added to ensure compatibility across platforms.
75 return HAL_OK;
78 /**
79 * @brief USB_EnableGlobalInt
80 * Enables the controller's Global Int in the AHB Config reg
81 * @param USBx : Selected device
82 * @retval HAL status
84 HAL_StatusTypeDef USB_EnableGlobalInt(USB_TypeDef *USBx)
86 uint16_t winterruptmask;
88 /* Set winterruptmask variable */
89 winterruptmask = USB_CNTR_CTRM | USB_CNTR_WKUPM |
90 USB_CNTR_SUSPM | USB_CNTR_ERRM |
91 USB_CNTR_SOFM | USB_CNTR_ESOFM |
92 USB_CNTR_RESETM | USB_CNTR_L1REQM;
94 /* Set interrupt mask */
95 USBx->CNTR |= winterruptmask;
97 return HAL_OK;
101 * @brief USB_DisableGlobalInt
102 * Disable the controller's Global Int in the AHB Config reg
103 * @param USBx : Selected device
104 * @retval HAL status
106 HAL_StatusTypeDef USB_DisableGlobalInt(USB_TypeDef *USBx)
108 uint16_t winterruptmask;
110 /* Set winterruptmask variable */
111 winterruptmask = USB_CNTR_CTRM | USB_CNTR_WKUPM |
112 USB_CNTR_SUSPM | USB_CNTR_ERRM |
113 USB_CNTR_SOFM | USB_CNTR_ESOFM |
114 USB_CNTR_RESETM | USB_CNTR_L1REQM;
116 /* Clear interrupt mask */
117 USBx->CNTR &= ~winterruptmask;
119 return HAL_OK;
123 * @brief USB_SetCurrentMode : Set functional mode
124 * @param USBx : Selected device
125 * @param mode : current core mode
126 * This parameter can be one of the these values:
127 * @arg USB_DEVICE_MODE: Peripheral mode mode
128 * @retval HAL status
130 HAL_StatusTypeDef USB_SetCurrentMode(USB_TypeDef *USBx, USB_ModeTypeDef mode)
132 /* Prevent unused argument(s) compilation warning */
133 UNUSED(USBx);
134 UNUSED(mode);
136 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
137 only by USB OTG FS peripheral.
138 - This function is added to ensure compatibility across platforms.
140 return HAL_OK;
144 * @brief USB_DevInit : Initializes the USB controller registers
145 * for device mode
146 * @param USBx : Selected device
147 * @param cfg : pointer to a USB_CfgTypeDef structure that contains
148 * the configuration information for the specified USBx peripheral.
149 * @retval HAL status
151 HAL_StatusTypeDef USB_DevInit(USB_TypeDef *USBx, USB_CfgTypeDef cfg)
153 /* Prevent unused argument(s) compilation warning */
154 UNUSED(cfg);
156 /* Init Device */
157 /*CNTR_FRES = 1*/
158 USBx->CNTR = USB_CNTR_FRES;
160 /*CNTR_FRES = 0*/
161 USBx->CNTR = 0;
163 /*Clear pending interrupts*/
164 USBx->ISTR = 0;
166 /*Set Btable Address*/
167 USBx->BTABLE = BTABLE_ADDRESS;
169 /* Enable USB Device Interrupt mask */
170 (void)USB_EnableGlobalInt(USBx);
172 return HAL_OK;
176 * @brief USB_SetDevSpeed :Initializes the device speed
177 * depending on the PHY type and the enumeration speed of the device.
178 * @param USBx Selected device
179 * @param speed device speed
180 * @retval Hal status
182 HAL_StatusTypeDef USB_SetDevSpeed(USB_TypeDef *USBx, uint8_t speed)
184 /* Prevent unused argument(s) compilation warning */
185 UNUSED(USBx);
186 UNUSED(speed);
188 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
189 only by USB OTG FS peripheral.
190 - This function is added to ensure compatibility across platforms.
193 return HAL_OK;
197 * @brief USB_FlushTxFifo : Flush a Tx FIFO
198 * @param USBx : Selected device
199 * @param num : FIFO number
200 * This parameter can be a value from 1 to 15
201 15 means Flush all Tx FIFOs
202 * @retval HAL status
204 HAL_StatusTypeDef USB_FlushTxFifo(USB_TypeDef *USBx, uint32_t num)
206 /* Prevent unused argument(s) compilation warning */
207 UNUSED(USBx);
208 UNUSED(num);
210 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
211 only by USB OTG FS peripheral.
212 - This function is added to ensure compatibility across platforms.
215 return HAL_OK;
219 * @brief USB_FlushRxFifo : Flush Rx FIFO
220 * @param USBx : Selected device
221 * @retval HAL status
223 HAL_StatusTypeDef USB_FlushRxFifo(USB_TypeDef *USBx)
225 /* Prevent unused argument(s) compilation warning */
226 UNUSED(USBx);
228 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
229 only by USB OTG FS peripheral.
230 - This function is added to ensure compatibility across platforms.
233 return HAL_OK;
237 * @brief Activate and configure an endpoint
238 * @param USBx : Selected device
239 * @param ep: pointer to endpoint structure
240 * @retval HAL status
242 HAL_StatusTypeDef USB_ActivateEndpoint(USB_TypeDef *USBx, USB_EPTypeDef *ep)
244 HAL_StatusTypeDef ret = HAL_OK;
245 uint16_t wEpRegVal;
247 wEpRegVal = PCD_GET_ENDPOINT(USBx, ep->num) & USB_EP_T_MASK;
249 /* initialize Endpoint */
250 switch (ep->type)
252 case EP_TYPE_CTRL:
253 wEpRegVal |= USB_EP_CONTROL;
254 break;
256 case EP_TYPE_BULK:
257 wEpRegVal |= USB_EP_BULK;
258 break;
260 case EP_TYPE_INTR:
261 wEpRegVal |= USB_EP_INTERRUPT;
262 break;
264 case EP_TYPE_ISOC:
265 wEpRegVal |= USB_EP_ISOCHRONOUS;
266 break;
268 default:
269 ret = HAL_ERROR;
270 break;
273 PCD_SET_ENDPOINT(USBx, ep->num, wEpRegVal | USB_EP_CTR_RX | USB_EP_CTR_TX);
275 PCD_SET_EP_ADDRESS(USBx, ep->num, ep->num);
277 if (ep->doublebuffer == 0U)
279 if (ep->is_in != 0U)
281 /*Set the endpoint Transmit buffer address */
282 PCD_SET_EP_TX_ADDRESS(USBx, ep->num, ep->pmaadress);
283 PCD_CLEAR_TX_DTOG(USBx, ep->num);
285 if (ep->type != EP_TYPE_ISOC)
287 /* Configure NAK status for the Endpoint */
288 PCD_SET_EP_TX_STATUS(USBx, ep->num, USB_EP_TX_NAK);
290 else
292 /* Configure TX Endpoint to disabled state */
293 PCD_SET_EP_TX_STATUS(USBx, ep->num, USB_EP_TX_DIS);
296 else
298 /*Set the endpoint Receive buffer address */
299 PCD_SET_EP_RX_ADDRESS(USBx, ep->num, ep->pmaadress);
300 /*Set the endpoint Receive buffer counter*/
301 PCD_SET_EP_RX_CNT(USBx, ep->num, ep->maxpacket);
302 PCD_CLEAR_RX_DTOG(USBx, ep->num);
303 /* Configure VALID status for the Endpoint*/
304 PCD_SET_EP_RX_STATUS(USBx, ep->num, USB_EP_RX_VALID);
307 /*Double Buffer*/
308 else
310 /* Set the endpoint as double buffered */
311 PCD_SET_EP_DBUF(USBx, ep->num);
312 /* Set buffer address for double buffered mode */
313 PCD_SET_EP_DBUF_ADDR(USBx, ep->num, ep->pmaaddr0, ep->pmaaddr1);
315 if (ep->is_in == 0U)
317 /* Clear the data toggle bits for the endpoint IN/OUT */
318 PCD_CLEAR_RX_DTOG(USBx, ep->num);
319 PCD_CLEAR_TX_DTOG(USBx, ep->num);
321 /* Reset value of the data toggle bits for the endpoint out */
322 PCD_TX_DTOG(USBx, ep->num);
324 PCD_SET_EP_RX_STATUS(USBx, ep->num, USB_EP_RX_VALID);
325 PCD_SET_EP_TX_STATUS(USBx, ep->num, USB_EP_TX_DIS);
327 else
329 /* Clear the data toggle bits for the endpoint IN/OUT */
330 PCD_CLEAR_RX_DTOG(USBx, ep->num);
331 PCD_CLEAR_TX_DTOG(USBx, ep->num);
332 PCD_RX_DTOG(USBx, ep->num);
334 if (ep->type != EP_TYPE_ISOC)
336 /* Configure NAK status for the Endpoint */
337 PCD_SET_EP_TX_STATUS(USBx, ep->num, USB_EP_TX_NAK);
339 else
341 /* Configure TX Endpoint to disabled state */
342 PCD_SET_EP_TX_STATUS(USBx, ep->num, USB_EP_TX_DIS);
345 PCD_SET_EP_RX_STATUS(USBx, ep->num, USB_EP_RX_DIS);
349 return ret;
353 * @brief De-activate and de-initialize an endpoint
354 * @param USBx : Selected device
355 * @param ep: pointer to endpoint structure
356 * @retval HAL status
358 HAL_StatusTypeDef USB_DeactivateEndpoint(USB_TypeDef *USBx, USB_EPTypeDef *ep)
360 if (ep->doublebuffer == 0U)
362 if (ep->is_in != 0U)
364 PCD_CLEAR_TX_DTOG(USBx, ep->num);
365 /* Configure DISABLE status for the Endpoint*/
366 PCD_SET_EP_TX_STATUS(USBx, ep->num, USB_EP_TX_DIS);
368 else
370 PCD_CLEAR_RX_DTOG(USBx, ep->num);
371 /* Configure DISABLE status for the Endpoint*/
372 PCD_SET_EP_RX_STATUS(USBx, ep->num, USB_EP_RX_DIS);
375 /*Double Buffer*/
376 else
378 if (ep->is_in == 0U)
380 /* Clear the data toggle bits for the endpoint IN/OUT*/
381 PCD_CLEAR_RX_DTOG(USBx, ep->num);
382 PCD_CLEAR_TX_DTOG(USBx, ep->num);
384 /* Reset value of the data toggle bits for the endpoint out*/
385 PCD_TX_DTOG(USBx, ep->num);
387 PCD_SET_EP_RX_STATUS(USBx, ep->num, USB_EP_RX_DIS);
388 PCD_SET_EP_TX_STATUS(USBx, ep->num, USB_EP_TX_DIS);
390 else
392 /* Clear the data toggle bits for the endpoint IN/OUT*/
393 PCD_CLEAR_RX_DTOG(USBx, ep->num);
394 PCD_CLEAR_TX_DTOG(USBx, ep->num);
395 PCD_RX_DTOG(USBx, ep->num);
396 /* Configure DISABLE status for the Endpoint*/
397 PCD_SET_EP_TX_STATUS(USBx, ep->num, USB_EP_TX_DIS);
398 PCD_SET_EP_RX_STATUS(USBx, ep->num, USB_EP_RX_DIS);
402 return HAL_OK;
406 * @brief USB_EPStartXfer : setup and starts a transfer over an EP
407 * @param USBx : Selected device
408 * @param ep: pointer to endpoint structure
409 * @retval HAL status
411 HAL_StatusTypeDef USB_EPStartXfer(USB_TypeDef *USBx, USB_EPTypeDef *ep)
413 uint16_t pmabuffer;
414 uint32_t len;
416 /* IN endpoint */
417 if (ep->is_in == 1U)
419 /*Multi packet transfer*/
420 if (ep->xfer_len > ep->maxpacket)
422 len = ep->maxpacket;
423 ep->xfer_len -= len;
425 else
427 len = ep->xfer_len;
428 ep->xfer_len = 0U;
431 /* configure and validate Tx endpoint */
432 if (ep->doublebuffer == 0U)
434 USB_WritePMA(USBx, ep->xfer_buff, ep->pmaadress, (uint16_t)len);
435 PCD_SET_EP_TX_CNT(USBx, ep->num, len);
437 else
439 /* Write the data to the USB endpoint */
440 if ((PCD_GET_ENDPOINT(USBx, ep->num) & USB_EP_DTOG_TX) != 0U)
442 /* Set the Double buffer counter for pmabuffer1 */
443 PCD_SET_EP_DBUF1_CNT(USBx, ep->num, ep->is_in, len);
444 pmabuffer = ep->pmaaddr1;
446 else
448 /* Set the Double buffer counter for pmabuffer0 */
449 PCD_SET_EP_DBUF0_CNT(USBx, ep->num, ep->is_in, len);
450 pmabuffer = ep->pmaaddr0;
452 USB_WritePMA(USBx, ep->xfer_buff, pmabuffer, (uint16_t)len);
453 PCD_FreeUserBuffer(USBx, ep->num, ep->is_in);
456 PCD_SET_EP_TX_STATUS(USBx, ep->num, USB_EP_TX_VALID);
458 else /* OUT endpoint */
460 /* Multi packet transfer*/
461 if (ep->xfer_len > ep->maxpacket)
463 len = ep->maxpacket;
464 ep->xfer_len -= len;
466 else
468 len = ep->xfer_len;
469 ep->xfer_len = 0U;
472 /* configure and validate Rx endpoint */
473 if (ep->doublebuffer == 0U)
475 /*Set RX buffer count*/
476 PCD_SET_EP_RX_CNT(USBx, ep->num, len);
478 else
480 /*Set the Double buffer counter*/
481 PCD_SET_EP_DBUF_CNT(USBx, ep->num, ep->is_in, len);
484 PCD_SET_EP_RX_STATUS(USBx, ep->num, USB_EP_RX_VALID);
487 return HAL_OK;
491 * @brief USB_WritePacket : Writes a packet into the Tx FIFO associated
492 * with the EP/channel
493 * @param USBx : Selected device
494 * @param src : pointer to source buffer
495 * @param ch_ep_num : endpoint or host channel number
496 * @param len : Number of bytes to write
497 * @retval HAL status
499 HAL_StatusTypeDef USB_WritePacket(USB_TypeDef *USBx, uint8_t *src, uint8_t ch_ep_num, uint16_t len)
501 /* Prevent unused argument(s) compilation warning */
502 UNUSED(USBx);
503 UNUSED(src);
504 UNUSED(ch_ep_num);
505 UNUSED(len);
506 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
507 only by USB OTG FS peripheral.
508 - This function is added to ensure compatibility across platforms.
510 return HAL_OK;
514 * @brief USB_ReadPacket : read a packet from the Tx FIFO associated
515 * with the EP/channel
516 * @param USBx : Selected device
517 * @param dest : destination pointer
518 * @param len : Number of bytes to read
519 * @retval pointer to destination buffer
521 void *USB_ReadPacket(USB_TypeDef *USBx, uint8_t *dest, uint16_t len)
523 /* Prevent unused argument(s) compilation warning */
524 UNUSED(USBx);
525 UNUSED(dest);
526 UNUSED(len);
527 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
528 only by USB OTG FS peripheral.
529 - This function is added to ensure compatibility across platforms.
531 return ((void *)NULL);
535 * @brief USB_EPSetStall : set a stall condition over an EP
536 * @param USBx : Selected device
537 * @param ep: pointer to endpoint structure
538 * @retval HAL status
540 HAL_StatusTypeDef USB_EPSetStall(USB_TypeDef *USBx, USB_EPTypeDef *ep)
542 if (ep->is_in != 0U)
544 PCD_SET_EP_TX_STATUS(USBx, ep->num, USB_EP_TX_STALL);
546 else
548 PCD_SET_EP_RX_STATUS(USBx, ep->num, USB_EP_RX_STALL);
551 return HAL_OK;
555 * @brief USB_EPClearStall : Clear a stall condition over an EP
556 * @param USBx : Selected device
557 * @param ep: pointer to endpoint structure
558 * @retval HAL status
560 HAL_StatusTypeDef USB_EPClearStall(USB_TypeDef *USBx, USB_EPTypeDef *ep)
562 if (ep->doublebuffer == 0U)
564 if (ep->is_in != 0U)
566 PCD_CLEAR_TX_DTOG(USBx, ep->num);
568 if (ep->type != EP_TYPE_ISOC)
570 /* Configure NAK status for the Endpoint */
571 PCD_SET_EP_TX_STATUS(USBx, ep->num, USB_EP_TX_NAK);
574 else
576 PCD_CLEAR_RX_DTOG(USBx, ep->num);
578 /* Configure VALID status for the Endpoint*/
579 PCD_SET_EP_RX_STATUS(USBx, ep->num, USB_EP_RX_VALID);
583 return HAL_OK;
587 * @brief USB_StopDevice : Stop the usb device mode
588 * @param USBx : Selected device
589 * @retval HAL status
591 HAL_StatusTypeDef USB_StopDevice(USB_TypeDef *USBx)
593 /* disable all interrupts and force USB reset */
594 USBx->CNTR = USB_CNTR_FRES;
596 /* clear interrupt status register */
597 USBx->ISTR = 0;
599 /* switch-off device */
600 USBx->CNTR = (USB_CNTR_FRES | USB_CNTR_PDWN);
602 return HAL_OK;
606 * @brief USB_SetDevAddress : Stop the usb device mode
607 * @param USBx : Selected device
608 * @param address : new device address to be assigned
609 * This parameter can be a value from 0 to 255
610 * @retval HAL status
612 HAL_StatusTypeDef USB_SetDevAddress(USB_TypeDef *USBx, uint8_t address)
614 if (address == 0U)
616 /* set device address and enable function */
617 USBx->DADDR = USB_DADDR_EF;
620 return HAL_OK;
624 * @brief USB_DevConnect : Connect the USB device by enabling the pull-up/pull-down
625 * @param USBx : Selected device
626 * @retval HAL status
628 HAL_StatusTypeDef USB_DevConnect(USB_TypeDef *USBx)
630 /* Enabling DP Pull-UP bit to Connect internal PU resistor on USB DP line */
631 USBx->BCDR |= USB_BCDR_DPPU;
633 return HAL_OK;
637 * @brief USB_DevDisconnect : Disconnect the USB device by disabling the pull-up/pull-down
638 * @param USBx : Selected device
639 * @retval HAL status
641 HAL_StatusTypeDef USB_DevDisconnect(USB_TypeDef *USBx)
643 /* Disable DP Pull-Up bit to disconnect the Internal PU resistor on USB DP line */
644 USBx->BCDR &= (uint16_t)(~(USB_BCDR_DPPU));
646 return HAL_OK;
650 * @brief USB_ReadInterrupts: return the global USB interrupt status
651 * @param USBx : Selected device
652 * @retval HAL status
654 uint32_t USB_ReadInterrupts(USB_TypeDef *USBx)
656 uint32_t tmpreg;
658 tmpreg = USBx->ISTR;
659 return tmpreg;
663 * @brief USB_ReadDevAllOutEpInterrupt: return the USB device OUT endpoints interrupt status
664 * @param USBx : Selected device
665 * @retval HAL status
667 uint32_t USB_ReadDevAllOutEpInterrupt(USB_TypeDef *USBx)
669 /* Prevent unused argument(s) compilation warning */
670 UNUSED(USBx);
671 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
672 only by USB OTG FS peripheral.
673 - This function is added to ensure compatibility across platforms.
675 return (0);
679 * @brief USB_ReadDevAllInEpInterrupt: return the USB device IN endpoints interrupt status
680 * @param USBx : Selected device
681 * @retval HAL status
683 uint32_t USB_ReadDevAllInEpInterrupt(USB_TypeDef *USBx)
685 /* Prevent unused argument(s) compilation warning */
686 UNUSED(USBx);
687 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
688 only by USB OTG FS peripheral.
689 - This function is added to ensure compatibility across platforms.
691 return (0);
695 * @brief Returns Device OUT EP Interrupt register
696 * @param USBx : Selected device
697 * @param epnum : endpoint number
698 * This parameter can be a value from 0 to 15
699 * @retval Device OUT EP Interrupt register
701 uint32_t USB_ReadDevOutEPInterrupt(USB_TypeDef *USBx, uint8_t epnum)
703 /* Prevent unused argument(s) compilation warning */
704 UNUSED(USBx);
705 UNUSED(epnum);
706 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
707 only by USB OTG FS peripheral.
708 - This function is added to ensure compatibility across platforms.
710 return (0);
714 * @brief Returns Device IN EP Interrupt register
715 * @param USBx : Selected device
716 * @param epnum : endpoint number
717 * This parameter can be a value from 0 to 15
718 * @retval Device IN EP Interrupt register
720 uint32_t USB_ReadDevInEPInterrupt(USB_TypeDef *USBx, uint8_t epnum)
722 /* Prevent unused argument(s) compilation warning */
723 UNUSED(USBx);
724 UNUSED(epnum);
725 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
726 only by USB OTG FS peripheral.
727 - This function is added to ensure compatibility across platforms.
729 return (0);
733 * @brief USB_ClearInterrupts: clear a USB interrupt
734 * @param USBx Selected device
735 * @param interrupt interrupt flag
736 * @retval None
738 void USB_ClearInterrupts(USB_TypeDef *USBx, uint32_t interrupt)
740 /* Prevent unused argument(s) compilation warning */
741 UNUSED(USBx);
742 UNUSED(interrupt);
743 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
744 only by USB OTG FS peripheral.
745 - This function is added to ensure compatibility across platforms.
750 * @brief Prepare the EP0 to start the first control setup
751 * @param USBx Selected device
752 * @param psetup pointer to setup packet
753 * @retval HAL status
755 HAL_StatusTypeDef USB_EP0_OutStart(USB_TypeDef *USBx, uint8_t *psetup)
757 /* Prevent unused argument(s) compilation warning */
758 UNUSED(USBx);
759 UNUSED(psetup);
760 /* NOTE : - This function is not required by USB Device FS peripheral, it is used
761 only by USB OTG FS peripheral.
762 - This function is added to ensure compatibility across platforms.
764 return HAL_OK;
768 * @brief USB_ActivateRemoteWakeup : active remote wakeup signalling
769 * @param USBx Selected device
770 * @retval HAL status
772 HAL_StatusTypeDef USB_ActivateRemoteWakeup(USB_TypeDef *USBx)
774 USBx->CNTR |= USB_CNTR_RESUME;
776 return HAL_OK;
780 * @brief USB_DeActivateRemoteWakeup : de-active remote wakeup signalling
781 * @param USBx Selected device
782 * @retval HAL status
784 HAL_StatusTypeDef USB_DeActivateRemoteWakeup(USB_TypeDef *USBx)
786 USBx->CNTR &= ~(USB_CNTR_RESUME);
787 return HAL_OK;
791 * @brief Copy a buffer from user memory area to packet memory area (PMA)
792 * @param USBx USB peripheral instance register address.
793 * @param pbUsrBuf pointer to user memory area.
794 * @param wPMABufAddr address into PMA.
795 * @param wNBytes: no. of bytes to be copied.
796 * @retval None
798 void USB_WritePMA(USB_TypeDef *USBx, uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes)
800 uint32_t n = ((uint32_t)wNBytes + 1U) >> 1;
801 uint32_t BaseAddr = (uint32_t)USBx;
802 uint32_t i, temp1, temp2;
803 uint16_t *pdwVal;
804 uint8_t *pBuf = pbUsrBuf;
806 pdwVal = (uint16_t *)(BaseAddr + 0x400U + ((uint32_t)wPMABufAddr * PMA_ACCESS));
808 for (i = n; i != 0U; i--)
810 temp1 = (uint16_t) * pBuf;
811 pBuf++;
812 temp2 = temp1 | ((uint16_t)((uint16_t) * pBuf << 8));
813 *pdwVal = (uint16_t)temp2;
814 pdwVal++;
816 #if PMA_ACCESS > 1U
817 pdwVal++;
818 #endif
820 pBuf++;
825 * @brief Copy a buffer from user memory area to packet memory area (PMA)
826 * @param USBx: USB peripheral instance register address.
827 * @param pbUsrBuf pointer to user memory area.
828 * @param wPMABufAddr address into PMA.
829 * @param wNBytes: no. of bytes to be copied.
830 * @retval None
832 void USB_ReadPMA(USB_TypeDef *USBx, uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes)
834 uint32_t n = (uint32_t)wNBytes >> 1;
835 uint32_t BaseAddr = (uint32_t)USBx;
836 uint32_t i, temp;
837 uint16_t *pdwVal;
838 uint8_t *pBuf = pbUsrBuf;
840 pdwVal = (uint16_t *)(BaseAddr + 0x400U + ((uint32_t)wPMABufAddr * PMA_ACCESS));
842 for (i = n; i != 0U; i--)
844 temp = *pdwVal;
845 pdwVal++;
846 *pBuf = (uint8_t)((temp >> 0) & 0xFFU);
847 pBuf++;
848 *pBuf = (uint8_t)((temp >> 8) & 0xFFU);
849 pBuf++;
851 #if PMA_ACCESS > 1U
852 pdwVal++;
853 #endif
856 if ((wNBytes % 2U) != 0U)
858 temp = *pdwVal;
859 *pBuf = (uint8_t)((temp >> 0) & 0xFFU);
865 * @}
869 * @}
871 #endif /* defined (USB) */
872 #endif /* defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED) */
875 * @}
878 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/