2 ******************************************************************************
3 * @file stm32f1xx_hal_pcd.c
4 * @author MCD Application Team
7 * @brief PCD HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the USB Peripheral Controller:
10 * + Initialization and de-initialization functions
11 * + IO operation functions
12 * + Peripheral Control functions
13 * + Peripheral State functions
16 ==============================================================================
17 ##### How to use this driver #####
18 ==============================================================================
20 The PCD HAL driver can be used as follows:
22 (#) Declare a PCD_HandleTypeDef handle structure, for example:
23 PCD_HandleTypeDef hpcd;
25 (#) Fill parameters of Init structure in HCD handle
27 (#) Call HAL_PCD_Init() API to initialize the HCD peripheral (Core, Device core, ...)
29 (#) Initialize the PCD low level resources through the HAL_PCD_MspInit() API:
30 (##) Enable the PCD/USB Low Level interface clock using the following macro
31 (+++) __HAL_RCC_USB_CLK_ENABLE(); For USB Device FS peripheral available
32 on STM32F102xx and STM32F103xx devices
33 (+++) __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); For USB OTG FS peripheral available
34 on STM32F105xx and STM32F107xx devices
36 (##) Initialize the related GPIO clocks
37 (##) Configure PCD pin-out
38 (##) Configure PCD NVIC interrupt
40 (#)Associate the Upper USB device stack to the HAL PCD Driver:
41 (##) hpcd.pData = pdev;
43 (#)Enable HCD transmission and reception:
47 ******************************************************************************
50 * <h2><center>© COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
52 * Redistribution and use in source and binary forms, with or without modification,
53 * are permitted provided that the following conditions are met:
54 * 1. Redistributions of source code must retain the above copyright notice,
55 * this list of conditions and the following disclaimer.
56 * 2. Redistributions in binary form must reproduce the above copyright notice,
57 * this list of conditions and the following disclaimer in the documentation
58 * and/or other materials provided with the distribution.
59 * 3. Neither the name of STMicroelectronics nor the names of its contributors
60 * may be used to endorse or promote products derived from this software
61 * without specific prior written permission.
63 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
64 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
65 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
66 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
67 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
68 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
69 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
70 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
71 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
72 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
74 ******************************************************************************
77 /* Includes ------------------------------------------------------------------*/
78 #include "stm32f1xx_hal.h"
80 /** @addtogroup STM32F1xx_HAL_Driver
86 #ifdef HAL_PCD_MODULE_ENABLED
88 #if defined(STM32F102x6) || defined(STM32F102xB) || \
89 defined(STM32F103x6) || defined(STM32F103xB) || \
90 defined(STM32F103xE) || defined(STM32F103xG) || \
91 defined(STM32F105xC) || defined(STM32F107xC)
94 * @brief PCD HAL module driver
98 /* Private types -------------------------------------------------------------*/
99 /* Private variables ---------------------------------------------------------*/
100 /* Private constants ---------------------------------------------------------*/
101 /* Private macros ------------------------------------------------------------*/
102 /** @defgroup PCD_Private_Macros PCD Private Macros
105 #define PCD_MIN(a, b) (((a) < (b)) ? (a) : (b))
106 #define PCD_MAX(a, b) (((a) > (b)) ? (a) : (b))
111 /* Private functions ---------------------------------------------------------*/
112 /** @defgroup PCD_Private_Functions PCD Private Functions
115 #if defined (USB_OTG_FS)
116 static HAL_StatusTypeDef
PCD_WriteEmptyTxFifo(PCD_HandleTypeDef
*hpcd
, uint32_t epnum
);
117 #endif /* USB_OTG_FS */
120 static HAL_StatusTypeDef
PCD_EP_ISR_Handler(PCD_HandleTypeDef
*hpcd
);
126 /* Exported functions --------------------------------------------------------*/
127 /** @defgroup PCD_Exported_Functions PCD Exported Functions
131 /** @defgroup PCD_Exported_Functions_Group1 Initialization and de-initialization functions
132 * @brief Initialization and Configuration functions
135 ===============================================================================
136 ##### Initialization and de-initialization functions #####
137 ===============================================================================
138 [..] This section provides functions allowing to:
145 * @brief Initializes the PCD according to the specified
146 * parameters in the PCD_InitTypeDef and create the associated handle.
147 * @param hpcd: PCD handle
150 HAL_StatusTypeDef
HAL_PCD_Init(PCD_HandleTypeDef
*hpcd
)
154 /* Check the PCD handle allocation */
160 /* Check the parameters */
161 assert_param(IS_PCD_ALL_INSTANCE(hpcd
->Instance
));
163 if(hpcd
->State
== HAL_PCD_STATE_RESET
)
165 /* Allocate lock resource and initialize it */
166 hpcd
->Lock
= HAL_UNLOCKED
;
168 /* Init the low level hardware : GPIO, CLOCK, NVIC... */
169 HAL_PCD_MspInit(hpcd
);
172 hpcd
->State
= HAL_PCD_STATE_BUSY
;
174 /* Disable the Interrupts */
175 __HAL_PCD_DISABLE(hpcd
);
177 /*Init the Core (common init.) */
178 USB_CoreInit(hpcd
->Instance
, hpcd
->Init
);
180 /* Force Device Mode*/
181 USB_SetCurrentMode(hpcd
->Instance
, USB_DEVICE_MODE
);
183 /* Init endpoints structures */
184 for (index
= 0U; index
< 15U ; index
++)
186 /* Init ep structure */
187 hpcd
->IN_ep
[index
].is_in
= 1U;
188 hpcd
->IN_ep
[index
].num
= index
;
189 hpcd
->IN_ep
[index
].tx_fifo_num
= index
;
190 /* Control until ep is actvated */
191 hpcd
->IN_ep
[index
].type
= EP_TYPE_CTRL
;
192 hpcd
->IN_ep
[index
].maxpacket
= 0U;
193 hpcd
->IN_ep
[index
].xfer_buff
= 0U;
194 hpcd
->IN_ep
[index
].xfer_len
= 0U;
197 for (index
= 0U; index
< 15U ; index
++)
199 hpcd
->OUT_ep
[index
].is_in
= 0U;
200 hpcd
->OUT_ep
[index
].num
= index
;
201 hpcd
->IN_ep
[index
].tx_fifo_num
= index
;
202 /* Control until ep is activated */
203 hpcd
->OUT_ep
[index
].type
= EP_TYPE_CTRL
;
204 hpcd
->OUT_ep
[index
].maxpacket
= 0U;
205 hpcd
->OUT_ep
[index
].xfer_buff
= 0U;
206 hpcd
->OUT_ep
[index
].xfer_len
= 0U;
210 USB_DevInit(hpcd
->Instance
, hpcd
->Init
);
212 hpcd
->USB_Address
= 0U;
213 hpcd
->State
= HAL_PCD_STATE_READY
;
215 USB_DevDisconnect (hpcd
->Instance
);
220 * @brief DeInitializes the PCD peripheral
221 * @param hpcd: PCD handle
224 HAL_StatusTypeDef
HAL_PCD_DeInit(PCD_HandleTypeDef
*hpcd
)
226 /* Check the PCD handle allocation */
232 hpcd
->State
= HAL_PCD_STATE_BUSY
;
237 /* DeInit the low level hardware */
238 HAL_PCD_MspDeInit(hpcd
);
240 hpcd
->State
= HAL_PCD_STATE_RESET
;
246 * @brief Initializes the PCD MSP.
247 * @param hpcd: PCD handle
250 __weak
void HAL_PCD_MspInit(PCD_HandleTypeDef
*hpcd
)
252 /* Prevent unused argument(s) compilation warning */
254 /* NOTE : This function should not be modified, when the callback is needed,
255 the HAL_PCD_MspInit could be implemented in the user file
260 * @brief DeInitializes PCD MSP.
261 * @param hpcd: PCD handle
264 __weak
void HAL_PCD_MspDeInit(PCD_HandleTypeDef
*hpcd
)
266 /* Prevent unused argument(s) compilation warning */
268 /* NOTE : This function should not be modified, when the callback is needed,
269 the HAL_PCD_MspDeInit could be implemented in the user file
277 /** @defgroup PCD_Exported_Functions_Group2 IO operation functions
278 * @brief Data transfers functions
281 ===============================================================================
282 ##### IO operation functions #####
283 ===============================================================================
285 This subsection provides a set of functions allowing to manage the PCD data
293 * @brief Start The USB Device.
294 * @param hpcd: PCD handle
297 HAL_StatusTypeDef
HAL_PCD_Start(PCD_HandleTypeDef
*hpcd
)
300 HAL_PCDEx_SetConnectionState (hpcd
, 1);
301 USB_DevConnect (hpcd
->Instance
);
302 __HAL_PCD_ENABLE(hpcd
);
308 * @brief Stop The USB Device.
309 * @param hpcd: PCD handle
312 HAL_StatusTypeDef
HAL_PCD_Stop(PCD_HandleTypeDef
*hpcd
)
315 __HAL_PCD_DISABLE(hpcd
);
316 USB_StopDevice(hpcd
->Instance
);
317 USB_DevDisconnect (hpcd
->Instance
);
322 #if defined (USB_OTG_FS)
324 * @brief This function handles PCD interrupt request.
325 * @param hpcd: PCD handle
328 void HAL_PCD_IRQHandler(PCD_HandleTypeDef
*hpcd
)
330 USB_OTG_GlobalTypeDef
*USBx
= hpcd
->Instance
;
331 uint32_t index
= 0U, ep_intr
= 0U, epint
= 0U, epnum
= 0U;
332 uint32_t fifoemptymsk
= 0U, temp
= 0U;
333 USB_OTG_EPTypeDef
*ep
= NULL
;
335 /* ensure that we are in device mode */
336 if (USB_GetMode(hpcd
->Instance
) == USB_OTG_MODE_DEVICE
)
338 /* avoid spurious interrupt */
339 if(__HAL_PCD_IS_INVALID_INTERRUPT(hpcd
))
344 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_MMIS
))
346 /* incorrect mode, acknowledge the interrupt */
347 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_OTG_GINTSTS_MMIS
);
350 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_OEPINT
))
354 /* Read in the device interrupt bits */
355 ep_intr
= USB_ReadDevAllOutEpInterrupt(hpcd
->Instance
);
361 epint
= USB_ReadDevOutEPInterrupt(hpcd
->Instance
, epnum
);
363 if(( epint
& USB_OTG_DOEPINT_XFRC
) == USB_OTG_DOEPINT_XFRC
)
365 CLEAR_OUT_EP_INTR(epnum
, USB_OTG_DOEPINT_XFRC
);
367 HAL_PCD_DataOutStageCallback(hpcd
, epnum
);
370 if(( epint
& USB_OTG_DOEPINT_STUP
) == USB_OTG_DOEPINT_STUP
)
372 /* Inform the upper layer that a setup packet is available */
373 HAL_PCD_SetupStageCallback(hpcd
);
374 CLEAR_OUT_EP_INTR(epnum
, USB_OTG_DOEPINT_STUP
);
377 if(( epint
& USB_OTG_DOEPINT_OTEPDIS
) == USB_OTG_DOEPINT_OTEPDIS
)
379 CLEAR_OUT_EP_INTR(epnum
, USB_OTG_DOEPINT_OTEPDIS
);
387 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_IEPINT
))
389 /* Read in the device interrupt bits */
390 ep_intr
= USB_ReadDevAllInEpInterrupt(hpcd
->Instance
);
396 if (ep_intr
& 0x1U
) /* In ITR */
398 epint
= USB_ReadDevInEPInterrupt(hpcd
->Instance
, epnum
);
400 if(( epint
& USB_OTG_DIEPINT_XFRC
) == USB_OTG_DIEPINT_XFRC
)
402 fifoemptymsk
= 0x1U
<< epnum
;
403 USBx_DEVICE
->DIEPEMPMSK
&= ~fifoemptymsk
;
405 CLEAR_IN_EP_INTR(epnum
, USB_OTG_DIEPINT_XFRC
);
407 HAL_PCD_DataInStageCallback(hpcd
, epnum
);
409 if(( epint
& USB_OTG_DIEPINT_TOC
) == USB_OTG_DIEPINT_TOC
)
411 CLEAR_IN_EP_INTR(epnum
, USB_OTG_DIEPINT_TOC
);
413 if(( epint
& USB_OTG_DIEPINT_ITTXFE
) == USB_OTG_DIEPINT_ITTXFE
)
415 CLEAR_IN_EP_INTR(epnum
, USB_OTG_DIEPINT_ITTXFE
);
417 if(( epint
& USB_OTG_DIEPINT_INEPNE
) == USB_OTG_DIEPINT_INEPNE
)
419 CLEAR_IN_EP_INTR(epnum
, USB_OTG_DIEPINT_INEPNE
);
421 if(( epint
& USB_OTG_DIEPINT_EPDISD
) == USB_OTG_DIEPINT_EPDISD
)
423 CLEAR_IN_EP_INTR(epnum
, USB_OTG_DIEPINT_EPDISD
);
425 if(( epint
& USB_OTG_DIEPINT_TXFE
) == USB_OTG_DIEPINT_TXFE
)
427 PCD_WriteEmptyTxFifo(hpcd
, epnum
);
435 /* Handle Resume Interrupt */
436 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_WKUINT
))
438 /* Clear the Remote Wake-up signalling */
439 USBx_DEVICE
->DCTL
&= ~USB_OTG_DCTL_RWUSIG
;
441 HAL_PCD_ResumeCallback(hpcd
);
443 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_OTG_GINTSTS_WKUINT
);
446 /* Handle Suspend Interrupt */
447 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_USBSUSP
))
449 if((USBx_DEVICE
->DSTS
& USB_OTG_DSTS_SUSPSTS
) == USB_OTG_DSTS_SUSPSTS
)
452 HAL_PCD_SuspendCallback(hpcd
);
454 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_OTG_GINTSTS_USBSUSP
);
457 /* Handle Reset Interrupt */
458 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_USBRST
))
460 USBx_DEVICE
->DCTL
&= ~USB_OTG_DCTL_RWUSIG
;
461 USB_FlushTxFifo(hpcd
->Instance
, 0x10U
);
463 for (index
= 0U; index
< hpcd
->Init
.dev_endpoints
; index
++)
465 USBx_INEP(index
)->DIEPINT
= 0xFFU
;
466 USBx_OUTEP(index
)->DOEPINT
= 0xFFU
;
468 USBx_DEVICE
->DAINT
= 0xFFFFFFFFU
;
469 USBx_DEVICE
->DAINTMSK
|= 0x10001U
;
471 USBx_DEVICE
->DOEPMSK
|= (USB_OTG_DOEPMSK_STUPM
| USB_OTG_DOEPMSK_XFRCM
| USB_OTG_DOEPMSK_EPDM
);
472 USBx_DEVICE
->DIEPMSK
|= (USB_OTG_DIEPMSK_TOM
| USB_OTG_DIEPMSK_XFRCM
| USB_OTG_DIEPMSK_EPDM
);
474 /* Set Default Address to 0 */
475 USBx_DEVICE
->DCFG
&= ~USB_OTG_DCFG_DAD
;
477 /* setup EP0 to receive SETUP packets */
478 USB_EP0_OutStart(hpcd
->Instance
, (uint8_t *)hpcd
->Setup
);
480 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_OTG_GINTSTS_USBRST
);
483 /* Handle Enumeration done Interrupt */
484 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_ENUMDNE
))
486 USB_ActivateSetup(hpcd
->Instance
);
487 hpcd
->Instance
->GUSBCFG
&= ~USB_OTG_GUSBCFG_TRDT
;
489 hpcd
->Init
.speed
= USB_OTG_SPEED_FULL
;
490 hpcd
->Init
.ep0_mps
= USB_OTG_FS_MAX_PACKET_SIZE
;
491 hpcd
->Instance
->GUSBCFG
|= (uint32_t)((USBD_FS_TRDT_VALUE
<< 10U) & USB_OTG_GUSBCFG_TRDT
);
493 HAL_PCD_ResetCallback(hpcd
);
495 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_OTG_GINTSTS_ENUMDNE
);
498 /* Handle RxQLevel Interrupt */
499 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_RXFLVL
))
501 USB_MASK_INTERRUPT(hpcd
->Instance
, USB_OTG_GINTSTS_RXFLVL
);
502 temp
= USBx
->GRXSTSP
;
503 ep
= &hpcd
->OUT_ep
[temp
& USB_OTG_GRXSTSP_EPNUM
];
505 if(((temp
& USB_OTG_GRXSTSP_PKTSTS
) >> 17U) == STS_DATA_UPDT
)
507 if((temp
& USB_OTG_GRXSTSP_BCNT
) != 0U)
509 USB_ReadPacket(USBx
, ep
->xfer_buff
, (temp
& USB_OTG_GRXSTSP_BCNT
) >> 4U);
510 ep
->xfer_buff
+= (temp
& USB_OTG_GRXSTSP_BCNT
) >> 4U;
511 ep
->xfer_count
+= (temp
& USB_OTG_GRXSTSP_BCNT
) >> 4U;
514 else if (((temp
& USB_OTG_GRXSTSP_PKTSTS
) >> 17U) == STS_SETUP_UPDT
)
516 USB_ReadPacket(USBx
, (uint8_t *)hpcd
->Setup
, 8U);
517 ep
->xfer_count
+= (temp
& USB_OTG_GRXSTSP_BCNT
) >> 4U;
519 USB_UNMASK_INTERRUPT(hpcd
->Instance
, USB_OTG_GINTSTS_RXFLVL
);
522 /* Handle SOF Interrupt */
523 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_SOF
))
525 HAL_PCD_SOFCallback(hpcd
);
526 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_OTG_GINTSTS_SOF
);
529 /* Handle Incomplete ISO IN Interrupt */
530 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_IISOIXFR
))
532 HAL_PCD_ISOINIncompleteCallback(hpcd
, epnum
);
533 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_OTG_GINTSTS_IISOIXFR
);
536 /* Handle Incomplete ISO OUT Interrupt */
537 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT
))
539 HAL_PCD_ISOOUTIncompleteCallback(hpcd
, epnum
);
540 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT
);
543 /* Handle Connection event Interrupt */
544 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_SRQINT
))
546 HAL_PCD_ConnectCallback(hpcd
);
547 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_OTG_GINTSTS_SRQINT
);
550 /* Handle Disconnection event Interrupt */
551 if(__HAL_PCD_GET_FLAG(hpcd
, USB_OTG_GINTSTS_OTGINT
))
553 temp
= hpcd
->Instance
->GOTGINT
;
555 if((temp
& USB_OTG_GOTGINT_SEDET
) == USB_OTG_GOTGINT_SEDET
)
557 HAL_PCD_DisconnectCallback(hpcd
);
559 hpcd
->Instance
->GOTGINT
|= temp
;
563 #endif /* USB_OTG_FS */
567 * @brief This function handles PCD interrupt request.
568 * @param hpcd: PCD handle
571 void HAL_PCD_IRQHandler(PCD_HandleTypeDef
*hpcd
)
573 if (__HAL_PCD_GET_FLAG (hpcd
, USB_ISTR_CTR
))
575 /* servicing of the endpoint correct transfer interrupt */
576 /* clear of the CTR flag into the sub */
577 PCD_EP_ISR_Handler(hpcd
);
580 if (__HAL_PCD_GET_FLAG (hpcd
, USB_ISTR_RESET
))
582 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_ISTR_RESET
);
583 HAL_PCD_ResetCallback(hpcd
);
584 HAL_PCD_SetAddress(hpcd
, 0U);
587 if (__HAL_PCD_GET_FLAG (hpcd
, USB_ISTR_PMAOVR
))
589 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_ISTR_PMAOVR
);
591 if (__HAL_PCD_GET_FLAG (hpcd
, USB_ISTR_ERR
))
593 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_ISTR_ERR
);
596 if (__HAL_PCD_GET_FLAG (hpcd
, USB_ISTR_WKUP
))
598 hpcd
->Instance
->CNTR
&= ~(USB_CNTR_LP_MODE
);
599 hpcd
->Instance
->CNTR
&= ~(USB_CNTR_FSUSP
);
601 HAL_PCD_ResumeCallback(hpcd
);
603 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_ISTR_WKUP
);
606 if (__HAL_PCD_GET_FLAG (hpcd
, USB_ISTR_SUSP
))
608 /* Force low-power mode in the macrocell */
609 hpcd
->Instance
->CNTR
|= USB_CNTR_FSUSP
;
611 /* clear of the ISTR bit must be done after setting of CNTR_FSUSP */
612 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_ISTR_SUSP
);
614 hpcd
->Instance
->CNTR
|= USB_CNTR_LP_MODE
;
615 if (__HAL_PCD_GET_FLAG (hpcd
, USB_ISTR_WKUP
) == 0U)
617 HAL_PCD_SuspendCallback(hpcd
);
621 if (__HAL_PCD_GET_FLAG (hpcd
, USB_ISTR_SOF
))
623 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_ISTR_SOF
);
624 HAL_PCD_SOFCallback(hpcd
);
627 if (__HAL_PCD_GET_FLAG (hpcd
, USB_ISTR_ESOF
))
629 /* clear ESOF flag in ISTR */
630 __HAL_PCD_CLEAR_FLAG(hpcd
, USB_ISTR_ESOF
);
636 * @brief Data out stage callbacks
637 * @param hpcd: PCD handle
638 * @param epnum: endpoint number
641 __weak
void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef
*hpcd
, uint8_t epnum
)
643 /* Prevent unused argument(s) compilation warning */
646 /* NOTE : This function should not be modified, when the callback is needed,
647 the HAL_PCD_DataOutStageCallback could be implemented in the user file
652 * @brief Data IN stage callbacks
653 * @param hpcd: PCD handle
654 * @param epnum: endpoint number
657 __weak
void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef
*hpcd
, uint8_t epnum
)
659 /* Prevent unused argument(s) compilation warning */
662 /* NOTE : This function should not be modified, when the callback is needed,
663 the HAL_PCD_DataInStageCallback could be implemented in the user file
667 * @brief Setup stage callback
668 * @param hpcd: PCD handle
671 __weak
void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef
*hpcd
)
673 /* Prevent unused argument(s) compilation warning */
675 /* NOTE : This function should not be modified, when the callback is needed,
676 the HAL_PCD_SetupStageCallback could be implemented in the user file
681 * @brief USB Start Of Frame callbacks
682 * @param hpcd: PCD handle
685 __weak
void HAL_PCD_SOFCallback(PCD_HandleTypeDef
*hpcd
)
687 /* Prevent unused argument(s) compilation warning */
689 /* NOTE : This function should not be modified, when the callback is needed,
690 the HAL_PCD_SOFCallback could be implemented in the user file
695 * @brief USB Reset callbacks
696 * @param hpcd: PCD handle
699 __weak
void HAL_PCD_ResetCallback(PCD_HandleTypeDef
*hpcd
)
701 /* Prevent unused argument(s) compilation warning */
703 /* NOTE : This function should not be modified, when the callback is needed,
704 the HAL_PCD_ResetCallback could be implemented in the user file
709 * @brief Suspend event callbacks
710 * @param hpcd: PCD handle
713 __weak
void HAL_PCD_SuspendCallback(PCD_HandleTypeDef
*hpcd
)
715 /* Prevent unused argument(s) compilation warning */
717 /* NOTE : This function should not be modified, when the callback is needed,
718 the HAL_PCD_SuspendCallback could be implemented in the user file
723 * @brief Resume event callbacks
724 * @param hpcd: PCD handle
727 __weak
void HAL_PCD_ResumeCallback(PCD_HandleTypeDef
*hpcd
)
729 /* Prevent unused argument(s) compilation warning */
731 /* NOTE : This function should not be modified, when the callback is needed,
732 the HAL_PCD_ResumeCallback could be implemented in the user file
737 * @brief Incomplete ISO OUT callbacks
738 * @param hpcd: PCD handle
739 * @param epnum: endpoint number
742 __weak
void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef
*hpcd
, uint8_t epnum
)
744 /* Prevent unused argument(s) compilation warning */
747 /* NOTE : This function should not be modified, when the callback is needed,
748 the HAL_PCD_ISOOUTIncompleteCallback could be implemented in the user file
753 * @brief Incomplete ISO IN callbacks
754 * @param hpcd: PCD handle
755 * @param epnum: endpoint number
758 __weak
void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef
*hpcd
, uint8_t epnum
)
760 /* Prevent unused argument(s) compilation warning */
763 /* NOTE : This function should not be modified, when the callback is needed,
764 the HAL_PCD_ISOINIncompleteCallback could be implemented in the user file
769 * @brief Connection event callbacks
770 * @param hpcd: PCD handle
773 __weak
void HAL_PCD_ConnectCallback(PCD_HandleTypeDef
*hpcd
)
775 /* Prevent unused argument(s) compilation warning */
777 /* NOTE : This function should not be modified, when the callback is needed,
778 the HAL_PCD_ConnectCallback could be implemented in the user file
783 * @brief Disconnection event callbacks
784 * @param hpcd: PCD handle
787 __weak
void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef
*hpcd
)
789 /* Prevent unused argument(s) compilation warning */
791 /* NOTE : This function should not be modified, when the callback is needed,
792 the HAL_PCD_DisconnectCallback could be implemented in the user file
800 /** @defgroup PCD_Exported_Functions_Group3 Peripheral Control functions
801 * @brief management functions
804 ===============================================================================
805 ##### Peripheral Control functions #####
806 ===============================================================================
808 This subsection provides a set of functions allowing to control the PCD data
816 * @brief Connect the USB device
817 * @param hpcd: PCD handle
820 HAL_StatusTypeDef
HAL_PCD_DevConnect(PCD_HandleTypeDef
*hpcd
)
823 HAL_PCDEx_SetConnectionState (hpcd
, 1);
824 USB_DevConnect(hpcd
->Instance
);
830 * @brief Disconnect the USB device
831 * @param hpcd: PCD handle
834 HAL_StatusTypeDef
HAL_PCD_DevDisconnect(PCD_HandleTypeDef
*hpcd
)
837 HAL_PCDEx_SetConnectionState (hpcd
, 0U);
838 USB_DevDisconnect(hpcd
->Instance
);
844 * @brief Set the USB Device address
845 * @param hpcd: PCD handle
846 * @param address: new device address
849 HAL_StatusTypeDef
HAL_PCD_SetAddress(PCD_HandleTypeDef
*hpcd
, uint8_t address
)
852 hpcd
->USB_Address
= address
;
853 USB_SetDevAddress(hpcd
->Instance
, address
);
858 * @brief Open and configure an endpoint
859 * @param hpcd: PCD handle
860 * @param ep_addr: endpoint address
861 * @param ep_mps: endpoint max packet size
862 * @param ep_type: endpoint type
865 HAL_StatusTypeDef
HAL_PCD_EP_Open(PCD_HandleTypeDef
*hpcd
, uint8_t ep_addr
, uint16_t ep_mps
, uint8_t ep_type
)
867 HAL_StatusTypeDef ret
= HAL_OK
;
868 PCD_EPTypeDef
*ep
= NULL
;
870 if ((ep_addr
& 0x80U
) == 0x80U
)
872 ep
= &hpcd
->IN_ep
[ep_addr
& 0x7FU
];
876 ep
= &hpcd
->OUT_ep
[ep_addr
& 0x7FU
];
878 ep
->num
= ep_addr
& 0x7FU
;
880 ep
->is_in
= (0x80U
& ep_addr
) != 0U;
881 ep
->maxpacket
= ep_mps
;
885 USB_ActivateEndpoint(hpcd
->Instance
, ep
);
891 * @brief Deactivate an endpoint
892 * @param hpcd: PCD handle
893 * @param ep_addr: endpoint address
896 HAL_StatusTypeDef
HAL_PCD_EP_Close(PCD_HandleTypeDef
*hpcd
, uint8_t ep_addr
)
898 PCD_EPTypeDef
*ep
= NULL
;
900 if ((ep_addr
& 0x80U
) == 0x80U
)
902 ep
= &hpcd
->IN_ep
[ep_addr
& 0x7FU
];
906 ep
= &hpcd
->OUT_ep
[ep_addr
& 0x7FU
];
908 ep
->num
= ep_addr
& 0x7FU
;
910 ep
->is_in
= (0x80U
& ep_addr
) != 0U;
913 USB_DeactivateEndpoint(hpcd
->Instance
, ep
);
920 * @brief Receive an amount of data
921 * @param hpcd: PCD handle
922 * @param ep_addr: endpoint address
923 * @param pBuf: pointer to the reception buffer
924 * @param len: amount of data to be received
927 HAL_StatusTypeDef
HAL_PCD_EP_Receive(PCD_HandleTypeDef
*hpcd
, uint8_t ep_addr
, uint8_t *pBuf
, uint32_t len
)
929 PCD_EPTypeDef
*ep
= NULL
;
931 ep
= &hpcd
->OUT_ep
[ep_addr
& 0x7FU
];
933 /*setup and start the Xfer */
934 ep
->xfer_buff
= pBuf
;
938 ep
->num
= ep_addr
& 0x7FU
;
940 if ((ep_addr
& 0x7FU
) == 0U)
942 USB_EP0StartXfer(hpcd
->Instance
, ep
);
946 USB_EPStartXfer(hpcd
->Instance
, ep
);
953 * @brief Get Received Data Size
954 * @param hpcd: PCD handle
955 * @param ep_addr: endpoint address
958 uint16_t HAL_PCD_EP_GetRxCount(PCD_HandleTypeDef
*hpcd
, uint8_t ep_addr
)
960 return hpcd
->OUT_ep
[ep_addr
& 0xF].xfer_count
;
963 * @brief Send an amount of data
964 * @param hpcd: PCD handle
965 * @param ep_addr: endpoint address
966 * @param pBuf: pointer to the transmission buffer
967 * @param len: amount of data to be sent
970 HAL_StatusTypeDef
HAL_PCD_EP_Transmit(PCD_HandleTypeDef
*hpcd
, uint8_t ep_addr
, uint8_t *pBuf
, uint32_t len
)
972 PCD_EPTypeDef
*ep
= NULL
;
974 ep
= &hpcd
->IN_ep
[ep_addr
& 0x7FU
];
976 /*setup and start the Xfer */
977 ep
->xfer_buff
= pBuf
;
981 ep
->num
= ep_addr
& 0x7FU
;
983 if ((ep_addr
& 0x7FU
) == 0U)
985 USB_EP0StartXfer(hpcd
->Instance
, ep
);
989 USB_EPStartXfer(hpcd
->Instance
, ep
);
996 * @brief Set a STALL condition over an endpoint
997 * @param hpcd: PCD handle
998 * @param ep_addr: endpoint address
1001 HAL_StatusTypeDef
HAL_PCD_EP_SetStall(PCD_HandleTypeDef
*hpcd
, uint8_t ep_addr
)
1003 PCD_EPTypeDef
*ep
= NULL
;
1005 if ((0x80U
& ep_addr
) == 0x80U
)
1007 ep
= &hpcd
->IN_ep
[ep_addr
& 0x7FU
];
1011 ep
= &hpcd
->OUT_ep
[ep_addr
];
1015 ep
->num
= ep_addr
& 0x7FU
;
1016 ep
->is_in
= ((ep_addr
& 0x80U
) == 0x80U
);
1019 USB_EPSetStall(hpcd
->Instance
, ep
);
1020 if((ep_addr
& 0x7FU
) == 0U)
1022 USB_EP0_OutStart(hpcd
->Instance
, (uint8_t *)hpcd
->Setup
);
1030 * @brief Clear a STALL condition over in an endpoint
1031 * @param hpcd: PCD handle
1032 * @param ep_addr: endpoint address
1033 * @retval HAL status
1035 HAL_StatusTypeDef
HAL_PCD_EP_ClrStall(PCD_HandleTypeDef
*hpcd
, uint8_t ep_addr
)
1037 PCD_EPTypeDef
*ep
= NULL
;
1039 if ((0x80U
& ep_addr
) == 0x80U
)
1041 ep
= &hpcd
->IN_ep
[ep_addr
& 0x7FU
];
1045 ep
= &hpcd
->OUT_ep
[ep_addr
];
1049 ep
->num
= ep_addr
& 0x7FU
;
1050 ep
->is_in
= ((ep_addr
& 0x80U
) == 0x80U
);
1053 USB_EPClearStall(hpcd
->Instance
, ep
);
1060 * @brief Flush an endpoint
1061 * @param hpcd: PCD handle
1062 * @param ep_addr: endpoint address
1063 * @retval HAL status
1065 HAL_StatusTypeDef
HAL_PCD_EP_Flush(PCD_HandleTypeDef
*hpcd
, uint8_t ep_addr
)
1069 if ((ep_addr
& 0x80U
) == 0x80U
)
1071 USB_FlushTxFifo(hpcd
->Instance
, ep_addr
& 0x7FU
);
1075 USB_FlushRxFifo(hpcd
->Instance
);
1084 * @brief HAL_PCD_ActivateRemoteWakeup : active remote wakeup signalling
1085 * @param hpcd: PCD handle
1086 * @retval HAL status
1088 HAL_StatusTypeDef
HAL_PCD_ActivateRemoteWakeup(PCD_HandleTypeDef
*hpcd
)
1090 return(USB_ActivateRemoteWakeup(hpcd
->Instance
));
1094 * @brief HAL_PCD_DeActivateRemoteWakeup : de-active remote wakeup signalling
1095 * @param hpcd: PCD handle
1096 * @retval HAL status
1098 HAL_StatusTypeDef
HAL_PCD_DeActivateRemoteWakeup(PCD_HandleTypeDef
*hpcd
)
1100 return(USB_DeActivateRemoteWakeup(hpcd
->Instance
));
1106 /** @defgroup PCD_Exported_Functions_Group4 Peripheral State functions
1107 * @brief Peripheral State functions
1110 ===============================================================================
1111 ##### Peripheral State functions #####
1112 ===============================================================================
1114 This subsection permits to get in run-time the status of the peripheral
1122 * @brief Return the PCD state
1123 * @param hpcd: PCD handle
1126 PCD_StateTypeDef
HAL_PCD_GetState(PCD_HandleTypeDef
*hpcd
)
1139 /** @addtogroup PCD_Private_Functions
1142 #if defined (USB_OTG_FS)
1144 * @brief DCD_WriteEmptyTxFifo
1145 * check FIFO for the next packet to be loaded
1146 * @param hpcd: PCD handle
1147 * @param epnum : endpoint number
1148 * This parameter can be a value from 0 to 15
1149 * @retval HAL status
1151 static HAL_StatusTypeDef
PCD_WriteEmptyTxFifo(PCD_HandleTypeDef
*hpcd
, uint32_t epnum
)
1153 USB_OTG_GlobalTypeDef
*USBx
= hpcd
->Instance
;
1154 USB_OTG_EPTypeDef
*ep
= NULL
;
1156 uint32_t len32b
= 0U;
1157 uint32_t fifoemptymsk
= 0U;
1159 ep
= &hpcd
->IN_ep
[epnum
];
1160 len
= ep
->xfer_len
- ep
->xfer_count
;
1162 if (len
> ep
->maxpacket
)
1164 len
= ep
->maxpacket
;
1167 len32b
= (len
+ 3U) / 4U;
1169 while ((USBx_INEP(epnum
)->DTXFSTS
& USB_OTG_DTXFSTS_INEPTFSAV
) > len32b
&&
1170 ep
->xfer_count
< ep
->xfer_len
&&
1173 /* Write the FIFO */
1174 len
= ep
->xfer_len
- ep
->xfer_count
;
1176 if ((uint32_t)len
> ep
->maxpacket
)
1178 len
= ep
->maxpacket
;
1180 len32b
= (len
+ 3U) / 4U;
1182 USB_WritePacket(USBx
, ep
->xfer_buff
, epnum
, len
);
1184 ep
->xfer_buff
+= len
;
1185 ep
->xfer_count
+= len
;
1190 fifoemptymsk
= 0x01U
<< epnum
;
1191 USBx_DEVICE
->DIEPEMPMSK
&= ~fifoemptymsk
;
1197 #endif /* USB_OTG_FS */
1201 * @brief This function handles PCD Endpoint interrupt request.
1202 * @param hpcd: PCD handle
1203 * @retval HAL status
1205 static HAL_StatusTypeDef
PCD_EP_ISR_Handler(PCD_HandleTypeDef
*hpcd
)
1207 PCD_EPTypeDef
*ep
= NULL
;
1209 uint8_t epindex
= 0;
1210 __IO
uint16_t wIstr
= 0;
1211 __IO
uint16_t wEPVal
= 0;
1213 /* stay in loop while pending interrupts */
1214 while (((wIstr
= hpcd
->Instance
->ISTR
) & USB_ISTR_CTR
) != 0)
1216 /* extract highest priority endpoint number */
1217 epindex
= (uint8_t)(wIstr
& USB_ISTR_EP_ID
);
1221 /* Decode and service control endpoint interrupt */
1223 /* DIR bit = origin of the interrupt */
1224 if ((wIstr
& USB_ISTR_DIR
) == 0)
1228 /* DIR = 0 => IN int */
1229 /* DIR = 0 implies that (EP_CTR_TX = 1) always */
1230 PCD_CLEAR_TX_EP_CTR(hpcd
->Instance
, PCD_ENDP0
);
1231 ep
= &hpcd
->IN_ep
[0];
1233 ep
->xfer_count
= PCD_GET_EP_TX_CNT(hpcd
->Instance
, ep
->num
);
1234 ep
->xfer_buff
+= ep
->xfer_count
;
1237 HAL_PCD_DataInStageCallback(hpcd
, 0U);
1240 if((hpcd
->USB_Address
> 0U)&& ( ep
->xfer_len
== 0U))
1242 hpcd
->Instance
->DADDR
= (hpcd
->USB_Address
| USB_DADDR_EF
);
1243 hpcd
->USB_Address
= 0U;
1251 /* DIR = 1 & CTR_RX => SETUP or OUT int */
1252 /* DIR = 1 & (CTR_TX | CTR_RX) => 2 int pending */
1253 ep
= &hpcd
->OUT_ep
[0U];
1254 wEPVal
= PCD_GET_ENDPOINT(hpcd
->Instance
, PCD_ENDP0
);
1256 if ((wEPVal
& USB_EP_SETUP
) != 0U)
1258 /* Get SETUP Packet*/
1259 ep
->xfer_count
= PCD_GET_EP_RX_CNT(hpcd
->Instance
, ep
->num
);
1260 USB_ReadPMA(hpcd
->Instance
, (uint8_t*)hpcd
->Setup
,ep
->pmaadress
, ep
->xfer_count
);
1261 /* SETUP bit kept frozen while CTR_RX = 1*/
1262 PCD_CLEAR_RX_EP_CTR(hpcd
->Instance
, PCD_ENDP0
);
1264 /* Process SETUP Packet*/
1265 HAL_PCD_SetupStageCallback(hpcd
);
1268 else if ((wEPVal
& USB_EP_CTR_RX
) != 0U)
1270 PCD_CLEAR_RX_EP_CTR(hpcd
->Instance
, PCD_ENDP0
);
1271 /* Get Control Data OUT Packet*/
1272 ep
->xfer_count
= PCD_GET_EP_RX_CNT(hpcd
->Instance
, ep
->num
);
1274 if (ep
->xfer_count
!= 0U)
1276 USB_ReadPMA(hpcd
->Instance
, ep
->xfer_buff
, ep
->pmaadress
, ep
->xfer_count
);
1277 ep
->xfer_buff
+=ep
->xfer_count
;
1280 /* Process Control Data OUT Packet*/
1281 HAL_PCD_DataOutStageCallback(hpcd
, 0U);
1283 PCD_SET_EP_RX_CNT(hpcd
->Instance
, PCD_ENDP0
, ep
->maxpacket
);
1284 PCD_SET_EP_RX_STATUS(hpcd
->Instance
, PCD_ENDP0
, USB_EP_RX_VALID
);
1290 /* Decode and service non control endpoints interrupt */
1292 /* process related endpoint register */
1293 wEPVal
= PCD_GET_ENDPOINT(hpcd
->Instance
, epindex
);
1294 if ((wEPVal
& USB_EP_CTR_RX
) != 0U)
1296 /* clear int flag */
1297 PCD_CLEAR_RX_EP_CTR(hpcd
->Instance
, epindex
);
1298 ep
= &hpcd
->OUT_ep
[epindex
];
1300 /* OUT double Buffering*/
1301 if (ep
->doublebuffer
== 0U)
1303 count
= PCD_GET_EP_RX_CNT(hpcd
->Instance
, ep
->num
);
1306 USB_ReadPMA(hpcd
->Instance
, ep
->xfer_buff
, ep
->pmaadress
, count
);
1311 if (PCD_GET_ENDPOINT(hpcd
->Instance
, ep
->num
) & USB_EP_DTOG_RX
)
1313 /*read from endpoint BUF0Addr buffer*/
1314 count
= PCD_GET_EP_DBUF0_CNT(hpcd
->Instance
, ep
->num
);
1317 USB_ReadPMA(hpcd
->Instance
, ep
->xfer_buff
, ep
->pmaaddr0
, count
);
1322 /*read from endpoint BUF1Addr buffer*/
1323 count
= PCD_GET_EP_DBUF1_CNT(hpcd
->Instance
, ep
->num
);
1326 USB_ReadPMA(hpcd
->Instance
, ep
->xfer_buff
, ep
->pmaaddr1
, count
);
1329 PCD_FreeUserBuffer(hpcd
->Instance
, ep
->num
, PCD_EP_DBUF_OUT
);
1331 /*multi-packet on the NON control OUT endpoint*/
1332 ep
->xfer_count
+=count
;
1333 ep
->xfer_buff
+=count
;
1335 if ((ep
->xfer_len
== 0U) || (count
< ep
->maxpacket
))
1338 HAL_PCD_DataOutStageCallback(hpcd
, ep
->num
);
1342 HAL_PCD_EP_Receive(hpcd
, ep
->num
, ep
->xfer_buff
, ep
->xfer_len
);
1345 } /* if((wEPVal & EP_CTR_RX) */
1347 if ((wEPVal
& USB_EP_CTR_TX
) != 0U)
1349 ep
= &hpcd
->IN_ep
[epindex
];
1351 /* clear int flag */
1352 PCD_CLEAR_TX_EP_CTR(hpcd
->Instance
, epindex
);
1354 /* IN double Buffering*/
1355 if (ep
->doublebuffer
== 0U)
1357 ep
->xfer_count
= PCD_GET_EP_TX_CNT(hpcd
->Instance
, ep
->num
);
1358 if (ep
->xfer_count
!= 0U)
1360 USB_WritePMA(hpcd
->Instance
, ep
->xfer_buff
, ep
->pmaadress
, ep
->xfer_count
);
1365 if (PCD_GET_ENDPOINT(hpcd
->Instance
, ep
->num
) & USB_EP_DTOG_TX
)
1367 /*read from endpoint BUF0Addr buffer*/
1368 ep
->xfer_count
= PCD_GET_EP_DBUF0_CNT(hpcd
->Instance
, ep
->num
);
1369 if (ep
->xfer_count
!= 0U)
1371 USB_WritePMA(hpcd
->Instance
, ep
->xfer_buff
, ep
->pmaaddr0
, ep
->xfer_count
);
1376 /*read from endpoint BUF1Addr buffer*/
1377 ep
->xfer_count
= PCD_GET_EP_DBUF1_CNT(hpcd
->Instance
, ep
->num
);
1378 if (ep
->xfer_count
!= 0U)
1380 USB_WritePMA(hpcd
->Instance
, ep
->xfer_buff
, ep
->pmaaddr1
, ep
->xfer_count
);
1383 PCD_FreeUserBuffer(hpcd
->Instance
, ep
->num
, PCD_EP_DBUF_IN
);
1385 /*multi-packet on the NON control IN endpoint*/
1386 ep
->xfer_count
= PCD_GET_EP_TX_CNT(hpcd
->Instance
, ep
->num
);
1387 ep
->xfer_buff
+=ep
->xfer_count
;
1389 /* Zero Length Packet? */
1390 if (ep
->xfer_len
== 0U)
1393 HAL_PCD_DataInStageCallback(hpcd
, ep
->num
);
1397 HAL_PCD_EP_Transmit(hpcd
, ep
->num
, ep
->xfer_buff
, ep
->xfer_len
);
1414 #endif /* STM32F102x6 || STM32F102xB || */
1415 /* STM32F103x6 || STM32F103xB || */
1416 /* STM32F103xE || STM32F103xG || */
1417 /* STM32F105xC || STM32F107xC */
1419 #endif /* HAL_PCD_MODULE_ENABLED */
1426 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/