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
15 ==============================================================================
16 ##### How to use this driver #####
17 ==============================================================================
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.
26 ******************************************************************************
29 * <h2><center>© 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
47 #if defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED)
49 /* Private typedef -----------------------------------------------------------*/
50 /* Private define ------------------------------------------------------------*/
51 /* Private macro -------------------------------------------------------------*/
52 /* Private variables ---------------------------------------------------------*/
53 /* Private function prototypes -----------------------------------------------*/
54 /* Private functions ---------------------------------------------------------*/
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.
64 HAL_StatusTypeDef
USB_CoreInit(USB_TypeDef
*USBx
, USB_CfgTypeDef cfg
)
66 /* Prevent unused argument(s) compilation warning */
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.
79 * @brief USB_EnableGlobalInt
80 * Enables the controller's Global Int in the AHB Config reg
81 * @param USBx : Selected device
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
;
101 * @brief USB_DisableGlobalInt
102 * Disable the controller's Global Int in the AHB Config reg
103 * @param USBx : Selected device
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
;
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
130 HAL_StatusTypeDef
USB_SetCurrentMode(USB_TypeDef
*USBx
, USB_ModeTypeDef mode
)
132 /* Prevent unused argument(s) compilation warning */
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.
144 * @brief USB_DevInit : Initializes the USB controller registers
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.
151 HAL_StatusTypeDef
USB_DevInit(USB_TypeDef
*USBx
, USB_CfgTypeDef cfg
)
153 /* Prevent unused argument(s) compilation warning */
158 USBx
->CNTR
= USB_CNTR_FRES
;
163 /*Clear pending interrupts*/
166 /*Set Btable Address*/
167 USBx
->BTABLE
= BTABLE_ADDRESS
;
169 /* Enable USB Device Interrupt mask */
170 (void)USB_EnableGlobalInt(USBx
);
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
182 HAL_StatusTypeDef
USB_SetDevSpeed(USB_TypeDef
*USBx
, uint8_t speed
)
184 /* Prevent unused argument(s) compilation warning */
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.
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
204 HAL_StatusTypeDef
USB_FlushTxFifo(USB_TypeDef
*USBx
, uint32_t num
)
206 /* Prevent unused argument(s) compilation warning */
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.
219 * @brief USB_FlushRxFifo : Flush Rx FIFO
220 * @param USBx : Selected device
223 HAL_StatusTypeDef
USB_FlushRxFifo(USB_TypeDef
*USBx
)
225 /* Prevent unused argument(s) compilation warning */
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.
237 * @brief Activate and configure an endpoint
238 * @param USBx : Selected device
239 * @param ep: pointer to endpoint structure
242 HAL_StatusTypeDef
USB_ActivateEndpoint(USB_TypeDef
*USBx
, USB_EPTypeDef
*ep
)
244 HAL_StatusTypeDef ret
= HAL_OK
;
247 wEpRegVal
= PCD_GET_ENDPOINT(USBx
, ep
->num
) & USB_EP_T_MASK
;
249 /* initialize Endpoint */
253 wEpRegVal
|= USB_EP_CONTROL
;
257 wEpRegVal
|= USB_EP_BULK
;
261 wEpRegVal
|= USB_EP_INTERRUPT
;
265 wEpRegVal
|= USB_EP_ISOCHRONOUS
;
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)
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
);
292 /* Configure TX Endpoint to disabled state */
293 PCD_SET_EP_TX_STATUS(USBx
, ep
->num
, USB_EP_TX_DIS
);
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
);
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
);
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
);
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
);
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
);
353 * @brief De-activate and de-initialize an endpoint
354 * @param USBx : Selected device
355 * @param ep: pointer to endpoint structure
358 HAL_StatusTypeDef
USB_DeactivateEndpoint(USB_TypeDef
*USBx
, USB_EPTypeDef
*ep
)
360 if (ep
->doublebuffer
== 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
);
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
);
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
);
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
);
406 * @brief USB_EPStartXfer : setup and starts a transfer over an EP
407 * @param USBx : Selected device
408 * @param ep: pointer to endpoint structure
411 HAL_StatusTypeDef
USB_EPStartXfer(USB_TypeDef
*USBx
, USB_EPTypeDef
*ep
)
419 /*Multi packet transfer*/
420 if (ep
->xfer_len
> ep
->maxpacket
)
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
);
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
;
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
)
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
);
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
);
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
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 */
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.
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 */
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
540 HAL_StatusTypeDef
USB_EPSetStall(USB_TypeDef
*USBx
, USB_EPTypeDef
*ep
)
544 PCD_SET_EP_TX_STATUS(USBx
, ep
->num
, USB_EP_TX_STALL
);
548 PCD_SET_EP_RX_STATUS(USBx
, ep
->num
, USB_EP_RX_STALL
);
555 * @brief USB_EPClearStall : Clear a stall condition over an EP
556 * @param USBx : Selected device
557 * @param ep: pointer to endpoint structure
560 HAL_StatusTypeDef
USB_EPClearStall(USB_TypeDef
*USBx
, USB_EPTypeDef
*ep
)
562 if (ep
->doublebuffer
== 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
);
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
);
587 * @brief USB_StopDevice : Stop the usb device mode
588 * @param USBx : Selected device
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 */
599 /* switch-off device */
600 USBx
->CNTR
= (USB_CNTR_FRES
| USB_CNTR_PDWN
);
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
612 HAL_StatusTypeDef
USB_SetDevAddress(USB_TypeDef
*USBx
, uint8_t address
)
616 /* set device address and enable function */
617 USBx
->DADDR
= USB_DADDR_EF
;
624 * @brief USB_DevConnect : Connect the USB device by enabling the pull-up/pull-down
625 * @param USBx : Selected device
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
;
637 * @brief USB_DevDisconnect : Disconnect the USB device by disabling the pull-up/pull-down
638 * @param USBx : Selected device
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
));
650 * @brief USB_ReadInterrupts: return the global USB interrupt status
651 * @param USBx : Selected device
654 uint32_t USB_ReadInterrupts(USB_TypeDef
*USBx
)
663 * @brief USB_ReadDevAllOutEpInterrupt: return the USB device OUT endpoints interrupt status
664 * @param USBx : Selected device
667 uint32_t USB_ReadDevAllOutEpInterrupt(USB_TypeDef
*USBx
)
669 /* Prevent unused argument(s) compilation warning */
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.
679 * @brief USB_ReadDevAllInEpInterrupt: return the USB device IN endpoints interrupt status
680 * @param USBx : Selected device
683 uint32_t USB_ReadDevAllInEpInterrupt(USB_TypeDef
*USBx
)
685 /* Prevent unused argument(s) compilation warning */
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.
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 */
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.
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 */
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.
733 * @brief USB_ClearInterrupts: clear a USB interrupt
734 * @param USBx Selected device
735 * @param interrupt interrupt flag
738 void USB_ClearInterrupts(USB_TypeDef
*USBx
, uint32_t interrupt
)
740 /* Prevent unused argument(s) compilation warning */
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
755 HAL_StatusTypeDef
USB_EP0_OutStart(USB_TypeDef
*USBx
, uint8_t *psetup
)
757 /* Prevent unused argument(s) compilation warning */
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.
768 * @brief USB_ActivateRemoteWakeup : active remote wakeup signalling
769 * @param USBx Selected device
772 HAL_StatusTypeDef
USB_ActivateRemoteWakeup(USB_TypeDef
*USBx
)
774 USBx
->CNTR
|= USB_CNTR_RESUME
;
780 * @brief USB_DeActivateRemoteWakeup : de-active remote wakeup signalling
781 * @param USBx Selected device
784 HAL_StatusTypeDef
USB_DeActivateRemoteWakeup(USB_TypeDef
*USBx
)
786 USBx
->CNTR
&= ~(USB_CNTR_RESUME
);
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.
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
;
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
;
812 temp2
= temp1
| ((uint16_t)((uint16_t) * pBuf
<< 8));
813 *pdwVal
= (uint16_t)temp2
;
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.
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
;
838 uint8_t *pBuf
= pbUsrBuf
;
840 pdwVal
= (uint16_t *)(BaseAddr
+ 0x400U
+ ((uint32_t)wPMABufAddr
* PMA_ACCESS
));
842 for (i
= n
; i
!= 0U; i
--)
846 *pBuf
= (uint8_t)((temp
>> 0) & 0xFFU
);
848 *pBuf
= (uint8_t)((temp
>> 8) & 0xFFU
);
856 if ((wNBytes
% 2U) != 0U)
859 *pBuf
= (uint8_t)((temp
>> 0) & 0xFFU
);
871 #endif /* defined (USB) */
872 #endif /* defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED) */
878 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/