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"
62 #include "drivers/usb_msc.h"
65 /* Private typedef ----------------------------------------------------------- */
66 /* Private define ------------------------------------------------------------ */
67 /* Private macro ------------------------------------------------------------- */
68 /* Private variables --------------------------------------------------------- */
69 PCD_HandleTypeDef hpcd
;
70 /* Private function prototypes ----------------------------------------------- */
71 /* Private functions --------------------------------------------------------- */
73 /*******************************************************************************
75 *******************************************************************************/
78 void OTG_FS_IRQHandler(void)
80 void OTG_HS_IRQHandler(void)
83 HAL_PCD_IRQHandler(&hpcd
);
87 * @brief Initializes the PCD MSP.
88 * @param hpcd: PCD handle
91 void HAL_PCD_MspInit(PCD_HandleTypeDef
* hpcd
)
93 GPIO_InitTypeDef GPIO_InitStruct
;
95 if (hpcd
->Instance
== USB_OTG_FS
)
97 __HAL_RCC_GPIOA_CLK_ENABLE();
99 /* Configure DM DP Pins */
100 GPIO_InitStruct
.Pin
= (GPIO_PIN_11
| GPIO_PIN_12
);
101 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
102 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
103 GPIO_InitStruct
.Speed
= GPIO_SPEED_FREQ_VERY_HIGH
;
104 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG1_FS
;
105 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
107 if (hpcd
->Init
.vbus_sensing_enable
== 1) {
108 /* Configure VBUS Pin */
109 GPIO_InitStruct
.Pin
= GPIO_PIN_9
;
110 GPIO_InitStruct
.Mode
= GPIO_MODE_INPUT
;
111 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
112 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
116 /* Configure ID pin */
117 GPIO_InitStruct
.Pin
= GPIO_PIN_10
;
118 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_OD
;
119 GPIO_InitStruct
.Pull
= GPIO_PULLUP
;
120 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG1_FS
;
121 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
124 /* Enable USB FS Clocks */
125 __HAL_RCC_USB2_OTG_FS_CLK_ENABLE();
127 /* XXX Todo: Configure and enable CRS for HSI48 */
129 /* Set USBFS Interrupt to the lowest priority */
130 HAL_NVIC_SetPriority(OTG_FS_IRQn
, 6, 0);
132 /* Enable USBFS Interrupt */
133 HAL_NVIC_EnableIRQ(OTG_FS_IRQn
);
136 else if (hpcd
->Instance
== USB1_OTG_HS
)
138 /* Configure USB FS GPIOs */
139 __GPIOA_CLK_ENABLE();
140 __GPIOB_CLK_ENABLE();
141 __GPIOC_CLK_ENABLE();
142 __GPIOH_CLK_ENABLE();
143 __GPIOI_CLK_ENABLE();
146 GPIO_InitStruct
.Pin
= GPIO_PIN_5
;
147 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
148 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
149 GPIO_InitStruct
.Speed
= GPIO_SPEED_FREQ_VERY_HIGH
;
150 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG2_HS
;
151 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
154 GPIO_InitStruct
.Pin
= GPIO_PIN_3
;
155 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
156 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
157 GPIO_InitStruct
.Speed
= GPIO_SPEED_FREQ_VERY_HIGH
;
158 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG2_HS
;
159 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
161 /* D1 D2 D3 D4 D5 D6 D7 */
162 GPIO_InitStruct
.Pin
= GPIO_PIN_0
| GPIO_PIN_1
| GPIO_PIN_5
|
163 GPIO_PIN_10
| GPIO_PIN_11
| GPIO_PIN_12
| GPIO_PIN_13
;
164 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
165 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
166 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG2_HS
;
167 HAL_GPIO_Init(GPIOB
, &GPIO_InitStruct
);
170 GPIO_InitStruct
.Pin
= GPIO_PIN_0
;
171 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
172 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
173 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG2_HS
;
174 HAL_GPIO_Init(GPIOC
, &GPIO_InitStruct
);
177 GPIO_InitStruct
.Pin
= GPIO_PIN_4
;
178 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
179 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
180 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG2_HS
;
181 HAL_GPIO_Init(GPIOH
, &GPIO_InitStruct
);
184 GPIO_InitStruct
.Pin
= GPIO_PIN_11
;
185 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
186 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
187 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG2_HS
;
188 HAL_GPIO_Init(GPIOI
, &GPIO_InitStruct
);
189 __HAL_RCC_USB1_OTG_HS_ULPI_CLK_ENABLE();
191 /* Enable USB HS Clocks */
192 __HAL_RCC_USB1_OTG_HS_CLK_ENABLE();
194 /* Set USBHS Interrupt to the lowest priority */
195 HAL_NVIC_SetPriority(OTG_HS_IRQn
, 1, 0);
197 /* Enable USBHS Interrupt */
198 HAL_NVIC_EnableIRQ(OTG_HS_IRQn
);
203 * @brief De-Initializes the PCD MSP.
204 * @param hpcd: PCD handle
207 void HAL_PCD_MspDeInit(PCD_HandleTypeDef
* hpcd
)
209 if (hpcd
->Instance
== USB2_OTG_FS
)
211 /* Disable USB FS Clocks */
212 __HAL_RCC_USB2_OTG_FS_CLK_DISABLE();
214 else if (hpcd
->Instance
== USB1_OTG_HS
)
216 /* Disable USB HS Clocks */
217 __HAL_RCC_USB1_OTG_HS_CLK_DISABLE();
218 __HAL_RCC_USB1_OTG_HS_ULPI_CLK_DISABLE();
222 /*******************************************************************************
223 LL Driver Callbacks (PCD -> USB Device Library)
224 *******************************************************************************/
227 * @brief SetupStage callback.
228 * @param hpcd: PCD handle
231 void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef
* hpcd
)
233 USBD_LL_SetupStage(hpcd
->pData
, (uint8_t *) hpcd
->Setup
);
237 * @brief DataOut Stage callback.
238 * @param hpcd: PCD handle
239 * @param epnum: Endpoint Number
242 void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef
* hpcd
, uint8_t epnum
)
244 USBD_LL_DataOutStage(hpcd
->pData
, epnum
, hpcd
->OUT_ep
[epnum
].xfer_buff
);
248 * @brief DataIn Stage callback.
249 * @param hpcd: PCD handle
250 * @param epnum: Endpoint Number
253 void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef
* hpcd
, uint8_t epnum
)
255 USBD_LL_DataInStage(hpcd
->pData
, epnum
, hpcd
->IN_ep
[epnum
].xfer_buff
);
259 * @brief SOF callback.
260 * @param hpcd: PCD handle
263 void HAL_PCD_SOFCallback(PCD_HandleTypeDef
* hpcd
)
265 USBD_LL_SOF(hpcd
->pData
);
269 * @brief Reset callback.
270 * @param hpcd: PCD handle
273 void HAL_PCD_ResetCallback(PCD_HandleTypeDef
* hpcd
)
275 USBD_SpeedTypeDef speed
= USBD_SPEED_FULL
;
277 /* Set USB Current Speed */
278 switch (hpcd
->Init
.speed
)
281 speed
= USBD_SPEED_HIGH
;
285 speed
= USBD_SPEED_FULL
;
289 speed
= USBD_SPEED_FULL
;
294 USBD_LL_Reset(hpcd
->pData
);
296 USBD_LL_SetSpeed(hpcd
->pData
, speed
);
300 * @brief Suspend callback.
301 * @param hpcd: PCD handle
304 void HAL_PCD_SuspendCallback(PCD_HandleTypeDef
* hpcd
)
306 USBD_LL_Suspend(hpcd
->pData
);
310 * @brief Resume callback.
311 * @param hpcd: PCD handle
314 void HAL_PCD_ResumeCallback(PCD_HandleTypeDef
* hpcd
)
316 USBD_LL_Resume(hpcd
->pData
);
320 * @brief ISOOUTIncomplete callback.
321 * @param hpcd: PCD handle
322 * @param epnum: Endpoint Number
325 void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef
* hpcd
, uint8_t epnum
)
327 USBD_LL_IsoOUTIncomplete(hpcd
->pData
, epnum
);
331 * @brief ISOINIncomplete callback.
332 * @param hpcd: PCD handle
333 * @param epnum: Endpoint Number
336 void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef
* hpcd
, uint8_t epnum
)
338 USBD_LL_IsoINIncomplete(hpcd
->pData
, epnum
);
342 * @brief ConnectCallback callback.
343 * @param hpcd: PCD handle
346 void HAL_PCD_ConnectCallback(PCD_HandleTypeDef
* hpcd
)
348 USBD_LL_DevConnected(hpcd
->pData
);
352 * @brief Disconnect callback.
353 * @param hpcd: PCD handle
356 void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef
* hpcd
)
358 USBD_LL_DevDisconnected(hpcd
->pData
);
362 /*******************************************************************************
363 LL Driver Interface (USB Device Library --> PCD)
364 *******************************************************************************/
367 * @brief Initializes the Low Level portion of the Device driver.
368 * @param pdev: Device handle
369 * @retval USBD Status
371 USBD_StatusTypeDef
USBD_LL_Init(USBD_HandleTypeDef
* pdev
)
374 /* Set LL Driver parameters */
375 hpcd
.Instance
= USB2_OTG_FS
;
376 hpcd
.Init
.dev_endpoints
= 9;
377 hpcd
.Init
.use_dedicated_ep1
= DISABLE
;
378 hpcd
.Init
.ep0_mps
= DEP0CTL_MPS_64
;
379 hpcd
.Init
.low_power_enable
= DISABLE
;
380 hpcd
.Init
.phy_itface
= PCD_PHY_EMBEDDED
;
381 hpcd
.Init
.Sof_enable
= DISABLE
;
382 hpcd
.Init
.battery_charging_enable
= DISABLE
;
383 hpcd
.Init
.speed
= PCD_SPEED_FULL
;
384 hpcd
.Init
.vbus_sensing_enable
= DISABLE
;
385 hpcd
.Init
.dma_enable
= DISABLE
;
386 hpcd
.Init
.lpm_enable
= DISABLE
;
388 /* Link The driver to the stack */
392 hpcd
.Init
.vbus_sensing_enable
= 0;
394 /* Initialize LL Driver */
397 #ifdef USE_USB_CDC_HID
399 if (usbDevConfig()->type
== COMPOSITE
&& !mscCheckBoot()) {
401 if (usbDevConfig()->type
== COMPOSITE
) {
403 HAL_PCDEx_SetRxFiFo(&hpcd
, 0x80);
404 HAL_PCDEx_SetTxFiFo(&hpcd
, 0, 0x20);
405 HAL_PCDEx_SetTxFiFo(&hpcd
, 1, 0x40);
406 HAL_PCDEx_SetTxFiFo(&hpcd
, 2, 0x20);
407 HAL_PCDEx_SetTxFiFo(&hpcd
, 3, 0x40);
410 HAL_PCDEx_SetRxFiFo(&hpcd
, 0x80);
411 HAL_PCDEx_SetTxFiFo(&hpcd
, 0, 0x40);
412 HAL_PCDEx_SetTxFiFo(&hpcd
, 1, 0x80);
413 #ifdef USE_USB_CDC_HID
420 /* Set LL Driver parameters */
421 hpcd
.Instance
= USB1_OTG_HS
;
422 hpcd
.Init
.dev_endpoints
= 8;
423 hpcd
.Init
.use_dedicated_ep1
= 0;
424 hpcd
.Init
.ep0_mps
= 0x40;
426 /* Be aware that enabling DMA mode will result in data being sent only by
427 * multiple of 4 packet sizes. This is due to the fact that USB DMA does not
428 * allow sending data from non word-aligned addresses. For this specific
429 * application, it is advised to not enable this option unless required. */
430 hpcd
.Init
.dma_enable
= 0;
431 hpcd
.Init
.low_power_enable
= 0;
432 hpcd
.Init
.lpm_enable
= 0;
433 hpcd
.Init
.phy_itface
= PCD_PHY_ULPI
;
434 hpcd
.Init
.Sof_enable
= 0;
435 hpcd
.Init
.speed
= PCD_SPEED_HIGH
;
436 hpcd
.Init
.vbus_sensing_enable
= 0;
438 /* Link The driver to the stack */
442 /* Initialize LL Driver */
445 HAL_PCDEx_SetRxFiFo(&hpcd
, 0x200);
446 HAL_PCDEx_SetTxFiFo(&hpcd
, 0, 0x80);
447 HAL_PCDEx_SetTxFiFo(&hpcd
, 1, 0x174);
454 * @brief De-Initializes the Low Level portion of the Device driver.
455 * @param pdev: Device handle
456 * @retval USBD Status
458 USBD_StatusTypeDef
USBD_LL_DeInit(USBD_HandleTypeDef
* pdev
)
460 HAL_PCD_DeInit(pdev
->pData
);
465 * @brief Starts the Low Level portion of the Device driver.
466 * @param pdev: Device handle
467 * @retval USBD Status
469 USBD_StatusTypeDef
USBD_LL_Start(USBD_HandleTypeDef
* pdev
)
471 HAL_PCD_Start(pdev
->pData
);
476 * @brief Stops the Low Level portion of the Device driver.
477 * @param pdev: Device handle
478 * @retval USBD Status
480 USBD_StatusTypeDef
USBD_LL_Stop(USBD_HandleTypeDef
* pdev
)
482 HAL_PCD_Stop(pdev
->pData
);
487 * @brief Opens an endpoint of the Low Level Driver.
488 * @param pdev: Device handle
489 * @param ep_addr: Endpoint Number
490 * @param ep_type: Endpoint Type
491 * @param ep_mps: Endpoint Max Packet Size
492 * @retval USBD Status
494 USBD_StatusTypeDef
USBD_LL_OpenEP(USBD_HandleTypeDef
* pdev
,
496 uint8_t ep_type
, uint16_t ep_mps
)
498 HAL_PCD_EP_Open(pdev
->pData
, ep_addr
, ep_mps
, ep_type
);
504 * @brief Closes an endpoint of the Low Level Driver.
505 * @param pdev: Device handle
506 * @param ep_addr: Endpoint Number
507 * @retval USBD Status
509 USBD_StatusTypeDef
USBD_LL_CloseEP(USBD_HandleTypeDef
* pdev
, uint8_t ep_addr
)
511 HAL_PCD_EP_Close(pdev
->pData
, ep_addr
);
516 * @brief Flushes an endpoint of the Low Level Driver.
517 * @param pdev: Device handle
518 * @param ep_addr: Endpoint Number
519 * @retval USBD Status
521 USBD_StatusTypeDef
USBD_LL_FlushEP(USBD_HandleTypeDef
* pdev
, uint8_t ep_addr
)
523 HAL_PCD_EP_Flush(pdev
->pData
, ep_addr
);
528 * @brief Sets a Stall condition on an endpoint of the Low Level Driver.
529 * @param pdev: Device handle
530 * @param ep_addr: Endpoint Number
531 * @retval USBD Status
533 USBD_StatusTypeDef
USBD_LL_StallEP(USBD_HandleTypeDef
* pdev
, uint8_t ep_addr
)
535 HAL_PCD_EP_SetStall(pdev
->pData
, ep_addr
);
540 * @brief Clears a Stall condition on an endpoint of the Low Level Driver.
541 * @param pdev: Device handle
542 * @param ep_addr: Endpoint Number
543 * @retval USBD Status
545 USBD_StatusTypeDef
USBD_LL_ClearStallEP(USBD_HandleTypeDef
* pdev
,
548 HAL_PCD_EP_ClrStall(pdev
->pData
, ep_addr
);
553 * @brief Returns Stall condition.
554 * @param pdev: Device handle
555 * @param ep_addr: Endpoint Number
556 * @retval Stall (1: Yes, 0: No)
558 uint8_t USBD_LL_IsStallEP(USBD_HandleTypeDef
* pdev
, uint8_t ep_addr
)
560 PCD_HandleTypeDef
*hpcd
= pdev
->pData
;
562 if ((ep_addr
& 0x80) == 0x80)
564 return hpcd
->IN_ep
[ep_addr
& 0x7F].is_stall
;
568 return hpcd
->OUT_ep
[ep_addr
& 0x7F].is_stall
;
573 * @brief Assigns a USB address to the device.
574 * @param pdev: Device handle
575 * @param ep_addr: Endpoint Number
576 * @retval USBD Status
578 USBD_StatusTypeDef
USBD_LL_SetUSBAddress(USBD_HandleTypeDef
* pdev
,
581 HAL_PCD_SetAddress(pdev
->pData
, dev_addr
);
586 * @brief Transmits data over an endpoint.
587 * @param pdev: Device handle
588 * @param ep_addr: Endpoint Number
589 * @param pbuf: Pointer to data to be sent
590 * @param size: Data size
591 * @retval USBD Status
593 USBD_StatusTypeDef
USBD_LL_Transmit(USBD_HandleTypeDef
* pdev
,
595 uint8_t * pbuf
, uint16_t size
)
597 /* Get the packet total length */
598 pdev
->ep_in
[ep_addr
& 0x7F].total_length
= size
;
600 HAL_PCD_EP_Transmit(pdev
->pData
, ep_addr
, pbuf
, size
);
605 * @brief Prepares an endpoint for reception.
606 * @param pdev: Device handle
607 * @param ep_addr: Endpoint Number
608 * @param pbuf: Pointer to data to be received
609 * @param size: Data size
610 * @retval USBD Status
612 USBD_StatusTypeDef
USBD_LL_PrepareReceive(USBD_HandleTypeDef
* pdev
,
614 uint8_t * pbuf
, uint16_t size
)
616 HAL_PCD_EP_Receive(pdev
->pData
, ep_addr
, pbuf
, size
);
621 * @brief Returns the last transferred packet size.
622 * @param pdev: Device handle
623 * @param ep_addr: Endpoint Number
624 * @retval Received Data Size
626 uint32_t USBD_LL_GetRxDataSize(USBD_HandleTypeDef
* pdev
, uint8_t ep_addr
)
628 return HAL_PCD_EP_GetRxCount(pdev
->pData
, ep_addr
);
632 * @brief Delays routine for the USB Device Library.
633 * @param Delay: Delay in ms
636 void USBD_LL_Delay(uint32_t Delay
)
641 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/