2 ******************************************************************************
3 * @file USB_Device/CDC_Standalone/Src/usbd_conf.c
4 * @author MCD Application Team
7 * @brief This file implements the USB Device library callbacks and MSP
8 ******************************************************************************
11 * <h2><center>© Copyright (c) 2016 STMicroelectronics International N.V.
12 * All rights reserved.</center></h2>
14 * Redistribution and use in source and binary forms, with or without
15 * modification, are permitted, provided that the following conditions are met:
17 * 1. Redistribution of source code must retain the above copyright notice,
18 * this list of conditions and the following disclaimer.
19 * 2. Redistributions in binary form must reproduce the above copyright notice,
20 * this list of conditions and the following disclaimer in the documentation
21 * and/or other materials provided with the distribution.
22 * 3. Neither the name of STMicroelectronics nor the names of other
23 * contributors to this software may be used to endorse or promote products
24 * derived from this software without specific written permission.
25 * 4. This software, including modifications and/or derivative works of this
26 * software, must execute solely and exclusively on microcontroller or
27 * microprocessor devices manufactured by or for STMicroelectronics.
28 * 5. Redistribution and use of this software other than as permitted under
29 * this license is void and will automatically terminate your rights under
32 * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
33 * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
34 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
35 * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
36 * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
37 * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
38 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
39 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
40 * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
41 * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
42 * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
43 * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
45 ******************************************************************************
48 /* Includes ------------------------------------------------------------------*/
49 #include "stm32f7xx_hal.h"
50 #include "usbd_core.h"
51 #include "usbd_desc.h"
53 #include "usbd_conf.h"
54 #include "usbd_cdc_interface.h"
56 /* Private typedef -----------------------------------------------------------*/
57 /* Private define ------------------------------------------------------------*/
58 /* Private macro -------------------------------------------------------------*/
59 /* Private variables ---------------------------------------------------------*/
60 PCD_HandleTypeDef hpcd
;
62 /* Private function prototypes -----------------------------------------------*/
63 /* Private functions ---------------------------------------------------------*/
65 /*******************************************************************************
67 *******************************************************************************/
70 void OTG_FS_IRQHandler(void)
72 void OTG_HS_IRQHandler(void)
75 HAL_PCD_IRQHandler(&hpcd
);
79 * @brief Initializes the PCD MSP.
80 * @param hpcd: PCD handle
83 void HAL_PCD_MspInit(PCD_HandleTypeDef
*hpcd
)
85 GPIO_InitTypeDef GPIO_InitStruct
;
87 if (hpcd
->Instance
== USB_OTG_FS
)
89 /* Configure USB FS GPIOs */
90 __HAL_RCC_GPIOA_CLK_ENABLE();
92 /* Configure DM DP Pins */
93 GPIO_InitStruct
.Pin
= (GPIO_PIN_11
| GPIO_PIN_12
);
94 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
95 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
96 GPIO_InitStruct
.Speed
= GPIO_SPEED_HIGH
;
97 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_FS
;
98 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
100 if (hpcd
->Init
.vbus_sensing_enable
== 1)
102 /* Configure VBUS Pin */
103 GPIO_InitStruct
.Pin
= GPIO_PIN_9
;
104 GPIO_InitStruct
.Mode
= GPIO_MODE_INPUT
;
105 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
106 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
109 /* Configure ID pin */
110 GPIO_InitStruct
.Pin
= GPIO_PIN_10
;
111 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_OD
;
112 GPIO_InitStruct
.Pull
= GPIO_PULLUP
;
113 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_FS
;
114 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
116 /* Enable USB FS Clock */
117 __HAL_RCC_USB_OTG_FS_CLK_ENABLE();
119 /* Set USBFS Interrupt priority */
120 HAL_NVIC_SetPriority(OTG_FS_IRQn
, 6, 0);
122 /* Enable USBFS Interrupt */
123 HAL_NVIC_EnableIRQ(OTG_FS_IRQn
);
125 else if (hpcd
->Instance
== USB_OTG_HS
)
127 #ifdef USE_USB_HS_IN_FS
129 __HAL_RCC_GPIOB_CLK_ENABLE();
131 /*Configure GPIO for HS on FS mode*/
132 GPIO_InitStruct
.Pin
= GPIO_PIN_12
| GPIO_PIN_14
|GPIO_PIN_15
;
133 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
134 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
135 GPIO_InitStruct
.Speed
= GPIO_SPEED_HIGH
;
136 GPIO_InitStruct
.Alternate
= GPIO_AF12_OTG_HS_FS
;
137 HAL_GPIO_Init(GPIOB
, &GPIO_InitStruct
);
139 if (hpcd
->Init
.vbus_sensing_enable
== 1)
141 /* Configure VBUS Pin */
142 GPIO_InitStruct
.Pin
= GPIO_PIN_13
;
143 GPIO_InitStruct
.Mode
= GPIO_MODE_INPUT
;
144 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
145 HAL_GPIO_Init(GPIOB
, &GPIO_InitStruct
);
148 /* Configure USB FS GPIOs */
149 __HAL_RCC_GPIOA_CLK_ENABLE();
150 __HAL_RCC_GPIOB_CLK_ENABLE();
151 __HAL_RCC_GPIOC_CLK_ENABLE();
152 __HAL_RCC_GPIOH_CLK_ENABLE();
153 __HAL_RCC_GPIOI_CLK_ENABLE();
156 GPIO_InitStruct
.Pin
= GPIO_PIN_5
;
157 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
158 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
159 GPIO_InitStruct
.Speed
= GPIO_SPEED_HIGH
;
160 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_HS
;
161 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
164 GPIO_InitStruct
.Pin
= GPIO_PIN_3
;
165 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
166 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
167 GPIO_InitStruct
.Speed
= GPIO_SPEED_HIGH
;
168 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_HS
;
169 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
171 /* D1 D2 D3 D4 D5 D6 D7 */
172 GPIO_InitStruct
.Pin
= GPIO_PIN_0
| GPIO_PIN_1
| GPIO_PIN_5
|\
173 GPIO_PIN_10
| GPIO_PIN_11
| GPIO_PIN_12
| GPIO_PIN_13
;
174 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
175 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
176 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_HS
;
177 HAL_GPIO_Init(GPIOB
, &GPIO_InitStruct
);
180 GPIO_InitStruct
.Pin
= GPIO_PIN_0
;
181 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
182 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
183 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_HS
;
184 HAL_GPIO_Init(GPIOC
, &GPIO_InitStruct
);
187 GPIO_InitStruct
.Pin
= GPIO_PIN_4
;
188 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
189 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
190 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_HS
;
191 HAL_GPIO_Init(GPIOH
, &GPIO_InitStruct
);
194 GPIO_InitStruct
.Pin
= GPIO_PIN_11
;
195 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
196 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
197 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_HS
;
198 HAL_GPIO_Init(GPIOI
, &GPIO_InitStruct
);
199 __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE();
201 /* Enable USB HS Clocks */
202 __HAL_RCC_USB_OTG_HS_CLK_ENABLE();
204 /* Set USBHS Interrupt to the lowest priority */
205 HAL_NVIC_SetPriority(OTG_HS_IRQn
, 6, 0);
207 /* Enable USBHS Interrupt */
208 HAL_NVIC_EnableIRQ(OTG_HS_IRQn
);
213 * @brief De-Initializes the PCD MSP.
214 * @param hpcd: PCD handle
217 void HAL_PCD_MspDeInit(PCD_HandleTypeDef
*hpcd
)
219 if (hpcd
->Instance
== USB_OTG_FS
)
221 /* Disable USB FS Clock */
222 __HAL_RCC_USB_OTG_FS_CLK_DISABLE();
223 __HAL_RCC_SYSCFG_CLK_DISABLE();
225 else if (hpcd
->Instance
== USB_OTG_HS
)
227 /* Disable USB HS Clocks */
228 __HAL_RCC_USB_OTG_HS_CLK_DISABLE();
229 __HAL_RCC_SYSCFG_CLK_DISABLE();
233 /*******************************************************************************
234 LL Driver Callbacks (PCD -> USB Device Library)
235 *******************************************************************************/
238 * @brief SetupStage callback.
239 * @param hpcd: PCD handle
242 void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef
*hpcd
)
244 USBD_LL_SetupStage(hpcd
->pData
, (uint8_t *)hpcd
->Setup
);
248 * @brief DataOut Stage callback.
249 * @param hpcd: PCD handle
250 * @param epnum: Endpoint Number
253 void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef
*hpcd
, uint8_t epnum
)
255 USBD_LL_DataOutStage(hpcd
->pData
, epnum
, hpcd
->OUT_ep
[epnum
].xfer_buff
);
259 * @brief DataIn Stage callback.
260 * @param hpcd: PCD handle
261 * @param epnum: Endpoint Number
264 void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef
*hpcd
, uint8_t epnum
)
266 USBD_LL_DataInStage(hpcd
->pData
, epnum
, hpcd
->IN_ep
[epnum
].xfer_buff
);
270 * @brief SOF callback.
271 * @param hpcd: PCD handle
274 void HAL_PCD_SOFCallback(PCD_HandleTypeDef
*hpcd
)
276 USBD_LL_SOF(hpcd
->pData
);
280 * @brief Reset callback.
281 * @param hpcd: PCD handle
284 void HAL_PCD_ResetCallback(PCD_HandleTypeDef
*hpcd
)
286 USBD_SpeedTypeDef speed
= USBD_SPEED_FULL
;
288 /* Set USB Current Speed */
289 switch (hpcd
->Init
.speed
)
292 speed
= USBD_SPEED_HIGH
;
296 speed
= USBD_SPEED_FULL
;
300 speed
= USBD_SPEED_FULL
;
305 USBD_LL_Reset(hpcd
->pData
);
307 USBD_LL_SetSpeed(hpcd
->pData
, speed
);
311 * @brief Suspend callback.
312 * @param hpcd: PCD handle
315 void HAL_PCD_SuspendCallback(PCD_HandleTypeDef
*hpcd
)
317 USBD_LL_Suspend(hpcd
->pData
);
321 * @brief Resume callback.
322 * @param hpcd: PCD handle
325 void HAL_PCD_ResumeCallback(PCD_HandleTypeDef
*hpcd
)
327 USBD_LL_Resume(hpcd
->pData
);
331 * @brief ISOOUTIncomplete callback.
332 * @param hpcd: PCD handle
333 * @param epnum: Endpoint Number
336 void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef
*hpcd
, uint8_t epnum
)
338 USBD_LL_IsoOUTIncomplete(hpcd
->pData
, epnum
);
342 * @brief ISOINIncomplete callback.
343 * @param hpcd: PCD handle
344 * @param epnum: Endpoint Number
347 void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef
*hpcd
, uint8_t epnum
)
349 USBD_LL_IsoINIncomplete(hpcd
->pData
, epnum
);
353 * @brief ConnectCallback callback.
354 * @param hpcd: PCD handle
357 void HAL_PCD_ConnectCallback(PCD_HandleTypeDef
*hpcd
)
359 USBD_LL_DevConnected(hpcd
->pData
);
363 * @brief Disconnect callback.
364 * @param hpcd: PCD handle
367 void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef
*hpcd
)
369 USBD_LL_DevDisconnected(hpcd
->pData
);
373 /*******************************************************************************
374 LL Driver Interface (USB Device Library --> PCD)
375 *******************************************************************************/
378 * @brief Initializes the Low Level portion of the Device driver.
379 * @param pdev: Device handle
380 * @retval USBD Status
382 USBD_StatusTypeDef
USBD_LL_Init(USBD_HandleTypeDef
*pdev
)
385 /* Set LL Driver parameters */
386 hpcd
.Instance
= USB_OTG_FS
;
387 hpcd
.Init
.dev_endpoints
= 4;
388 hpcd
.Init
.use_dedicated_ep1
= 0;
389 hpcd
.Init
.ep0_mps
= 0x40;
390 hpcd
.Init
.dma_enable
= 0;
391 hpcd
.Init
.low_power_enable
= 0;
392 hpcd
.Init
.phy_itface
= PCD_PHY_EMBEDDED
;
393 hpcd
.Init
.Sof_enable
= 0;
394 hpcd
.Init
.speed
= PCD_SPEED_FULL
;
395 hpcd
.Init
.vbus_sensing_enable
= 0;
396 hpcd
.Init
.lpm_enable
= 0;
398 /* Link The driver to the stack */
402 /* Initialize LL Driver */
405 HAL_PCDEx_SetRxFiFo(&hpcd
, 0x80);
406 HAL_PCDEx_SetTxFiFo(&hpcd
, 0, 0x40);
407 HAL_PCDEx_SetTxFiFo(&hpcd
, 1, 0x80);
411 /* Set LL Driver parameters */
412 hpcd
.Instance
= USB_OTG_HS
;
413 hpcd
.Init
.dev_endpoints
= 6;
414 hpcd
.Init
.use_dedicated_ep1
= 0;
415 hpcd
.Init
.ep0_mps
= 0x40;
417 /* Be aware that enabling DMA mode will result in data being sent only by
418 multiple of 4 packet sizes. This is due to the fact that USB DMA does
419 not allow sending data from non word-aligned addresses.
420 For this specific application, it is advised to not enable this option
422 hpcd
.Init
.dma_enable
= 0;
423 hpcd
.Init
.low_power_enable
= 0;
424 hpcd
.Init
.lpm_enable
= 0;
426 #ifdef USE_USB_HS_IN_FS
427 hpcd
.Init
.phy_itface
= PCD_PHY_EMBEDDED
;
429 hpcd
.Init
.phy_itface
= PCD_PHY_ULPI
;
431 hpcd
.Init
.Sof_enable
= 0;
432 hpcd
.Init
.speed
= PCD_SPEED_HIGH
;
433 hpcd
.Init
.vbus_sensing_enable
= 1;
435 /* Link The driver to the stack */
439 /* Initialize LL Driver */
442 HAL_PCDEx_SetRxFiFo(&hpcd
, 0x200);
443 HAL_PCDEx_SetTxFiFo(&hpcd
, 0, 0x80);
444 HAL_PCDEx_SetTxFiFo(&hpcd
, 1, 0x174);
451 * @brief De-Initializes the Low Level portion of the Device driver.
452 * @param pdev: Device handle
453 * @retval USBD Status
455 USBD_StatusTypeDef
USBD_LL_DeInit(USBD_HandleTypeDef
*pdev
)
457 HAL_PCD_DeInit(pdev
->pData
);
462 * @brief Starts the Low Level portion of the Device driver.
463 * @param pdev: Device handle
464 * @retval USBD Status
466 USBD_StatusTypeDef
USBD_LL_Start(USBD_HandleTypeDef
*pdev
)
468 HAL_PCD_Start(pdev
->pData
);
473 * @brief Stops the Low Level portion of the Device driver.
474 * @param pdev: Device handle
475 * @retval USBD Status
477 USBD_StatusTypeDef
USBD_LL_Stop(USBD_HandleTypeDef
*pdev
)
479 HAL_PCD_Stop(pdev
->pData
);
484 * @brief Opens an endpoint of the Low Level Driver.
485 * @param pdev: Device handle
486 * @param ep_addr: Endpoint Number
487 * @param ep_type: Endpoint Type
488 * @param ep_mps: Endpoint Max Packet Size
489 * @retval USBD Status
491 USBD_StatusTypeDef
USBD_LL_OpenEP(USBD_HandleTypeDef
*pdev
,
496 HAL_PCD_EP_Open(pdev
->pData
,
505 * @brief Closes an endpoint of the Low Level Driver.
506 * @param pdev: Device handle
507 * @param ep_addr: Endpoint Number
508 * @retval USBD Status
510 USBD_StatusTypeDef
USBD_LL_CloseEP(USBD_HandleTypeDef
*pdev
, uint8_t ep_addr
)
512 HAL_PCD_EP_Close(pdev
->pData
, ep_addr
);
517 * @brief Flushes an endpoint of the Low Level Driver.
518 * @param pdev: Device handle
519 * @param ep_addr: Endpoint Number
520 * @retval USBD Status
522 USBD_StatusTypeDef
USBD_LL_FlushEP(USBD_HandleTypeDef
*pdev
, uint8_t ep_addr
)
524 HAL_PCD_EP_Flush(pdev
->pData
, ep_addr
);
529 * @brief Sets a Stall condition on an endpoint of the Low Level Driver.
530 * @param pdev: Device handle
531 * @param ep_addr: Endpoint Number
532 * @retval USBD Status
534 USBD_StatusTypeDef
USBD_LL_StallEP(USBD_HandleTypeDef
*pdev
, uint8_t ep_addr
)
536 HAL_PCD_EP_SetStall(pdev
->pData
, ep_addr
);
541 * @brief Clears a Stall condition on an endpoint of the Low Level Driver.
542 * @param pdev: Device handle
543 * @param ep_addr: Endpoint Number
544 * @retval USBD Status
546 USBD_StatusTypeDef
USBD_LL_ClearStallEP(USBD_HandleTypeDef
*pdev
, uint8_t ep_addr
)
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
, uint8_t dev_addr
)
580 HAL_PCD_SetAddress(pdev
->pData
, dev_addr
);
585 * @brief Transmits data over an endpoint.
586 * @param pdev: Device handle
587 * @param ep_addr: Endpoint Number
588 * @param pbuf: Pointer to data to be sent
589 * @param size: Data size
590 * @retval USBD Status
592 USBD_StatusTypeDef
USBD_LL_Transmit(USBD_HandleTypeDef
*pdev
,
597 HAL_PCD_EP_Transmit(pdev
->pData
, ep_addr
, pbuf
, size
);
602 * @brief Prepares an endpoint for reception.
603 * @param pdev: Device handle
604 * @param ep_addr: Endpoint Number
605 * @param pbuf: Pointer to data to be received
606 * @param size: Data size
607 * @retval USBD Status
609 USBD_StatusTypeDef
USBD_LL_PrepareReceive(USBD_HandleTypeDef
*pdev
,
614 HAL_PCD_EP_Receive(pdev
->pData
, ep_addr
, pbuf
, size
);
619 * @brief Returns the last transferred packet size.
620 * @param pdev: Device handle
621 * @param ep_addr: Endpoint Number
622 * @retval Received Data Size
624 uint32_t USBD_LL_GetRxDataSize(USBD_HandleTypeDef
*pdev
, uint8_t ep_addr
)
626 return HAL_PCD_EP_GetRxCount(pdev
->pData
, ep_addr
);
630 * @brief Delays routine for the USB Device Library.
631 * @param Delay: Delay in ms
634 void USBD_LL_Delay(uint32_t Delay
)
639 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/