Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Src / stm32f3xx_hal_pcd.c
blobccad29abaac6d41feadf35fcdd24d25c20cbd33f
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_hal_pcd.c
4 * @author MCD Application Team
5 * @brief PCD HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the USB Peripheral Controller:
8 * + Initialization and de-initialization functions
9 * + IO operation functions
10 * + Peripheral Control functions
11 * + Peripheral State functions
13 @verbatim
14 ==============================================================================
15 ##### How to use this driver #####
16 ==============================================================================
17 [..]
18 The PCD HAL driver can be used as follows:
20 (#) Declare a PCD_HandleTypeDef handle structure, for example:
21 PCD_HandleTypeDef hpcd;
23 (#) Fill parameters of Init structure in HCD handle
25 (#) Call HAL_PCD_Init() API to initialize the HCD peripheral (Core, Device core, ...)
27 (#) Initialize the PCD low level resources through the HAL_PCD_MspInit() API:
28 (##) Enable the PCD/USB Low Level interface clock using
29 (+++) __HAL_RCC_USB_CLK_ENABLE();
31 (##) Initialize the related GPIO clocks
32 (##) Configure PCD pin-out
33 (##) Configure PCD NVIC interrupt
35 (#)Associate the Upper USB device stack to the HAL PCD Driver:
36 (##) hpcd.pData = pdev;
38 (#)Enable HCD transmission and reception:
39 (##) HAL_PCD_Start();
41 @endverbatim
42 ******************************************************************************
43 * @attention
45 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
47 * Redistribution and use in source and binary forms, with or without modification,
48 * are permitted provided that the following conditions are met:
49 * 1. Redistributions of source code must retain the above copyright notice,
50 * this list of conditions and the following disclaimer.
51 * 2. Redistributions in binary form must reproduce the above copyright notice,
52 * this list of conditions and the following disclaimer in the documentation
53 * and/or other materials provided with the distribution.
54 * 3. Neither the name of STMicroelectronics nor the names of its contributors
55 * may be used to endorse or promote products derived from this software
56 * without specific prior written permission.
58 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
59 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
60 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
61 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
62 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
63 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
64 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
65 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
66 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
67 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
69 ******************************************************************************
72 /* Includes ------------------------------------------------------------------*/
73 #include "stm32f3xx_hal.h"
75 #ifdef HAL_PCD_MODULE_ENABLED
77 #if defined(STM32F302xE) || defined(STM32F303xE) || \
78 defined(STM32F302xC) || defined(STM32F303xC) || \
79 defined(STM32F302x8) || \
80 defined(STM32F373xC)
82 /** @addtogroup STM32F3xx_HAL_Driver
83 * @{
86 /** @defgroup PCD PCD
87 * @brief PCD HAL module driver
88 * @{
91 /* Private typedef -----------------------------------------------------------*/
92 /* Private define ------------------------------------------------------------*/
94 /** @defgroup PCD_Private_Define PCD Private Define
95 * @{
97 #define BTABLE_ADDRESS (0x000U)
98 /**
99 * @}
102 /* Private macro -------------------------------------------------------------*/
103 /* Private variables ---------------------------------------------------------*/
104 /* Private function prototypes -----------------------------------------------*/
105 /** @defgroup PCD_Private_Functions PCD Private Functions
106 * @{
108 static HAL_StatusTypeDef PCD_EP_ISR_Handler(PCD_HandleTypeDef *hpcd);
110 * @}
113 /* Exported functions ---------------------------------------------------------*/
115 /** @defgroup PCD_Exported_Functions PCD Exported Functions
116 * @{
119 /** @defgroup PCD_Exported_Functions_Group1 Initialization and de-initialization functions
120 * @brief Initialization and Configuration functions
122 @verbatim
123 ===============================================================================
124 ##### Initialization and de-initialization functions #####
125 ===============================================================================
126 [..] This section provides functions allowing to:
128 @endverbatim
129 * @{
133 * @brief Initializes the PCD according to the specified
134 * parameters in the PCD_InitTypeDef and create the associated handle.
135 * @param hpcd PCD handle
136 * @retval HAL status
138 HAL_StatusTypeDef HAL_PCD_Init(PCD_HandleTypeDef *hpcd)
140 uint32_t i = 0U;
142 uint32_t wInterrupt_Mask = 0U;
144 /* Check the PCD handle allocation */
145 if(hpcd == NULL)
147 return HAL_ERROR;
150 /* Check the parameters */
151 assert_param(IS_PCD_ALL_INSTANCE(hpcd->Instance));
153 if(hpcd->State == HAL_PCD_STATE_RESET)
155 /* Allocate lock resource and initialize it */
156 hpcd->Lock = HAL_UNLOCKED;
158 /* Init the low level hardware : GPIO, CLOCK, NVIC... */
159 HAL_PCD_MspInit(hpcd);
162 hpcd->State = HAL_PCD_STATE_BUSY;
164 /* Init endpoints structures */
165 for (i = 0U; i < hpcd->Init.dev_endpoints ; i++)
167 /* Init ep structure */
168 hpcd->IN_ep[i].is_in = 1U;
169 hpcd->IN_ep[i].num = i;
170 /* Control until ep is actvated */
171 hpcd->IN_ep[i].type = PCD_EP_TYPE_CTRL;
172 hpcd->IN_ep[i].maxpacket = 0U;
173 hpcd->IN_ep[i].xfer_buff = 0U;
174 hpcd->IN_ep[i].xfer_len = 0U;
177 for (i = 0U; i < hpcd->Init.dev_endpoints ; i++)
179 hpcd->OUT_ep[i].is_in = 0U;
180 hpcd->OUT_ep[i].num = i;
181 /* Control until ep is activated */
182 hpcd->OUT_ep[i].type = PCD_EP_TYPE_CTRL;
183 hpcd->OUT_ep[i].maxpacket = 0U;
184 hpcd->OUT_ep[i].xfer_buff = 0U;
185 hpcd->OUT_ep[i].xfer_len = 0U;
188 /* Init Device */
189 /*CNTR_FRES = 1U*/
190 hpcd->Instance->CNTR = USB_CNTR_FRES;
192 /*CNTR_FRES = 0U*/
193 hpcd->Instance->CNTR = 0U;
195 /*Clear pending interrupts*/
196 hpcd->Instance->ISTR = 0U;
198 /*Set Btable Adress*/
199 hpcd->Instance->BTABLE = BTABLE_ADDRESS;
201 /*set wInterrupt_Mask global variable*/
202 wInterrupt_Mask = USB_CNTR_CTRM | USB_CNTR_WKUPM | USB_CNTR_SUSPM | USB_CNTR_ERRM \
203 | USB_CNTR_SOFM | USB_CNTR_ESOFM | USB_CNTR_RESETM;
205 /*Set interrupt mask*/
206 hpcd->Instance->CNTR = wInterrupt_Mask;
208 hpcd->USB_Address = 0U;
209 hpcd->State= HAL_PCD_STATE_READY;
211 return HAL_OK;
215 * @brief DeInitializes the PCD peripheral
216 * @param hpcd PCD handle
217 * @retval HAL status
219 HAL_StatusTypeDef HAL_PCD_DeInit(PCD_HandleTypeDef *hpcd)
221 /* Check the PCD handle allocation */
222 if(hpcd == NULL)
224 return HAL_ERROR;
227 hpcd->State = HAL_PCD_STATE_BUSY;
229 /* Stop Device */
230 HAL_PCD_Stop(hpcd);
232 /* DeInit the low level hardware */
233 HAL_PCD_MspDeInit(hpcd);
235 hpcd->State = HAL_PCD_STATE_RESET;
237 return HAL_OK;
241 * @brief Initializes the PCD MSP.
242 * @param hpcd PCD handle
243 * @retval None
245 __weak void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
247 /* Prevent unused argument(s) compilation warning */
248 UNUSED(hpcd);
250 /* NOTE : This function should not be modified, when the callback is needed,
251 the HAL_PCD_MspInit could be implemented in the user file
256 * @brief DeInitializes PCD MSP.
257 * @param hpcd PCD handle
258 * @retval None
260 __weak void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd)
262 /* Prevent unused argument(s) compilation warning */
263 UNUSED(hpcd);
265 /* NOTE : This function should not be modified, when the callback is needed,
266 the HAL_PCD_MspDeInit could be implemented in the user file
271 * @}
274 /** @defgroup PCD_Exported_Functions_Group2 IO operation functions
275 * @brief Data transfers functions
277 @verbatim
278 ===============================================================================
279 ##### IO operation functions #####
280 ===============================================================================
281 [..]
282 This subsection provides a set of functions allowing to manage the PCD data
283 transfers.
285 @endverbatim
286 * @{
290 * @brief Start the USB device.
291 * @param hpcd PCD handle
292 * @retval HAL status
294 HAL_StatusTypeDef HAL_PCD_Start(PCD_HandleTypeDef *hpcd)
296 /* DP Pull-Down is external */
297 HAL_PCDEx_SetConnectionState (hpcd, 1U);
299 return HAL_OK;
303 * @brief Stop the USB device.
304 * @param hpcd PCD handle
305 * @retval HAL status
307 HAL_StatusTypeDef HAL_PCD_Stop(PCD_HandleTypeDef *hpcd)
309 __HAL_LOCK(hpcd);
311 /* disable all interrupts and force USB reset */
312 hpcd->Instance->CNTR = USB_CNTR_FRES;
314 /* clear interrupt status register */
315 hpcd->Instance->ISTR = 0U;
317 /* switch-off device */
318 hpcd->Instance->CNTR = (USB_CNTR_FRES | USB_CNTR_PDWN);
320 __HAL_UNLOCK(hpcd);
321 return HAL_OK;
324 * @}
328 * @}
331 /** @addtogroup PCD_Private_Functions PCD Private Functions
332 * @{
335 * @brief This function handles PCD Endpoint interrupt request.
336 * @param hpcd PCD handle
337 * @retval HAL status
339 static HAL_StatusTypeDef PCD_EP_ISR_Handler(PCD_HandleTypeDef *hpcd)
341 PCD_EPTypeDef *ep;
342 uint16_t count=0U;
343 uint8_t EPindex;
344 __IO uint16_t wIstr;
345 __IO uint16_t wEPVal = 0U;
347 /* stay in loop while pending interrupts */
348 while (((wIstr = hpcd->Instance->ISTR) & USB_ISTR_CTR) != 0U)
350 /* extract highest priority endpoint number */
351 EPindex = (uint8_t)(wIstr & USB_ISTR_EP_ID);
353 if (EPindex == 0U)
355 /* Decode and service control endpoint interrupt */
357 /* DIR bit = origin of the interrupt */
358 if ((wIstr & USB_ISTR_DIR) == 0U)
360 /* DIR = 0U */
362 /* DIR = 0 => IN int */
363 /* DIR = 0 implies that (EP_CTR_TX = 1U) always */
364 PCD_CLEAR_TX_EP_CTR(hpcd->Instance, PCD_ENDP0);
365 ep = &hpcd->IN_ep[0];
367 ep->xfer_count = PCD_GET_EP_TX_CNT(hpcd->Instance, ep->num);
368 ep->xfer_buff += ep->xfer_count;
370 /* TX COMPLETE */
371 HAL_PCD_DataInStageCallback(hpcd, 0U);
374 if((hpcd->USB_Address > 0U)&& ( ep->xfer_len == 0U))
376 hpcd->Instance->DADDR = (hpcd->USB_Address | USB_DADDR_EF);
377 hpcd->USB_Address = 0U;
381 else
383 /* DIR = 1U */
385 /* DIR = 1U & CTR_RX => SETUP or OUT int */
386 /* DIR = 1U & (CTR_TX | CTR_RX) => 2 int pending */
387 ep = &hpcd->OUT_ep[0];
388 wEPVal = PCD_GET_ENDPOINT(hpcd->Instance, PCD_ENDP0);
390 if ((wEPVal & USB_EP_SETUP) != 0U)
392 /* Get SETUP Packet*/
393 ep->xfer_count = PCD_GET_EP_RX_CNT(hpcd->Instance, ep->num);
394 PCD_ReadPMA(hpcd->Instance, (uint8_t*)(void*)hpcd->Setup ,ep->pmaadress , ep->xfer_count);
395 /* SETUP bit kept frozen while CTR_RX = 1U*/
396 PCD_CLEAR_RX_EP_CTR(hpcd->Instance, PCD_ENDP0);
398 /* Process SETUP Packet*/
399 HAL_PCD_SetupStageCallback(hpcd);
402 else if ((wEPVal & USB_EP_CTR_RX) != 0U)
404 PCD_CLEAR_RX_EP_CTR(hpcd->Instance, PCD_ENDP0);
405 /* Get Control Data OUT Packet*/
406 ep->xfer_count = PCD_GET_EP_RX_CNT(hpcd->Instance, ep->num);
408 if (ep->xfer_count != 0U)
410 PCD_ReadPMA(hpcd->Instance, ep->xfer_buff, ep->pmaadress, ep->xfer_count);
411 ep->xfer_buff+=ep->xfer_count;
414 /* Process Control Data OUT Packet*/
415 HAL_PCD_DataOutStageCallback(hpcd, 0U);
417 PCD_SET_EP_RX_CNT(hpcd->Instance, PCD_ENDP0, ep->maxpacket)
418 PCD_SET_EP_RX_STATUS(hpcd->Instance, PCD_ENDP0, USB_EP_RX_VALID)
422 else
425 /* Decode and service non control endpoints interrupt */
427 /* process related endpoint register */
428 wEPVal = PCD_GET_ENDPOINT(hpcd->Instance, EPindex);
429 if ((wEPVal & USB_EP_CTR_RX) != 0U)
431 /* clear int flag */
432 PCD_CLEAR_RX_EP_CTR(hpcd->Instance, EPindex);
433 ep = &hpcd->OUT_ep[EPindex];
435 /* OUT double Buffering*/
436 if (ep->doublebuffer == 0U)
438 count = PCD_GET_EP_RX_CNT(hpcd->Instance, ep->num);
439 if (count != 0U)
441 PCD_ReadPMA(hpcd->Instance, ep->xfer_buff, ep->pmaadress, count);
444 else
446 if ((PCD_GET_ENDPOINT(hpcd->Instance, ep->num)& USB_EP_DTOG_RX) == USB_EP_DTOG_RX)
448 /*read from endpoint BUF0Addr buffer*/
449 count = PCD_GET_EP_DBUF0_CNT(hpcd->Instance, ep->num);
450 if (count != 0U)
452 PCD_ReadPMA(hpcd->Instance, ep->xfer_buff, ep->pmaaddr0, count);
455 else
457 /*read from endpoint BUF1Addr buffer*/
458 count = PCD_GET_EP_DBUF1_CNT(hpcd->Instance, ep->num);
459 if (count != 0U)
461 PCD_ReadPMA(hpcd->Instance, ep->xfer_buff, ep->pmaaddr1, count);
464 PCD_FreeUserBuffer(hpcd->Instance, ep->num, PCD_EP_DBUF_OUT)
466 /*multi-packet on the NON control OUT endpoint*/
467 ep->xfer_count+=count;
468 ep->xfer_buff+=count;
470 if ((ep->xfer_len == 0U) || (count < ep->maxpacket))
472 /* RX COMPLETE */
473 HAL_PCD_DataOutStageCallback(hpcd, ep->num);
475 else
477 HAL_PCD_EP_Receive(hpcd, ep->num, ep->xfer_buff, ep->xfer_len);
480 } /* if((wEPVal & EP_CTR_RX) */
482 if ((wEPVal & USB_EP_CTR_TX) != 0U)
484 ep = &hpcd->IN_ep[EPindex];
486 /* clear int flag */
487 PCD_CLEAR_TX_EP_CTR(hpcd->Instance, EPindex);
489 /* IN double Buffering*/
490 if (ep->doublebuffer == 0U)
492 ep->xfer_count = PCD_GET_EP_TX_CNT(hpcd->Instance, ep->num);
493 if (ep->xfer_count != 0U)
495 PCD_WritePMA(hpcd->Instance, ep->xfer_buff, ep->pmaadress, ep->xfer_count);
498 else
500 if ((PCD_GET_ENDPOINT(hpcd->Instance, ep->num)& USB_EP_DTOG_TX) == USB_EP_DTOG_TX)
502 /*read from endpoint BUF0Addr buffer*/
503 ep->xfer_count = PCD_GET_EP_DBUF0_CNT(hpcd->Instance, ep->num);
504 if (ep->xfer_count != 0U)
506 PCD_WritePMA(hpcd->Instance, ep->xfer_buff, ep->pmaaddr0, ep->xfer_count);
509 else
511 /*read from endpoint BUF1Addr buffer*/
512 ep->xfer_count = PCD_GET_EP_DBUF1_CNT(hpcd->Instance, ep->num);
513 if (ep->xfer_count != 0U)
515 PCD_WritePMA(hpcd->Instance, ep->xfer_buff, ep->pmaaddr1, ep->xfer_count);
518 PCD_FreeUserBuffer(hpcd->Instance, ep->num, PCD_EP_DBUF_IN)
520 /*multi-packet on the NON control IN endpoint*/
521 ep->xfer_count = PCD_GET_EP_TX_CNT(hpcd->Instance, ep->num);
522 ep->xfer_buff+=ep->xfer_count;
524 /* Zero Length Packet? */
525 if (ep->xfer_len == 0U)
527 /* TX COMPLETE */
528 HAL_PCD_DataInStageCallback(hpcd, ep->num);
530 else
532 HAL_PCD_EP_Transmit(hpcd, ep->num, ep->xfer_buff, ep->xfer_len);
537 return HAL_OK;
540 * @}
543 /** @addtogroup PCD_Exported_Functions
544 * @{
547 /** @defgroup PCD_Exported_Functions_Group2 IO operation functions
548 * @{
552 * @brief This function handles PCD interrupt request.
553 * @param hpcd PCD handle
554 * @retval HAL status
556 void HAL_PCD_IRQHandler(PCD_HandleTypeDef *hpcd)
559 if (__HAL_PCD_GET_FLAG (hpcd, USB_ISTR_CTR))
561 /* servicing of the endpoint correct transfer interrupt */
562 /* clear of the CTR flag into the sub */
563 PCD_EP_ISR_Handler(hpcd);
566 if (__HAL_PCD_GET_FLAG (hpcd, USB_ISTR_RESET))
568 __HAL_PCD_CLEAR_FLAG(hpcd, USB_ISTR_RESET);
569 HAL_PCD_ResetCallback(hpcd);
570 HAL_PCD_SetAddress(hpcd, 0U);
573 if (__HAL_PCD_GET_FLAG (hpcd, USB_ISTR_PMAOVR))
575 __HAL_PCD_CLEAR_FLAG(hpcd, USB_ISTR_PMAOVR);
577 if (__HAL_PCD_GET_FLAG (hpcd, USB_ISTR_ERR))
579 __HAL_PCD_CLEAR_FLAG(hpcd, USB_ISTR_ERR);
582 if (__HAL_PCD_GET_FLAG (hpcd, USB_ISTR_WKUP))
584 hpcd->Instance->CNTR &= (uint16_t) ~(USB_CNTR_LPMODE);
585 hpcd->Instance->CNTR &= (uint16_t) ~(USB_CNTR_FSUSP);
587 HAL_PCD_ResumeCallback(hpcd);
589 __HAL_PCD_CLEAR_FLAG(hpcd, USB_ISTR_WKUP);
592 if (__HAL_PCD_GET_FLAG (hpcd, USB_ISTR_SUSP))
594 /* Force low-power mode in the macrocell */
595 hpcd->Instance->CNTR |= USB_CNTR_FSUSP;
597 /* clear of the ISTR bit must be done after setting of CNTR_FSUSP */
598 __HAL_PCD_CLEAR_FLAG(hpcd, USB_ISTR_SUSP);
600 hpcd->Instance->CNTR |= USB_CNTR_LPMODE;
601 if (__HAL_PCD_GET_FLAG (hpcd, USB_ISTR_WKUP) == 0U)
603 HAL_PCD_SuspendCallback(hpcd);
607 if (__HAL_PCD_GET_FLAG (hpcd, USB_ISTR_SOF))
609 __HAL_PCD_CLEAR_FLAG(hpcd, USB_ISTR_SOF);
610 HAL_PCD_SOFCallback(hpcd);
613 if (__HAL_PCD_GET_FLAG (hpcd, USB_ISTR_ESOF))
615 /* clear ESOF flag in ISTR */
616 __HAL_PCD_CLEAR_FLAG(hpcd, USB_ISTR_ESOF);
621 * @brief Data out stage callbacks
622 * @param hpcd PCD handle
623 * @param epnum endpoint number
624 * @retval None
626 __weak void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
628 /* Prevent unused argument(s) compilation warning */
629 UNUSED(hpcd);
630 UNUSED(epnum);
632 /* NOTE : This function should not be modified, when the callback is needed,
633 the HAL_PCD_DataOutStageCallback could be implemented in the user file
638 * @brief Data IN stage callbacks
639 * @param hpcd PCD handle
640 * @param epnum endpoint number
641 * @retval None
643 __weak void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
645 /* Prevent unused argument(s) compilation warning */
646 UNUSED(hpcd);
647 UNUSED(epnum);
649 /* NOTE : This function should not be modified, when the callback is needed,
650 the HAL_PCD_DataInStageCallback could be implemented in the user file
654 * @brief Setup stage callback
655 * @param hpcd PCD handle
656 * @retval None
658 __weak void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd)
660 /* Prevent unused argument(s) compilation warning */
661 UNUSED(hpcd);
663 /* NOTE : This function should not be modified, when the callback is needed,
664 the HAL_PCD_SetupStageCallback could be implemented in the user file
669 * @brief USB Start Of Frame callbacks
670 * @param hpcd PCD handle
671 * @retval None
673 __weak void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd)
675 /* Prevent unused argument(s) compilation warning */
676 UNUSED(hpcd);
678 /* NOTE : This function should not be modified, when the callback is needed,
679 the HAL_PCD_SOFCallback could be implemented in the user file
684 * @brief USB Reset callbacks
685 * @param hpcd PCD handle
686 * @retval None
688 __weak void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd)
690 /* Prevent unused argument(s) compilation warning */
691 UNUSED(hpcd);
693 /* NOTE : This function should not be modified, when the callback is needed,
694 the HAL_PCD_ResetCallback could be implemented in the user file
699 * @brief Suspend event callbacks
700 * @param hpcd PCD handle
701 * @retval None
703 __weak void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd)
705 /* Prevent unused argument(s) compilation warning */
706 UNUSED(hpcd);
708 /* NOTE : This function should not be modified, when the callback is needed,
709 the HAL_PCD_SuspendCallback could be implemented in the user file
714 * @brief Resume event callbacks
715 * @param hpcd PCD handle
716 * @retval None
718 __weak void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd)
720 /* Prevent unused argument(s) compilation warning */
721 UNUSED(hpcd);
723 /* NOTE : This function should not be modified, when the callback is needed,
724 the HAL_PCD_ResumeCallback could be implemented in the user file
729 * @brief Incomplete ISO OUT callbacks
730 * @param hpcd PCD handle
731 * @param epnum endpoint number
732 * @retval None
734 __weak void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
736 /* Prevent unused argument(s) compilation warning */
737 UNUSED(hpcd);
738 UNUSED(epnum);
740 /* NOTE : This function should not be modified, when the callback is needed,
741 the HAL_PCD_ISOOUTIncompleteCallback could be implemented in the user file
746 * @brief Incomplete ISO IN callbacks
747 * @param hpcd PCD handle
748 * @param epnum endpoint number
749 * @retval None
751 __weak void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
753 /* Prevent unused argument(s) compilation warning */
754 UNUSED(hpcd);
755 UNUSED(epnum);
757 /* NOTE : This function should not be modified, when the callback is needed,
758 the HAL_PCD_ISOINIncompleteCallback could be implemented in the user file
763 * @brief Connection event callbacks
764 * @param hpcd PCD handle
765 * @retval None
767 __weak void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd)
769 /* Prevent unused argument(s) compilation warning */
770 UNUSED(hpcd);
772 /* NOTE : This function should not be modified, when the callback is needed,
773 the HAL_PCD_ConnectCallback could be implemented in the user file
778 * @brief Disconnection event callbacks
779 * @param hpcd PCD handle
780 * @retval None
782 __weak void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd)
784 /* Prevent unused argument(s) compilation warning */
785 UNUSED(hpcd);
787 /* NOTE : This function should not be modified, when the callback is needed,
788 the HAL_PCD_DisconnectCallback could be implemented in the user file
792 * @}
795 /** @defgroup PCD_Exported_Functions_Group3 Peripheral Control functions
796 * @brief management functions
798 @verbatim
799 ===============================================================================
800 ##### Peripheral Control functions #####
801 ===============================================================================
802 [..]
803 This subsection provides a set of functions allowing to control the PCD data
804 transfers.
806 @endverbatim
807 * @{
811 * @brief Connect the USB device
812 * @param hpcd PCD handle
813 * @retval HAL status
815 HAL_StatusTypeDef HAL_PCD_DevConnect(PCD_HandleTypeDef *hpcd)
817 __HAL_LOCK(hpcd);
819 /* Enabling DP Pull-Down bit to Connect internal pull-up on USB DP line */
820 HAL_PCDEx_SetConnectionState(hpcd, 1U);
822 __HAL_UNLOCK(hpcd);
823 return HAL_OK;
827 * @brief Disconnect the USB device
828 * @param hpcd PCD handle
829 * @retval HAL status
831 HAL_StatusTypeDef HAL_PCD_DevDisconnect(PCD_HandleTypeDef *hpcd)
833 __HAL_LOCK(hpcd);
835 /* Disable DP Pull-Down bit*/
836 HAL_PCDEx_SetConnectionState(hpcd, 0U);
838 __HAL_UNLOCK(hpcd);
839 return HAL_OK;
843 * @brief Set the USB Device address
844 * @param hpcd PCD handle
845 * @param address new device address
846 * @retval HAL status
848 HAL_StatusTypeDef HAL_PCD_SetAddress(PCD_HandleTypeDef *hpcd, uint8_t address)
850 __HAL_LOCK(hpcd);
852 if(address == 0U)
854 /* set device address and enable function */
855 hpcd->Instance->DADDR = USB_DADDR_EF;
857 else /* USB Address will be applied later */
859 hpcd->USB_Address = address;
862 __HAL_UNLOCK(hpcd);
863 return HAL_OK;
866 * @brief Open and configure an endpoint
867 * @param hpcd PCD handle
868 * @param ep_addr endpoint address
869 * @param ep_mps endpoint max packet size
870 * @param ep_type endpoint type
871 * @retval HAL status
873 HAL_StatusTypeDef HAL_PCD_EP_Open(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint16_t ep_mps, uint8_t ep_type)
875 HAL_StatusTypeDef ret = HAL_OK;
876 PCD_EPTypeDef *ep;
878 if ((ep_addr & 0x80U) == 0x80U)
880 ep = &hpcd->IN_ep[ep_addr & 0x7FU];
882 else
884 ep = &hpcd->OUT_ep[ep_addr & 0x7FU];
886 ep->num = ep_addr & 0x7FU;
888 ep->is_in = (0x80U & ep_addr) != 0U;
889 ep->maxpacket = ep_mps;
890 ep->type = ep_type;
892 __HAL_LOCK(hpcd);
894 /* initialize Endpoint */
895 switch (ep->type)
897 case PCD_EP_TYPE_CTRL:
898 PCD_SET_EPTYPE(hpcd->Instance, ep->num, USB_EP_CONTROL);
899 break;
900 case PCD_EP_TYPE_BULK:
901 PCD_SET_EPTYPE(hpcd->Instance, ep->num, USB_EP_BULK);
902 break;
903 case PCD_EP_TYPE_INTR:
904 PCD_SET_EPTYPE(hpcd->Instance, ep->num, USB_EP_INTERRUPT);
905 break;
906 case PCD_EP_TYPE_ISOC:
907 PCD_SET_EPTYPE(hpcd->Instance, ep->num, USB_EP_ISOCHRONOUS);
908 break;
909 default:
910 break;
913 PCD_SET_EP_ADDRESS(hpcd->Instance, ep->num, ep->num);
915 if (ep->doublebuffer == 0U)
917 if (ep->is_in)
919 /*Set the endpoint Transmit buffer address */
920 PCD_SET_EP_TX_ADDRESS(hpcd->Instance, ep->num, ep->pmaadress);
921 PCD_CLEAR_TX_DTOG(hpcd->Instance, ep->num)
922 /* Configure NAK status for the Endpoint*/
923 PCD_SET_EP_TX_STATUS(hpcd->Instance, ep->num, USB_EP_TX_NAK)
925 else
927 /*Set the endpoint Receive buffer address */
928 PCD_SET_EP_RX_ADDRESS(hpcd->Instance, ep->num, ep->pmaadress);
929 /*Set the endpoint Receive buffer counter*/
930 PCD_SET_EP_RX_CNT(hpcd->Instance, ep->num, ep->maxpacket)
931 PCD_CLEAR_RX_DTOG(hpcd->Instance, ep->num)
932 /* Configure VALID status for the Endpoint*/
933 PCD_SET_EP_RX_STATUS(hpcd->Instance, ep->num, USB_EP_RX_VALID)
936 /*Double Buffer*/
937 else
939 /*Set the endpoint as double buffered*/
940 PCD_SET_EP_DBUF(hpcd->Instance, ep->num);
941 /*Set buffer address for double buffered mode*/
942 PCD_SET_EP_DBUF_ADDR(hpcd->Instance, ep->num,ep->pmaaddr0, ep->pmaaddr1)
944 if (ep->is_in==0U)
946 /* Clear the data toggle bits for the endpoint IN/OUT*/
947 PCD_CLEAR_RX_DTOG(hpcd->Instance, ep->num)
948 PCD_CLEAR_TX_DTOG(hpcd->Instance, ep->num)
950 /* Reset value of the data toggle bits for the endpoint out*/
951 PCD_TX_DTOG(hpcd->Instance, ep->num);
953 PCD_SET_EP_RX_STATUS(hpcd->Instance, ep->num, USB_EP_RX_VALID)
954 PCD_SET_EP_TX_STATUS(hpcd->Instance, ep->num, USB_EP_TX_DIS)
956 else
958 /* Clear the data toggle bits for the endpoint IN/OUT*/
959 PCD_CLEAR_RX_DTOG(hpcd->Instance, ep->num)
960 PCD_CLEAR_TX_DTOG(hpcd->Instance, ep->num)
961 PCD_RX_DTOG(hpcd->Instance, ep->num);
962 /* Configure DISABLE status for the Endpoint*/
963 PCD_SET_EP_TX_STATUS(hpcd->Instance, ep->num, USB_EP_TX_DIS)
964 PCD_SET_EP_RX_STATUS(hpcd->Instance, ep->num, USB_EP_RX_DIS)
968 __HAL_UNLOCK(hpcd);
969 return ret;
974 * @brief Deactivate an endpoint
975 * @param hpcd PCD handle
976 * @param ep_addr endpoint address
977 * @retval HAL status
979 HAL_StatusTypeDef HAL_PCD_EP_Close(PCD_HandleTypeDef *hpcd, uint8_t ep_addr)
981 PCD_EPTypeDef *ep;
983 if ((ep_addr & 0x80U) == 0x80U)
985 ep = &hpcd->IN_ep[ep_addr & 0x7F];
987 else
989 ep = &hpcd->OUT_ep[ep_addr & 0x7F];
991 ep->num = ep_addr & 0x7FU;
993 ep->is_in = (0x80U & ep_addr) != 0U;
995 __HAL_LOCK(hpcd);
997 if (ep->doublebuffer == 0U)
999 if (ep->is_in)
1001 PCD_CLEAR_TX_DTOG(hpcd->Instance, ep->num)
1002 /* Configure DISABLE status for the Endpoint*/
1003 PCD_SET_EP_TX_STATUS(hpcd->Instance, ep->num, USB_EP_TX_DIS)
1005 else
1007 PCD_CLEAR_RX_DTOG(hpcd->Instance, ep->num)
1008 /* Configure DISABLE status for the Endpoint*/
1009 PCD_SET_EP_RX_STATUS(hpcd->Instance, ep->num, USB_EP_RX_DIS)
1012 /*Double Buffer*/
1013 else
1015 if (ep->is_in==0U)
1017 /* Clear the data toggle bits for the endpoint IN/OUT*/
1018 PCD_CLEAR_RX_DTOG(hpcd->Instance, ep->num)
1019 PCD_CLEAR_TX_DTOG(hpcd->Instance, ep->num)
1021 /* Reset value of the data toggle bits for the endpoint out*/
1022 PCD_TX_DTOG(hpcd->Instance, ep->num);
1024 PCD_SET_EP_RX_STATUS(hpcd->Instance, ep->num, USB_EP_RX_DIS)
1025 PCD_SET_EP_TX_STATUS(hpcd->Instance, ep->num, USB_EP_TX_DIS)
1027 else
1029 /* Clear the data toggle bits for the endpoint IN/OUT*/
1030 PCD_CLEAR_RX_DTOG(hpcd->Instance, ep->num)
1031 PCD_CLEAR_TX_DTOG(hpcd->Instance, ep->num)
1032 PCD_RX_DTOG(hpcd->Instance, ep->num);
1033 /* Configure DISABLE status for the Endpoint*/
1034 PCD_SET_EP_TX_STATUS(hpcd->Instance, ep->num, USB_EP_TX_DIS)
1035 PCD_SET_EP_RX_STATUS(hpcd->Instance, ep->num, USB_EP_RX_DIS)
1039 __HAL_UNLOCK(hpcd);
1040 return HAL_OK;
1045 * @brief Receive an amount of data
1046 * @param hpcd PCD handle
1047 * @param ep_addr endpoint address
1048 * @param pBuf pointer to the reception buffer
1049 * @param len amount of data to be received
1050 * @retval HAL status
1052 HAL_StatusTypeDef HAL_PCD_EP_Receive(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len)
1055 PCD_EPTypeDef *ep;
1057 ep = &hpcd->OUT_ep[ep_addr & 0x7F];
1059 /*setup and start the Xfer */
1060 ep->xfer_buff = pBuf;
1061 ep->xfer_len = len;
1062 ep->xfer_count = 0U;
1063 ep->is_in = 0U;
1064 ep->num = ep_addr & 0x7FU;
1066 /* Multi packet transfer*/
1067 if (ep->xfer_len > ep->maxpacket)
1069 len=ep->maxpacket;
1070 ep->xfer_len-=len;
1072 else
1074 len=ep->xfer_len;
1075 ep->xfer_len =0U;
1078 /* configure and validate Rx endpoint */
1079 if (ep->doublebuffer == 0U)
1081 /*Set RX buffer count*/
1082 PCD_SET_EP_RX_CNT(hpcd->Instance, ep->num, len)
1084 else
1086 /*Set the Double buffer counter*/
1087 PCD_SET_EP_DBUF1_CNT(hpcd->Instance, ep->num, ep->is_in, len)
1090 PCD_SET_EP_RX_STATUS(hpcd->Instance, ep->num, USB_EP_RX_VALID)
1092 return HAL_OK;
1096 * @brief Get Received Data Size
1097 * @param hpcd PCD handle
1098 * @param ep_addr endpoint address
1099 * @retval Data Size
1101 uint16_t HAL_PCD_EP_GetRxCount(PCD_HandleTypeDef *hpcd, uint8_t ep_addr)
1103 return hpcd->OUT_ep[ep_addr & 0x7F].xfer_count;
1106 * @brief Send an amount of data
1107 * @param hpcd PCD handle
1108 * @param ep_addr endpoint address
1109 * @param pBuf pointer to the transmission buffer
1110 * @param len amount of data to be sent
1111 * @retval HAL status
1113 HAL_StatusTypeDef HAL_PCD_EP_Transmit(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len)
1115 PCD_EPTypeDef *ep;
1116 uint16_t pmabuffer = 0U;
1118 ep = &hpcd->IN_ep[ep_addr & 0x7F];
1120 /*setup and start the Xfer */
1121 ep->xfer_buff = pBuf;
1122 ep->xfer_len = len;
1123 ep->xfer_count = 0U;
1124 ep->is_in = 1U;
1125 ep->num = ep_addr & 0x7FU;
1127 /*Multi packet transfer*/
1128 if (ep->xfer_len > ep->maxpacket)
1130 len=ep->maxpacket;
1131 ep->xfer_len-=len;
1133 else
1135 len=ep->xfer_len;
1136 ep->xfer_len =0U;
1139 /* configure and validate Tx endpoint */
1140 if (ep->doublebuffer == 0U)
1142 PCD_WritePMA(hpcd->Instance, ep->xfer_buff, ep->pmaadress, len);
1143 PCD_SET_EP_TX_CNT(hpcd->Instance, ep->num, len);
1145 else
1147 /*Write the data to the USB endpoint*/
1148 if ((PCD_GET_ENDPOINT(hpcd->Instance, ep->num)& USB_EP_DTOG_TX) == USB_EP_DTOG_TX)
1150 pmabuffer = ep->pmaaddr1;
1152 else
1154 pmabuffer = ep->pmaaddr0;
1156 PCD_WritePMA(hpcd->Instance, ep->xfer_buff, pmabuffer, len);
1157 PCD_FreeUserBuffer(hpcd->Instance, ep->num, ep->is_in)
1160 PCD_SET_EP_TX_STATUS(hpcd->Instance, ep->num, USB_EP_TX_VALID)
1162 return HAL_OK;
1166 * @brief Set a STALL condition over an endpoint
1167 * @param hpcd PCD handle
1168 * @param ep_addr endpoint address
1169 * @retval HAL status
1171 HAL_StatusTypeDef HAL_PCD_EP_SetStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr)
1173 PCD_EPTypeDef *ep;
1175 __HAL_LOCK(hpcd);
1177 if ((0x80U & ep_addr) == 0x80U)
1179 ep = &hpcd->IN_ep[ep_addr & 0x7F];
1181 else
1183 ep = &hpcd->OUT_ep[ep_addr];
1186 ep->is_stall = 1U;
1187 ep->num = ep_addr & 0x7FU;
1188 ep->is_in = ((ep_addr & 0x80U) == 0x80U);
1190 if (ep->num == 0U)
1192 /* This macro sets STALL status for RX & TX*/
1193 PCD_SET_EP_TXRX_STATUS(hpcd->Instance, ep->num, USB_EP_RX_STALL, USB_EP_TX_STALL)
1195 else
1197 if (ep->is_in)
1199 PCD_SET_EP_TX_STATUS(hpcd->Instance, ep->num , USB_EP_TX_STALL)
1201 else
1203 PCD_SET_EP_RX_STATUS(hpcd->Instance, ep->num , USB_EP_RX_STALL)
1206 __HAL_UNLOCK(hpcd);
1208 return HAL_OK;
1212 * @brief Clear a STALL condition over in an endpoint
1213 * @param hpcd PCD handle
1214 * @param ep_addr endpoint address
1215 * @retval HAL status
1217 HAL_StatusTypeDef HAL_PCD_EP_ClrStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr)
1219 PCD_EPTypeDef *ep;
1221 if ((0x80U & ep_addr) == 0x80U)
1223 ep = &hpcd->IN_ep[ep_addr & 0x7F];
1225 else
1227 ep = &hpcd->OUT_ep[ep_addr];
1230 ep->is_stall = 0U;
1231 ep->num = ep_addr & 0x7FU;
1232 ep->is_in = ((ep_addr & 0x80U) == 0x80U);
1234 __HAL_LOCK(hpcd);
1236 if (ep->is_in)
1238 PCD_CLEAR_TX_DTOG(hpcd->Instance, ep->num)
1239 PCD_SET_EP_TX_STATUS(hpcd->Instance, ep->num, USB_EP_TX_VALID)
1241 else
1243 PCD_CLEAR_RX_DTOG(hpcd->Instance, ep->num)
1244 PCD_SET_EP_RX_STATUS(hpcd->Instance, ep->num, USB_EP_RX_VALID)
1246 __HAL_UNLOCK(hpcd);
1248 return HAL_OK;
1252 * @brief Flush an endpoint
1253 * @param hpcd PCD handle
1254 * @param ep_addr endpoint address
1255 * @retval HAL status
1257 HAL_StatusTypeDef HAL_PCD_EP_Flush(PCD_HandleTypeDef *hpcd, uint8_t ep_addr)
1259 return HAL_OK;
1263 * @brief HAL_PCD_ActivateRemoteWakeup : active remote wakeup signalling
1264 * @param hpcd PCD handle
1265 * @retval HAL status
1267 HAL_StatusTypeDef HAL_PCD_ActivateRemoteWakeup(PCD_HandleTypeDef *hpcd)
1269 hpcd->Instance->CNTR |= USB_CNTR_RESUME;
1270 return HAL_OK;
1274 * @brief HAL_PCD_DeActivateRemoteWakeup : de-active remote wakeup signalling
1275 * @param hpcd PCD handle
1276 * @retval HAL status
1278 HAL_StatusTypeDef HAL_PCD_DeActivateRemoteWakeup(PCD_HandleTypeDef *hpcd)
1280 hpcd->Instance->CNTR &=~((uint32_t)USB_CNTR_RESUME);
1281 return HAL_OK;
1285 * @}
1288 /** @defgroup PCD_Exported_Functions_Group4 Peripheral State functions
1289 * @brief Peripheral State functions
1291 @verbatim
1292 ===============================================================================
1293 ##### Peripheral State functions #####
1294 ===============================================================================
1295 [..]
1296 This subsection permits to get in run-time the status of the peripheral
1297 and the data flow.
1299 @endverbatim
1300 * @{
1304 * @brief Return the PCD state
1305 * @param hpcd PCD handle
1306 * @retval HAL state
1308 PCD_StateTypeDef HAL_PCD_GetState(PCD_HandleTypeDef *hpcd)
1310 return hpcd->State;
1313 * @}
1318 * @}
1322 * @}
1326 * @}
1329 #endif /* STM32F302xE || STM32F303xE || */
1330 /* STM32F302xC || STM32F303xC || */
1331 /* STM32F302x8 || */
1332 /* STM32F373xC */
1334 #endif /* HAL_PCD_MODULE_ENABLED */
1336 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/