2 * usbd_conf.c adopted from
3 * STM32Cube_FW_H7_V1.3.0/Projects/STM32H743I_EVAL/Applications/USB_Device/CDC_Standalone
7 ******************************************************************************
8 * @file USB_Device/CDC_Standalone/Src/usbd_conf.c
9 * @author MCD Application Team
10 * @brief This file implements the USB Device library callbacks and MSP
11 ******************************************************************************
14 * <h2><center>© Copyright (c) 2017 STMicroelectronics International N.V.
15 * All rights reserved.</center></h2>
17 * Redistribution and use in source and binary forms, with or without
18 * modification, are permitted, provided that the following conditions are met:
20 * 1. Redistribution of source code must retain the above copyright notice,
21 * this list of conditions and the following disclaimer.
22 * 2. Redistributions in binary form must reproduce the above copyright notice,
23 * this list of conditions and the following disclaimer in the documentation
24 * and/or other materials provided with the distribution.
25 * 3. Neither the name of STMicroelectronics nor the names of other
26 * contributors to this software may be used to endorse or promote products
27 * derived from this software without specific written permission.
28 * 4. This software, including modifications and/or derivative works of this
29 * software, must execute solely and exclusively on microcontroller or
30 * microprocessor devices manufactured by or for STMicroelectronics.
31 * 5. Redistribution and use of this software other than as permitted under
32 * this license is void and will automatically terminate your rights under
35 * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
36 * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
37 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
38 * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
39 * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
40 * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
41 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
42 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
43 * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
44 * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
45 * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
46 * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
48 ******************************************************************************
51 /* Includes ------------------------------------------------------------------ */
52 #include "stm32h7xx_hal.h"
53 #include "usbd_conf.h"
54 #include "usbd_core.h"
55 #include "usbd_desc.h"
57 #include "usbd_cdc_interface.h"
64 #include "drivers/usb_msc.h"
67 /* Private typedef ----------------------------------------------------------- */
68 /* Private define ------------------------------------------------------------ */
69 /* Private macro ------------------------------------------------------------- */
70 /* Private variables --------------------------------------------------------- */
71 PCD_HandleTypeDef hpcd
;
72 /* Private function prototypes ----------------------------------------------- */
73 /* Private functions --------------------------------------------------------- */
75 /*******************************************************************************
77 *******************************************************************************/
79 #if defined(USE_USB_FS) && !(defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx))
80 void OTG_FS_IRQHandler(void)
82 void OTG_HS_IRQHandler(void)
85 HAL_PCD_IRQHandler(&hpcd
);
89 * @brief Initializes the PCD MSP.
90 * @param hpcd: PCD handle
93 void HAL_PCD_MspInit(PCD_HandleTypeDef
* hpcd
)
95 GPIO_InitTypeDef GPIO_InitStruct
= {0};
97 #if defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
99 // H7A3 uses USB1_OTG_HS in FS mode
103 __HAL_RCC_GPIOA_CLK_ENABLE();
105 /**USB GPIO Configuration
109 GPIO_InitStruct
.Pin
= GPIO_PIN_11
|GPIO_PIN_12
;
110 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
111 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
112 GPIO_InitStruct
.Speed
= GPIO_SPEED_FREQ_VERY_HIGH
;
113 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG1_HS
;
114 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
116 /* Peripheral clock enable */
117 __HAL_RCC_USB1_OTG_HS_CLK_ENABLE();
119 /* Set USB HS Interrupt priority */
120 HAL_NVIC_SetPriority(OTG_HS_IRQn
, 6, 0);
122 /* Enable USB HS Interrupt */
123 HAL_NVIC_EnableIRQ(OTG_HS_IRQn
);
125 #elif defined(STM32H743xx) || defined(STM32H750xx)
127 if (hpcd
->Instance
== USB_OTG_FS
)
129 __HAL_RCC_GPIOA_CLK_ENABLE();
131 /* Configure DM DP Pins */
132 GPIO_InitStruct
.Pin
= (GPIO_PIN_11
| GPIO_PIN_12
);
133 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
134 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
135 GPIO_InitStruct
.Speed
= GPIO_SPEED_FREQ_VERY_HIGH
;
136 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG1_FS
;
137 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
139 if (hpcd
->Init
.vbus_sensing_enable
== 1) {
140 /* Configure VBUS Pin */
141 GPIO_InitStruct
.Pin
= GPIO_PIN_9
;
142 GPIO_InitStruct
.Mode
= GPIO_MODE_INPUT
;
143 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
144 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
148 /* Configure ID pin */
149 GPIO_InitStruct
.Pin
= GPIO_PIN_10
;
150 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_OD
;
151 GPIO_InitStruct
.Pull
= GPIO_PULLUP
;
152 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG1_FS
;
153 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
156 /* Enable USB FS Clocks */
157 __HAL_RCC_USB2_OTG_FS_CLK_ENABLE();
159 /* XXX Todo: Configure and enable CRS for HSI48 */
161 /* Set USBFS Interrupt to the lowest priority */
162 HAL_NVIC_SetPriority(OTG_FS_IRQn
, 6, 0);
164 /* Enable USBFS Interrupt */
165 HAL_NVIC_EnableIRQ(OTG_FS_IRQn
);
168 else if (hpcd
->Instance
== USB1_OTG_HS
)
170 /* Configure USB FS GPIOs */
171 __GPIOA_CLK_ENABLE();
172 __GPIOB_CLK_ENABLE();
173 __GPIOC_CLK_ENABLE();
174 __GPIOH_CLK_ENABLE();
175 __GPIOI_CLK_ENABLE();
178 GPIO_InitStruct
.Pin
= GPIO_PIN_5
;
179 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
180 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
181 GPIO_InitStruct
.Speed
= GPIO_SPEED_FREQ_VERY_HIGH
;
182 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG2_HS
;
183 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
186 GPIO_InitStruct
.Pin
= GPIO_PIN_3
;
187 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
188 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
189 GPIO_InitStruct
.Speed
= GPIO_SPEED_FREQ_VERY_HIGH
;
190 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG2_HS
;
191 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
193 /* D1 D2 D3 D4 D5 D6 D7 */
194 GPIO_InitStruct
.Pin
= GPIO_PIN_0
| GPIO_PIN_1
| GPIO_PIN_5
|
195 GPIO_PIN_10
| GPIO_PIN_11
| GPIO_PIN_12
| GPIO_PIN_13
;
196 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
197 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
198 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG2_HS
;
199 HAL_GPIO_Init(GPIOB
, &GPIO_InitStruct
);
202 GPIO_InitStruct
.Pin
= GPIO_PIN_0
;
203 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
204 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
205 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG2_HS
;
206 HAL_GPIO_Init(GPIOC
, &GPIO_InitStruct
);
209 GPIO_InitStruct
.Pin
= GPIO_PIN_4
;
210 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
211 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
212 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG2_HS
;
213 HAL_GPIO_Init(GPIOH
, &GPIO_InitStruct
);
216 GPIO_InitStruct
.Pin
= GPIO_PIN_11
;
217 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
218 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
219 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG2_HS
;
220 HAL_GPIO_Init(GPIOI
, &GPIO_InitStruct
);
221 __HAL_RCC_USB1_OTG_HS_ULPI_CLK_ENABLE();
223 /* Enable USB HS Clocks */
224 __HAL_RCC_USB1_OTG_HS_CLK_ENABLE();
226 /* Set USBHS Interrupt to the lowest priority */
227 HAL_NVIC_SetPriority(OTG_HS_IRQn
, 1, 0);
229 /* Enable USBHS Interrupt */
230 HAL_NVIC_EnableIRQ(OTG_HS_IRQn
);
233 #elif defined(STM32H723xx) || defined(STM32H725xx)
236 __HAL_RCC_GPIOA_CLK_ENABLE();
238 /**USB GPIO Configuration
242 GPIO_InitStruct
.Pin
= GPIO_PIN_11
|GPIO_PIN_12
;
243 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
244 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
245 GPIO_InitStruct
.Speed
= GPIO_SPEED_FREQ_VERY_HIGH
;
246 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG1_FS
;
247 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
249 /* Peripheral clock enable */
250 __HAL_RCC_USB1_OTG_HS_CLK_ENABLE();
252 /* Set USB FS Interrupt priority */
253 HAL_NVIC_SetPriority(OTG_HS_IRQn
, 6, 0);
255 /* Enable USB FS Interrupt */
256 HAL_NVIC_EnableIRQ(OTG_HS_IRQn
);
257 #elif defined(STM32H730xx)
260 __HAL_RCC_GPIOA_CLK_ENABLE();
262 /**USB GPIO Configuration
266 GPIO_InitStruct
.Pin
= GPIO_PIN_11
|GPIO_PIN_12
;
267 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
268 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
269 GPIO_InitStruct
.Speed
= GPIO_SPEED_FREQ_VERY_HIGH
;
270 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG1_HS
;
271 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
273 /* Enable USB HS Clocks */
274 __HAL_RCC_USB1_OTG_HS_CLK_ENABLE();
276 HAL_NVIC_SetPriority(OTG_HS_EP1_OUT_IRQn
, 6, 0);
277 HAL_NVIC_EnableIRQ(OTG_HS_EP1_OUT_IRQn
);
279 HAL_NVIC_SetPriority(OTG_HS_EP1_IN_IRQn
, 6, 0);
280 HAL_NVIC_EnableIRQ(OTG_HS_EP1_IN_IRQn
);
282 HAL_NVIC_SetPriority(OTG_HS_IRQn
, 7, 0);
283 HAL_NVIC_EnableIRQ(OTG_HS_IRQn
);
286 #error Unknown MCU type
291 * @brief De-Initializes the PCD MSP.
292 * @param hpcd: PCD handle
295 void HAL_PCD_MspDeInit(PCD_HandleTypeDef
* hpcd
)
297 #if defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
298 if(hpcd
->Instance
==USB1_OTG_HS
) {
300 __HAL_RCC_USB1_OTG_HS_CLK_DISABLE();
302 HAL_GPIO_DeInit(GPIOA
, GPIO_PIN_11
|GPIO_PIN_12
);
304 HAL_NVIC_DisableIRQ(OTG_HS_IRQn
);
306 __HAL_RCC_GPIOA_CLK_DISABLE();
308 #elif defined(STM32H743xx) || defined(STM32H750xx)
309 if (hpcd
->Instance
== USB2_OTG_FS
)
311 /* Disable USB FS Clocks */
312 __HAL_RCC_USB2_OTG_FS_CLK_DISABLE();
314 else if (hpcd
->Instance
== USB1_OTG_HS
)
316 /* Disable USB HS Clocks */
317 __HAL_RCC_USB1_OTG_HS_CLK_DISABLE();
318 __HAL_RCC_USB1_OTG_HS_ULPI_CLK_DISABLE();
320 #elif defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
321 if(hpcd
->Instance
==USB1_OTG_HS
)
323 /* Peripheral clock disable */
324 __HAL_RCC_USB1_OTG_HS_CLK_DISABLE();
326 /**USB GPIO Configuration
330 HAL_GPIO_DeInit(GPIOA
, GPIO_PIN_11
|GPIO_PIN_12
);
332 /* Peripheral interrupt Deinit*/
333 HAL_NVIC_DisableIRQ(OTG_HS_IRQn
);
340 /*******************************************************************************
341 LL Driver Callbacks (PCD -> USB Device Library)
342 *******************************************************************************/
345 * @brief SetupStage callback.
346 * @param hpcd: PCD handle
349 void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef
* hpcd
)
351 USBD_LL_SetupStage(hpcd
->pData
, (uint8_t *) hpcd
->Setup
);
355 * @brief DataOut Stage callback.
356 * @param hpcd: PCD handle
357 * @param epnum: Endpoint Number
360 void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef
* hpcd
, uint8_t epnum
)
362 USBD_LL_DataOutStage(hpcd
->pData
, epnum
, hpcd
->OUT_ep
[epnum
].xfer_buff
);
366 * @brief DataIn Stage callback.
367 * @param hpcd: PCD handle
368 * @param epnum: Endpoint Number
371 void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef
* hpcd
, uint8_t epnum
)
373 USBD_LL_DataInStage(hpcd
->pData
, epnum
, hpcd
->IN_ep
[epnum
].xfer_buff
);
377 * @brief SOF callback.
378 * @param hpcd: PCD handle
381 void HAL_PCD_SOFCallback(PCD_HandleTypeDef
* hpcd
)
383 USBD_LL_SOF(hpcd
->pData
);
387 * @brief Reset callback.
388 * @param hpcd: PCD handle
391 void HAL_PCD_ResetCallback(PCD_HandleTypeDef
* hpcd
)
393 USBD_SpeedTypeDef speed
= USBD_SPEED_FULL
;
395 /* Set USB Current Speed */
396 switch (hpcd
->Init
.speed
)
399 speed
= USBD_SPEED_HIGH
;
403 speed
= USBD_SPEED_FULL
;
407 speed
= USBD_SPEED_FULL
;
412 USBD_LL_Reset(hpcd
->pData
);
414 USBD_LL_SetSpeed(hpcd
->pData
, speed
);
418 * @brief Suspend callback.
419 * @param hpcd: PCD handle
422 void HAL_PCD_SuspendCallback(PCD_HandleTypeDef
* hpcd
)
424 USBD_LL_Suspend(hpcd
->pData
);
428 * @brief Resume callback.
429 * @param hpcd: PCD handle
432 void HAL_PCD_ResumeCallback(PCD_HandleTypeDef
* hpcd
)
434 USBD_LL_Resume(hpcd
->pData
);
438 * @brief ISOOUTIncomplete callback.
439 * @param hpcd: PCD handle
440 * @param epnum: Endpoint Number
443 void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef
* hpcd
, uint8_t epnum
)
445 USBD_LL_IsoOUTIncomplete(hpcd
->pData
, epnum
);
449 * @brief ISOINIncomplete callback.
450 * @param hpcd: PCD handle
451 * @param epnum: Endpoint Number
454 void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef
* hpcd
, uint8_t epnum
)
456 USBD_LL_IsoINIncomplete(hpcd
->pData
, epnum
);
460 * @brief ConnectCallback callback.
461 * @param hpcd: PCD handle
464 void HAL_PCD_ConnectCallback(PCD_HandleTypeDef
* hpcd
)
466 USBD_LL_DevConnected(hpcd
->pData
);
470 * @brief Disconnect callback.
471 * @param hpcd: PCD handle
474 void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef
* hpcd
)
476 USBD_LL_DevDisconnected(hpcd
->pData
);
480 /*******************************************************************************
481 LL Driver Interface (USB Device Library --> PCD)
482 *******************************************************************************/
485 * @brief Initializes the Low Level portion of the Device driver.
486 * @param pdev: Device handle
487 * @retval USBD Status
489 USBD_StatusTypeDef
USBD_LL_Init(USBD_HandleTypeDef
* pdev
)
492 /* Set LL Driver parameters */
493 #if defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
494 hpcd
.Instance
= USB1_OTG_HS
;
495 #elif defined(STM32H743xx) || defined(STM32H750xx)
496 hpcd
.Instance
= USB2_OTG_FS
;
498 #error Unknown MCU type
500 hpcd
.Init
.dev_endpoints
= 9;
501 hpcd
.Init
.use_dedicated_ep1
= DISABLE
;
502 hpcd
.Init
.ep0_mps
= DEP0CTL_MPS_64
;
503 hpcd
.Init
.low_power_enable
= DISABLE
;
504 hpcd
.Init
.phy_itface
= PCD_PHY_EMBEDDED
;
505 hpcd
.Init
.Sof_enable
= DISABLE
;
506 hpcd
.Init
.battery_charging_enable
= DISABLE
;
507 hpcd
.Init
.speed
= PCD_SPEED_FULL
;
508 hpcd
.Init
.vbus_sensing_enable
= DISABLE
;
509 hpcd
.Init
.dma_enable
= DISABLE
;
510 hpcd
.Init
.lpm_enable
= DISABLE
;
512 /* Link The driver to the stack */
516 hpcd
.Init
.vbus_sensing_enable
= 0;
518 /* Initialize LL Driver */
521 #ifdef USE_USB_CDC_HID
523 if (usbDevConfig()->type
== COMPOSITE
&& !mscCheckBootAndReset()) {
525 if (usbDevConfig()->type
== COMPOSITE
) {
527 HAL_PCDEx_SetRxFiFo(&hpcd
, 0x80);
528 HAL_PCDEx_SetTxFiFo(&hpcd
, 0, 0x20);
529 HAL_PCDEx_SetTxFiFo(&hpcd
, 1, 0x40);
530 HAL_PCDEx_SetTxFiFo(&hpcd
, 2, 0x20);
531 HAL_PCDEx_SetTxFiFo(&hpcd
, 3, 0x40);
534 HAL_PCDEx_SetRxFiFo(&hpcd
, 0x80);
535 HAL_PCDEx_SetTxFiFo(&hpcd
, 0, 0x40);
536 HAL_PCDEx_SetTxFiFo(&hpcd
, 1, 0x80);
537 #ifdef USE_USB_CDC_HID
544 /* Set LL Driver parameters */
545 hpcd
.Instance
= USB1_OTG_HS
;
546 hpcd
.Init
.dev_endpoints
= 8;
547 hpcd
.Init
.use_dedicated_ep1
= 0;
548 hpcd
.Init
.ep0_mps
= 0x40;
550 /* Be aware that enabling DMA mode will result in data being sent only by
551 * multiple of 4 packet sizes. This is due to the fact that USB DMA does not
552 * allow sending data from non word-aligned addresses. For this specific
553 * application, it is advised to not enable this option unless required. */
554 hpcd
.Init
.dma_enable
= 0;
555 hpcd
.Init
.low_power_enable
= 0;
556 hpcd
.Init
.lpm_enable
= 0;
557 hpcd
.Init
.phy_itface
= PCD_PHY_ULPI
;
558 hpcd
.Init
.Sof_enable
= 0;
559 hpcd
.Init
.speed
= PCD_SPEED_HIGH
;
560 hpcd
.Init
.vbus_sensing_enable
= 0;
562 /* Link The driver to the stack */
566 /* Initialize LL Driver */
569 HAL_PCDEx_SetRxFiFo(&hpcd
, 0x200);
570 HAL_PCDEx_SetTxFiFo(&hpcd
, 0, 0x80);
571 HAL_PCDEx_SetTxFiFo(&hpcd
, 1, 0x174);
578 * @brief De-Initializes the Low Level portion of the Device driver.
579 * @param pdev: Device handle
580 * @retval USBD Status
582 USBD_StatusTypeDef
USBD_LL_DeInit(USBD_HandleTypeDef
* pdev
)
584 HAL_PCD_DeInit(pdev
->pData
);
589 * @brief Starts the Low Level portion of the Device driver.
590 * @param pdev: Device handle
591 * @retval USBD Status
593 USBD_StatusTypeDef
USBD_LL_Start(USBD_HandleTypeDef
* pdev
)
595 HAL_PCD_Start(pdev
->pData
);
600 * @brief Stops the Low Level portion of the Device driver.
601 * @param pdev: Device handle
602 * @retval USBD Status
604 USBD_StatusTypeDef
USBD_LL_Stop(USBD_HandleTypeDef
* pdev
)
606 HAL_PCD_Stop(pdev
->pData
);
611 * @brief Opens an endpoint of the Low Level Driver.
612 * @param pdev: Device handle
613 * @param ep_addr: Endpoint Number
614 * @param ep_type: Endpoint Type
615 * @param ep_mps: Endpoint Max Packet Size
616 * @retval USBD Status
618 USBD_StatusTypeDef
USBD_LL_OpenEP(USBD_HandleTypeDef
* pdev
,
620 uint8_t ep_type
, uint16_t ep_mps
)
622 HAL_PCD_EP_Open(pdev
->pData
, ep_addr
, ep_mps
, ep_type
);
628 * @brief Closes an endpoint of the Low Level Driver.
629 * @param pdev: Device handle
630 * @param ep_addr: Endpoint Number
631 * @retval USBD Status
633 USBD_StatusTypeDef
USBD_LL_CloseEP(USBD_HandleTypeDef
* pdev
, uint8_t ep_addr
)
635 HAL_PCD_EP_Close(pdev
->pData
, ep_addr
);
640 * @brief Flushes an endpoint of the Low Level Driver.
641 * @param pdev: Device handle
642 * @param ep_addr: Endpoint Number
643 * @retval USBD Status
645 USBD_StatusTypeDef
USBD_LL_FlushEP(USBD_HandleTypeDef
* pdev
, uint8_t ep_addr
)
647 HAL_PCD_EP_Flush(pdev
->pData
, ep_addr
);
652 * @brief Sets a Stall condition on an endpoint of the Low Level Driver.
653 * @param pdev: Device handle
654 * @param ep_addr: Endpoint Number
655 * @retval USBD Status
657 USBD_StatusTypeDef
USBD_LL_StallEP(USBD_HandleTypeDef
* pdev
, uint8_t ep_addr
)
659 HAL_PCD_EP_SetStall(pdev
->pData
, ep_addr
);
664 * @brief Clears a Stall condition on an endpoint of the Low Level Driver.
665 * @param pdev: Device handle
666 * @param ep_addr: Endpoint Number
667 * @retval USBD Status
669 USBD_StatusTypeDef
USBD_LL_ClearStallEP(USBD_HandleTypeDef
* pdev
,
672 HAL_PCD_EP_ClrStall(pdev
->pData
, ep_addr
);
677 * @brief Returns Stall condition.
678 * @param pdev: Device handle
679 * @param ep_addr: Endpoint Number
680 * @retval Stall (1: Yes, 0: No)
682 uint8_t USBD_LL_IsStallEP(USBD_HandleTypeDef
* pdev
, uint8_t ep_addr
)
684 PCD_HandleTypeDef
*hpcd
= pdev
->pData
;
686 if ((ep_addr
& 0x80) == 0x80)
688 return hpcd
->IN_ep
[ep_addr
& 0x7F].is_stall
;
692 return hpcd
->OUT_ep
[ep_addr
& 0x7F].is_stall
;
697 * @brief Assigns a USB address to the device.
698 * @param pdev: Device handle
699 * @param ep_addr: Endpoint Number
700 * @retval USBD Status
702 USBD_StatusTypeDef
USBD_LL_SetUSBAddress(USBD_HandleTypeDef
* pdev
,
705 HAL_PCD_SetAddress(pdev
->pData
, dev_addr
);
710 * @brief Transmits data over an endpoint.
711 * @param pdev: Device handle
712 * @param ep_addr: Endpoint Number
713 * @param pbuf: Pointer to data to be sent
714 * @param size: Data size
715 * @retval USBD Status
717 USBD_StatusTypeDef
USBD_LL_Transmit(USBD_HandleTypeDef
* pdev
,
719 uint8_t * pbuf
, uint32_t size
)
721 /* Get the packet total length */
722 pdev
->ep_in
[ep_addr
& 0x7F].total_length
= size
;
724 HAL_PCD_EP_Transmit(pdev
->pData
, ep_addr
, pbuf
, size
);
729 * @brief Prepares an endpoint for reception.
730 * @param pdev: Device handle
731 * @param ep_addr: Endpoint Number
732 * @param pbuf: Pointer to data to be received
733 * @param size: Data size
734 * @retval USBD Status
736 USBD_StatusTypeDef
USBD_LL_PrepareReceive(USBD_HandleTypeDef
* pdev
,
738 uint8_t * pbuf
, uint32_t size
)
740 HAL_PCD_EP_Receive(pdev
->pData
, ep_addr
, pbuf
, size
);
745 * @brief Returns the last transferred packet size.
746 * @param pdev: Device handle
747 * @param ep_addr: Endpoint Number
748 * @retval Received Data Size
750 uint32_t USBD_LL_GetRxDataSize(USBD_HandleTypeDef
* pdev
, uint8_t ep_addr
)
752 return HAL_PCD_EP_GetRxCount(pdev
->pData
, ep_addr
);
756 * @brief Delays routine for the USB Device Library.
757 * @param Delay: Delay in ms
760 void USBD_LL_Delay(uint32_t Delay
)
765 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/