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 "common/maths.h"
51 #include "stm32f7xx_hal.h"
52 #include "usbd_core.h"
53 #include "usbd_desc.h"
55 #include "usbd_conf.h"
56 #include "usbd_cdc_interface.h"
63 #include "drivers/usb_msc.h"
66 /* Private typedef -----------------------------------------------------------*/
67 /* Private define ------------------------------------------------------------*/
68 /* Private macro -------------------------------------------------------------*/
69 /* Private variables ---------------------------------------------------------*/
70 PCD_HandleTypeDef hpcd
;
72 /* Private function prototypes -----------------------------------------------*/
73 /* Private functions ---------------------------------------------------------*/
75 /*******************************************************************************
77 *******************************************************************************/
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
;
97 if (hpcd
->Instance
== USB_OTG_FS
)
99 /* Configure USB FS GPIOs */
100 __HAL_RCC_GPIOA_CLK_ENABLE();
102 /* Configure DM DP Pins */
103 GPIO_InitStruct
.Pin
= (GPIO_PIN_11
| GPIO_PIN_12
);
104 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
105 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
106 GPIO_InitStruct
.Speed
= GPIO_SPEED_HIGH
;
107 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_FS
;
108 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
110 if (hpcd
->Init
.vbus_sensing_enable
== 1)
112 /* Configure VBUS Pin */
113 GPIO_InitStruct
.Pin
= GPIO_PIN_9
;
114 GPIO_InitStruct
.Mode
= GPIO_MODE_INPUT
;
115 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
116 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
119 /* Configure ID pin */
120 GPIO_InitStruct
.Pin
= GPIO_PIN_10
;
121 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_OD
;
122 GPIO_InitStruct
.Pull
= GPIO_PULLUP
;
123 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_FS
;
124 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
126 /* Enable USB FS Clock */
127 __HAL_RCC_USB_OTG_FS_CLK_ENABLE();
129 /* Set USBFS Interrupt priority */
130 HAL_NVIC_SetPriority(OTG_FS_IRQn
, 6, 0);
132 /* Enable USBFS Interrupt */
133 HAL_NVIC_EnableIRQ(OTG_FS_IRQn
);
135 else if (hpcd
->Instance
== USB_OTG_HS
)
137 #ifdef USE_USB_HS_IN_FS
139 __HAL_RCC_GPIOB_CLK_ENABLE();
141 /*Configure GPIO for HS on FS mode*/
142 GPIO_InitStruct
.Pin
= GPIO_PIN_12
| GPIO_PIN_14
|GPIO_PIN_15
;
143 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
144 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
145 GPIO_InitStruct
.Speed
= GPIO_SPEED_HIGH
;
146 GPIO_InitStruct
.Alternate
= GPIO_AF12_OTG_HS_FS
;
147 HAL_GPIO_Init(GPIOB
, &GPIO_InitStruct
);
149 if (hpcd
->Init
.vbus_sensing_enable
== 1)
151 /* Configure VBUS Pin */
152 GPIO_InitStruct
.Pin
= GPIO_PIN_13
;
153 GPIO_InitStruct
.Mode
= GPIO_MODE_INPUT
;
154 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
155 HAL_GPIO_Init(GPIOB
, &GPIO_InitStruct
);
158 /* Configure USB FS GPIOs */
159 __HAL_RCC_GPIOA_CLK_ENABLE();
160 __HAL_RCC_GPIOB_CLK_ENABLE();
161 __HAL_RCC_GPIOC_CLK_ENABLE();
162 __HAL_RCC_GPIOH_CLK_ENABLE();
163 __HAL_RCC_GPIOI_CLK_ENABLE();
166 GPIO_InitStruct
.Pin
= GPIO_PIN_5
;
167 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
168 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
169 GPIO_InitStruct
.Speed
= GPIO_SPEED_HIGH
;
170 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_HS
;
171 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
174 GPIO_InitStruct
.Pin
= GPIO_PIN_3
;
175 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
176 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
177 GPIO_InitStruct
.Speed
= GPIO_SPEED_HIGH
;
178 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_HS
;
179 HAL_GPIO_Init(GPIOA
, &GPIO_InitStruct
);
181 /* D1 D2 D3 D4 D5 D6 D7 */
182 GPIO_InitStruct
.Pin
= GPIO_PIN_0
| GPIO_PIN_1
| GPIO_PIN_5
|\
183 GPIO_PIN_10
| GPIO_PIN_11
| GPIO_PIN_12
| GPIO_PIN_13
;
184 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
185 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
186 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_HS
;
187 HAL_GPIO_Init(GPIOB
, &GPIO_InitStruct
);
190 GPIO_InitStruct
.Pin
= GPIO_PIN_0
;
191 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
192 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
193 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_HS
;
194 HAL_GPIO_Init(GPIOC
, &GPIO_InitStruct
);
197 GPIO_InitStruct
.Pin
= GPIO_PIN_4
;
198 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
199 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
200 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_HS
;
201 HAL_GPIO_Init(GPIOH
, &GPIO_InitStruct
);
204 GPIO_InitStruct
.Pin
= GPIO_PIN_11
;
205 GPIO_InitStruct
.Mode
= GPIO_MODE_AF_PP
;
206 GPIO_InitStruct
.Pull
= GPIO_NOPULL
;
207 GPIO_InitStruct
.Alternate
= GPIO_AF10_OTG_HS
;
208 HAL_GPIO_Init(GPIOI
, &GPIO_InitStruct
);
209 __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE();
211 /* Enable USB HS Clocks */
212 __HAL_RCC_USB_OTG_HS_CLK_ENABLE();
214 /* Set USBHS Interrupt to the lowest priority */
215 HAL_NVIC_SetPriority(OTG_HS_IRQn
, 6, 0);
217 /* Enable USBHS Interrupt */
218 HAL_NVIC_EnableIRQ(OTG_HS_IRQn
);
223 * @brief De-Initializes the PCD MSP.
224 * @param hpcd: PCD handle
227 void HAL_PCD_MspDeInit(PCD_HandleTypeDef
*hpcd
)
229 if (hpcd
->Instance
== USB_OTG_FS
)
231 /* Disable USB FS Clock */
232 __HAL_RCC_USB_OTG_FS_CLK_DISABLE();
233 __HAL_RCC_SYSCFG_CLK_DISABLE();
235 else if (hpcd
->Instance
== USB_OTG_HS
)
237 /* Disable USB HS Clocks */
238 __HAL_RCC_USB_OTG_HS_CLK_DISABLE();
239 __HAL_RCC_SYSCFG_CLK_DISABLE();
243 /*******************************************************************************
244 LL Driver Callbacks (PCD -> USB Device Library)
245 *******************************************************************************/
248 * @brief SetupStage callback.
249 * @param hpcd: PCD handle
252 void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef
*hpcd
)
254 USBD_LL_SetupStage(hpcd
->pData
, (uint8_t *)hpcd
->Setup
);
258 * @brief DataOut Stage callback.
259 * @param hpcd: PCD handle
260 * @param epnum: Endpoint Number
263 void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef
*hpcd
, uint8_t epnum
)
265 USBD_LL_DataOutStage(hpcd
->pData
, epnum
, hpcd
->OUT_ep
[epnum
].xfer_buff
);
269 * @brief DataIn Stage callback.
270 * @param hpcd: PCD handle
271 * @param epnum: Endpoint Number
274 void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef
*hpcd
, uint8_t epnum
)
276 USBD_LL_DataInStage(hpcd
->pData
, epnum
, hpcd
->IN_ep
[epnum
].xfer_buff
);
280 * @brief SOF callback.
281 * @param hpcd: PCD handle
284 void HAL_PCD_SOFCallback(PCD_HandleTypeDef
*hpcd
)
286 USBD_LL_SOF(hpcd
->pData
);
290 * @brief Reset callback.
291 * @param hpcd: PCD handle
294 void HAL_PCD_ResetCallback(PCD_HandleTypeDef
*hpcd
)
296 USBD_SpeedTypeDef speed
= USBD_SPEED_FULL
;
298 /* Set USB Current Speed */
299 switch (hpcd
->Init
.speed
)
302 speed
= USBD_SPEED_HIGH
;
306 speed
= USBD_SPEED_FULL
;
310 speed
= USBD_SPEED_FULL
;
315 USBD_LL_Reset(hpcd
->pData
);
317 USBD_LL_SetSpeed(hpcd
->pData
, speed
);
321 * @brief Suspend callback.
322 * @param hpcd: PCD handle
325 void HAL_PCD_SuspendCallback(PCD_HandleTypeDef
*hpcd
)
327 USBD_LL_Suspend(hpcd
->pData
);
331 * @brief Resume callback.
332 * @param hpcd: PCD handle
335 void HAL_PCD_ResumeCallback(PCD_HandleTypeDef
*hpcd
)
337 USBD_LL_Resume(hpcd
->pData
);
341 * @brief ISOOUTIncomplete callback.
342 * @param hpcd: PCD handle
343 * @param epnum: Endpoint Number
346 void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef
*hpcd
, uint8_t epnum
)
348 USBD_LL_IsoOUTIncomplete(hpcd
->pData
, epnum
);
352 * @brief ISOINIncomplete callback.
353 * @param hpcd: PCD handle
354 * @param epnum: Endpoint Number
357 void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef
*hpcd
, uint8_t epnum
)
359 USBD_LL_IsoINIncomplete(hpcd
->pData
, epnum
);
363 * @brief ConnectCallback callback.
364 * @param hpcd: PCD handle
367 void HAL_PCD_ConnectCallback(PCD_HandleTypeDef
*hpcd
)
369 USBD_LL_DevConnected(hpcd
->pData
);
373 * @brief Disconnect callback.
374 * @param hpcd: PCD handle
377 void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef
*hpcd
)
379 USBD_LL_DevDisconnected(hpcd
->pData
);
383 /*******************************************************************************
384 LL Driver Interface (USB Device Library --> PCD)
385 *******************************************************************************/
388 * @brief Initializes the Low Level portion of the Device driver.
389 * @param pdev: Device handle
390 * @retval USBD Status
392 USBD_StatusTypeDef
USBD_LL_Init(USBD_HandleTypeDef
*pdev
)
395 /* Set LL Driver parameters */
396 hpcd
.Instance
= USB_OTG_FS
;
397 hpcd
.Init
.dev_endpoints
= 4;
398 hpcd
.Init
.use_dedicated_ep1
= 0;
399 hpcd
.Init
.ep0_mps
= 0x40;
400 hpcd
.Init
.dma_enable
= 0;
401 hpcd
.Init
.low_power_enable
= 0;
402 hpcd
.Init
.phy_itface
= PCD_PHY_EMBEDDED
;
403 hpcd
.Init
.Sof_enable
= 0;
404 hpcd
.Init
.speed
= PCD_SPEED_FULL
;
405 hpcd
.Init
.vbus_sensing_enable
= 0;
406 hpcd
.Init
.lpm_enable
= 0;
408 /* Link The driver to the stack */
412 /* Initialize LL Driver */
416 #ifdef USE_USB_CDC_HID
418 if (usbDevConfig()->type
== COMPOSITE
&& !mscCheckBootAndReset()) {
420 if (usbDevConfig()->type
== COMPOSITE
) {
422 HAL_PCDEx_SetRxFiFo(&hpcd
, 0x80);
423 HAL_PCDEx_SetTxFiFo(&hpcd
, 0, 0x20);
424 HAL_PCDEx_SetTxFiFo(&hpcd
, 1, 0x40);
425 HAL_PCDEx_SetTxFiFo(&hpcd
, 2, 0x20);
426 HAL_PCDEx_SetTxFiFo(&hpcd
, 3, 0x40);
429 HAL_PCDEx_SetRxFiFo(&hpcd
, 0x80);
430 HAL_PCDEx_SetTxFiFo(&hpcd
, 0, 0x40);
431 HAL_PCDEx_SetTxFiFo(&hpcd
, 1, 0x80);
432 #ifdef USE_USB_CDC_HID
438 /* Set LL Driver parameters */
439 hpcd
.Instance
= USB_OTG_HS
;
440 hpcd
.Init
.dev_endpoints
= 6;
441 hpcd
.Init
.use_dedicated_ep1
= 0;
442 hpcd
.Init
.ep0_mps
= 0x40;
444 /* Be aware that enabling DMA mode will result in data being sent only by
445 multiple of 4 packet sizes. This is due to the fact that USB DMA does
446 not allow sending data from non word-aligned addresses.
447 For this specific application, it is advised to not enable this option
449 hpcd
.Init
.dma_enable
= 0;
450 hpcd
.Init
.low_power_enable
= 0;
451 hpcd
.Init
.lpm_enable
= 0;
453 #ifdef USE_USB_HS_IN_FS
454 hpcd
.Init
.phy_itface
= PCD_PHY_EMBEDDED
;
456 hpcd
.Init
.phy_itface
= PCD_PHY_ULPI
;
458 hpcd
.Init
.Sof_enable
= 0;
459 hpcd
.Init
.speed
= PCD_SPEED_HIGH
;
460 hpcd
.Init
.vbus_sensing_enable
= 1;
462 /* Link The driver to the stack */
466 /* Initialize LL Driver */
469 HAL_PCDEx_SetRxFiFo(&hpcd
, 0x200);
470 HAL_PCDEx_SetTxFiFo(&hpcd
, 0, 0x80);
471 HAL_PCDEx_SetTxFiFo(&hpcd
, 1, 0x174);
478 * @brief De-Initializes the Low Level portion of the Device driver.
479 * @param pdev: Device handle
480 * @retval USBD Status
482 USBD_StatusTypeDef
USBD_LL_DeInit(USBD_HandleTypeDef
*pdev
)
484 HAL_PCD_DeInit(pdev
->pData
);
489 * @brief Starts the Low Level portion of the Device driver.
490 * @param pdev: Device handle
491 * @retval USBD Status
493 USBD_StatusTypeDef
USBD_LL_Start(USBD_HandleTypeDef
*pdev
)
495 HAL_PCD_Start(pdev
->pData
);
500 * @brief Stops the Low Level portion of the Device driver.
501 * @param pdev: Device handle
502 * @retval USBD Status
504 USBD_StatusTypeDef
USBD_LL_Stop(USBD_HandleTypeDef
*pdev
)
506 HAL_PCD_Stop(pdev
->pData
);
511 * @brief Opens an endpoint of the Low Level Driver.
512 * @param pdev: Device handle
513 * @param ep_addr: Endpoint Number
514 * @param ep_type: Endpoint Type
515 * @param ep_mps: Endpoint Max Packet Size
516 * @retval USBD Status
518 USBD_StatusTypeDef
USBD_LL_OpenEP(USBD_HandleTypeDef
*pdev
,
523 HAL_PCD_EP_Open(pdev
->pData
,
532 * @brief Closes an endpoint of the Low Level Driver.
533 * @param pdev: Device handle
534 * @param ep_addr: Endpoint Number
535 * @retval USBD Status
537 USBD_StatusTypeDef
USBD_LL_CloseEP(USBD_HandleTypeDef
*pdev
, uint8_t ep_addr
)
539 HAL_PCD_EP_Close(pdev
->pData
, ep_addr
);
544 * @brief Flushes an endpoint of the Low Level Driver.
545 * @param pdev: Device handle
546 * @param ep_addr: Endpoint Number
547 * @retval USBD Status
549 USBD_StatusTypeDef
USBD_LL_FlushEP(USBD_HandleTypeDef
*pdev
, uint8_t ep_addr
)
551 HAL_PCD_EP_Flush(pdev
->pData
, ep_addr
);
556 * @brief Sets a Stall condition on an endpoint of the Low Level Driver.
557 * @param pdev: Device handle
558 * @param ep_addr: Endpoint Number
559 * @retval USBD Status
561 USBD_StatusTypeDef
USBD_LL_StallEP(USBD_HandleTypeDef
*pdev
, uint8_t ep_addr
)
563 HAL_PCD_EP_SetStall(pdev
->pData
, ep_addr
);
568 * @brief Clears a Stall condition on an endpoint of the Low Level Driver.
569 * @param pdev: Device handle
570 * @param ep_addr: Endpoint Number
571 * @retval USBD Status
573 USBD_StatusTypeDef
USBD_LL_ClearStallEP(USBD_HandleTypeDef
*pdev
, uint8_t ep_addr
)
575 HAL_PCD_EP_ClrStall(pdev
->pData
, ep_addr
);
580 * @brief Returns Stall condition.
581 * @param pdev: Device handle
582 * @param ep_addr: Endpoint Number
583 * @retval Stall (1: Yes, 0: No)
585 uint8_t USBD_LL_IsStallEP(USBD_HandleTypeDef
*pdev
, uint8_t ep_addr
)
587 PCD_HandleTypeDef
*hpcd
= pdev
->pData
;
589 if ((ep_addr
& 0x80) == 0x80)
591 return hpcd
->IN_ep
[ep_addr
& 0x7F].is_stall
;
595 return hpcd
->OUT_ep
[ep_addr
& 0x7F].is_stall
;
600 * @brief Assigns a USB address to the device.
601 * @param pdev: Device handle
602 * @param ep_addr: Endpoint Number
603 * @retval USBD Status
605 USBD_StatusTypeDef
USBD_LL_SetUSBAddress(USBD_HandleTypeDef
*pdev
, uint8_t dev_addr
)
607 HAL_PCD_SetAddress(pdev
->pData
, dev_addr
);
612 * @brief Transmits data over an endpoint.
613 * @param pdev: Device handle
614 * @param ep_addr: Endpoint Number
615 * @param pbuf: Pointer to data to be sent
616 * @param size: Data size
617 * @retval USBD Status
619 USBD_StatusTypeDef
USBD_LL_Transmit(USBD_HandleTypeDef
*pdev
,
624 HAL_PCD_EP_Transmit(pdev
->pData
, ep_addr
, pbuf
, size
);
629 * @brief Prepares an endpoint for reception.
630 * @param pdev: Device handle
631 * @param ep_addr: Endpoint Number
632 * @param pbuf: Pointer to data to be received
633 * @param size: Data size
634 * @retval USBD Status
636 USBD_StatusTypeDef
USBD_LL_PrepareReceive(USBD_HandleTypeDef
*pdev
,
641 HAL_PCD_EP_Receive(pdev
->pData
, ep_addr
, pbuf
, size
);
646 * @brief Returns the last transferred packet size.
647 * @param pdev: Device handle
648 * @param ep_addr: Endpoint Number
649 * @retval Received Data Size
651 uint32_t USBD_LL_GetRxDataSize(USBD_HandleTypeDef
*pdev
, uint8_t ep_addr
)
653 return HAL_PCD_EP_GetRxCount(pdev
->pData
, ep_addr
);
657 * @brief Delays routine for the USB Device Library.
658 * @param Delay: Delay in ms
661 void USBD_LL_Delay(uint32_t Delay
)
666 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/