2 ******************************************************************************
3 * @file stm32f4xx_hal_hcd.c
4 * @author MCD Application Team
7 * @brief HCD 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 (#)Declare a HCD_HandleTypeDef handle structure, for example:
21 HCD_HandleTypeDef hhcd;
23 (#)Fill parameters of Init structure in HCD handle
25 (#)Call HAL_HCD_Init() API to initialize the HCD peripheral (Core, Host core, ...)
27 (#)Initialize the HCD low level resources through the HAL_HCD_MspInit() API:
28 (##) Enable the HCD/USB Low Level interface clock using the following macros
29 (+++) __HAL_RCC_USB_OTG_FS_CLK_ENABLE();
30 (+++) __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); (For High Speed Mode)
31 (+++) __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); (For High Speed Mode)
33 (##) Initialize the related GPIO clocks
34 (##) Configure HCD pin-out
35 (##) Configure HCD NVIC interrupt
37 (#)Associate the Upper USB Host stack to the HAL HCD Driver:
38 (##) hhcd.pData = phost;
40 (#)Enable HCD transmission and reception:
44 ******************************************************************************
47 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
49 * Redistribution and use in source and binary forms, with or without modification,
50 * are permitted provided that the following conditions are met:
51 * 1. Redistributions of source code must retain the above copyright notice,
52 * this list of conditions and the following disclaimer.
53 * 2. Redistributions in binary form must reproduce the above copyright notice,
54 * this list of conditions and the following disclaimer in the documentation
55 * and/or other materials provided with the distribution.
56 * 3. Neither the name of STMicroelectronics nor the names of its contributors
57 * may be used to endorse or promote products derived from this software
58 * without specific prior written permission.
60 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
61 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
62 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
63 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
64 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
65 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
66 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
67 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
68 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
69 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
71 ******************************************************************************
74 /* Includes ------------------------------------------------------------------*/
75 #include "stm32f4xx_hal.h"
77 /** @addtogroup STM32F4xx_HAL_Driver
82 * @brief HCD HAL module driver
86 #ifdef HAL_HCD_MODULE_ENABLED
87 #if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \
88 defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \
89 defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \
90 defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \
91 defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx)
92 /* Private typedef -----------------------------------------------------------*/
93 /* Private define ------------------------------------------------------------*/
94 /* Private macro -------------------------------------------------------------*/
95 /* Private variables ---------------------------------------------------------*/
96 /* Private function prototypes -----------------------------------------------*/
97 /** @defgroup HCD_Private_Functions HCD Private Functions
100 static void HCD_HC_IN_IRQHandler(HCD_HandleTypeDef
*hhcd
, uint8_t chnum
);
101 static void HCD_HC_OUT_IRQHandler(HCD_HandleTypeDef
*hhcd
, uint8_t chnum
);
102 static void HCD_RXQLVL_IRQHandler(HCD_HandleTypeDef
*hhcd
);
103 static void HCD_Port_IRQHandler(HCD_HandleTypeDef
*hhcd
);
108 /* Exported functions --------------------------------------------------------*/
109 /** @defgroup HCD_Exported_Functions HCD Exported Functions
113 /** @defgroup HCD_Exported_Functions_Group1 Initialization and de-initialization functions
114 * @brief Initialization and Configuration functions
117 ===============================================================================
118 ##### Initialization and de-initialization functions #####
119 ===============================================================================
120 [..] This section provides functions allowing to:
127 * @brief Initialize the host driver.
128 * @param hhcd: HCD handle
131 HAL_StatusTypeDef
HAL_HCD_Init(HCD_HandleTypeDef
*hhcd
)
133 /* Check the HCD handle allocation */
139 /* Check the parameters */
140 assert_param(IS_HCD_ALL_INSTANCE(hhcd
->Instance
));
142 hhcd
->State
= HAL_HCD_STATE_BUSY
;
144 /* Init the low level hardware : GPIO, CLOCK, NVIC... */
145 HAL_HCD_MspInit(hhcd
);
147 /* Disable the Interrupts */
148 __HAL_HCD_DISABLE(hhcd
);
150 /* Init the Core (common init.) */
151 USB_CoreInit(hhcd
->Instance
, hhcd
->Init
);
154 USB_SetCurrentMode(hhcd
->Instance
, USB_OTG_HOST_MODE
);
157 USB_HostInit(hhcd
->Instance
, hhcd
->Init
);
159 hhcd
->State
= HAL_HCD_STATE_READY
;
165 * @brief Initialize a host channel.
166 * @param hhcd: HCD handle
167 * @param ch_num: Channel number.
168 * This parameter can be a value from 1 to 15
169 * @param epnum: Endpoint number.
170 * This parameter can be a value from 1 to 15
171 * @param dev_address : Current device address
172 * This parameter can be a value from 0 to 255
173 * @param speed: Current device speed.
174 * This parameter can be one of these values:
175 * HCD_SPEED_HIGH: High speed mode,
176 * HCD_SPEED_FULL: Full speed mode,
177 * HCD_SPEED_LOW: Low speed mode
178 * @param ep_type: Endpoint Type.
179 * This parameter can be one of these values:
180 * EP_TYPE_CTRL: Control type,
181 * EP_TYPE_ISOC: Isochronous type,
182 * EP_TYPE_BULK: Bulk type,
183 * EP_TYPE_INTR: Interrupt type
184 * @param mps: Max Packet Size.
185 * This parameter can be a value from 0 to32K
188 HAL_StatusTypeDef
HAL_HCD_HC_Init(HCD_HandleTypeDef
*hhcd
,
196 HAL_StatusTypeDef status
= HAL_OK
;
200 hhcd
->hc
[ch_num
].dev_addr
= dev_address
;
201 hhcd
->hc
[ch_num
].max_packet
= mps
;
202 hhcd
->hc
[ch_num
].ch_num
= ch_num
;
203 hhcd
->hc
[ch_num
].ep_type
= ep_type
;
204 hhcd
->hc
[ch_num
].ep_num
= epnum
& 0x7F;
205 hhcd
->hc
[ch_num
].ep_is_in
= ((epnum
& 0x80) == 0x80);
206 hhcd
->hc
[ch_num
].speed
= speed
;
208 status
= USB_HC_Init(hhcd
->Instance
,
221 * @brief Halt a host channel.
222 * @param hhcd: HCD handle
223 * @param ch_num: Channel number.
224 * This parameter can be a value from 1 to 15
227 HAL_StatusTypeDef
HAL_HCD_HC_Halt(HCD_HandleTypeDef
*hhcd
, uint8_t ch_num
)
229 HAL_StatusTypeDef status
= HAL_OK
;
232 USB_HC_Halt(hhcd
->Instance
, ch_num
);
239 * @brief DeInitialize the host driver.
240 * @param hhcd: HCD handle
243 HAL_StatusTypeDef
HAL_HCD_DeInit(HCD_HandleTypeDef
*hhcd
)
245 /* Check the HCD handle allocation */
251 hhcd
->State
= HAL_HCD_STATE_BUSY
;
253 /* DeInit the low level hardware */
254 HAL_HCD_MspDeInit(hhcd
);
256 __HAL_HCD_DISABLE(hhcd
);
258 hhcd
->State
= HAL_HCD_STATE_RESET
;
264 * @brief Initialize the HCD MSP.
265 * @param hhcd: HCD handle
268 __weak
void HAL_HCD_MspInit(HCD_HandleTypeDef
*hhcd
)
270 /* Prevent unused argument(s) compilation warning */
272 /* NOTE : This function Should not be modified, when the callback is needed,
273 the HAL_PCD_MspInit could be implemented in the user file
278 * @brief DeInitialize the HCD MSP.
279 * @param hhcd: HCD handle
282 __weak
void HAL_HCD_MspDeInit(HCD_HandleTypeDef
*hhcd
)
284 /* Prevent unused argument(s) compilation warning */
286 /* NOTE : This function Should not be modified, when the callback is needed,
287 the HAL_PCD_MspDeInit could be implemented in the user file
295 /** @defgroup HCD_Exported_Functions_Group2 Input and Output operation functions
296 * @brief HCD IO operation functions
299 ===============================================================================
300 ##### IO operation functions #####
301 ===============================================================================
302 [..] This subsection provides a set of functions allowing to manage the USB Host Data
310 * @brief Submit a new URB for processing.
311 * @param hhcd: HCD handle
312 * @param ch_num: Channel number.
313 * This parameter can be a value from 1 to 15
314 * @param direction: Channel number.
315 * This parameter can be one of these values:
316 * 0 : Output / 1 : Input
317 * @param ep_type: Endpoint Type.
318 * This parameter can be one of these values:
319 * EP_TYPE_CTRL: Control type/
320 * EP_TYPE_ISOC: Isochronous type/
321 * EP_TYPE_BULK: Bulk type/
322 * EP_TYPE_INTR: Interrupt type/
323 * @param token: Endpoint Type.
324 * This parameter can be one of these values:
325 * 0: HC_PID_SETUP / 1: HC_PID_DATA1
326 * @param pbuff: pointer to URB data
327 * @param length: Length of URB data
328 * @param do_ping: activate do ping protocol (for high speed only).
329 * This parameter can be one of these values:
330 * 0 : do ping inactive / 1 : do ping active
333 HAL_StatusTypeDef
HAL_HCD_HC_SubmitRequest(HCD_HandleTypeDef
*hhcd
,
342 hhcd
->hc
[ch_num
].ep_is_in
= direction
;
343 hhcd
->hc
[ch_num
].ep_type
= ep_type
;
347 hhcd
->hc
[ch_num
].data_pid
= HC_PID_SETUP
;
351 hhcd
->hc
[ch_num
].data_pid
= HC_PID_DATA1
;
354 /* Manage Data Toggle */
358 if((token
== 1) && (direction
== 0)) /*send data */
361 { /* For Status OUT stage, Length==0, Status Out PID = 1 */
362 hhcd
->hc
[ch_num
].toggle_out
= 1;
365 /* Set the Data Toggle bit as per the Flag */
366 if (hhcd
->hc
[ch_num
].toggle_out
== 0)
367 { /* Put the PID 0 */
368 hhcd
->hc
[ch_num
].data_pid
= HC_PID_DATA0
;
371 { /* Put the PID 1 */
372 hhcd
->hc
[ch_num
].data_pid
= HC_PID_DATA1
;
374 if(hhcd
->hc
[ch_num
].urb_state
!= URB_NOTREADY
)
376 hhcd
->hc
[ch_num
].do_ping
= do_ping
;
384 /* Set the Data Toggle bit as per the Flag */
385 if ( hhcd
->hc
[ch_num
].toggle_out
== 0)
386 { /* Put the PID 0 */
387 hhcd
->hc
[ch_num
].data_pid
= HC_PID_DATA0
;
390 { /* Put the PID 1 */
391 hhcd
->hc
[ch_num
].data_pid
= HC_PID_DATA1
;
393 if(hhcd
->hc
[ch_num
].urb_state
!= URB_NOTREADY
)
395 hhcd
->hc
[ch_num
].do_ping
= do_ping
;
400 if( hhcd
->hc
[ch_num
].toggle_in
== 0)
402 hhcd
->hc
[ch_num
].data_pid
= HC_PID_DATA0
;
406 hhcd
->hc
[ch_num
].data_pid
= HC_PID_DATA1
;
414 /* Set the Data Toggle bit as per the Flag */
415 if ( hhcd
->hc
[ch_num
].toggle_out
== 0)
416 { /* Put the PID 0 */
417 hhcd
->hc
[ch_num
].data_pid
= HC_PID_DATA0
;
420 { /* Put the PID 1 */
421 hhcd
->hc
[ch_num
].data_pid
= HC_PID_DATA1
;
426 if( hhcd
->hc
[ch_num
].toggle_in
== 0)
428 hhcd
->hc
[ch_num
].data_pid
= HC_PID_DATA0
;
432 hhcd
->hc
[ch_num
].data_pid
= HC_PID_DATA1
;
438 hhcd
->hc
[ch_num
].data_pid
= HC_PID_DATA0
;
442 hhcd
->hc
[ch_num
].xfer_buff
= pbuff
;
443 hhcd
->hc
[ch_num
].xfer_len
= length
;
444 hhcd
->hc
[ch_num
].urb_state
= URB_IDLE
;
445 hhcd
->hc
[ch_num
].xfer_count
= 0;
446 hhcd
->hc
[ch_num
].ch_num
= ch_num
;
447 hhcd
->hc
[ch_num
].state
= HC_IDLE
;
449 return USB_HC_StartXfer(hhcd
->Instance
, &(hhcd
->hc
[ch_num
]), hhcd
->Init
.dma_enable
);
453 * @brief Handle HCD interrupt request.
454 * @param hhcd: HCD handle
457 void HAL_HCD_IRQHandler(HCD_HandleTypeDef
*hhcd
)
459 USB_OTG_GlobalTypeDef
*USBx
= hhcd
->Instance
;
460 uint32_t i
= 0U , interrupt
= 0U;
462 /* Ensure that we are in device mode */
463 if (USB_GetMode(hhcd
->Instance
) == USB_OTG_MODE_HOST
)
465 /* Avoid spurious interrupt */
466 if(__HAL_HCD_IS_INVALID_INTERRUPT(hhcd
))
471 if(__HAL_HCD_GET_FLAG(hhcd
, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT
))
473 /* Incorrect mode, acknowledge the interrupt */
474 __HAL_HCD_CLEAR_FLAG(hhcd
, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT
);
477 if(__HAL_HCD_GET_FLAG(hhcd
, USB_OTG_GINTSTS_IISOIXFR
))
479 /* Incorrect mode, acknowledge the interrupt */
480 __HAL_HCD_CLEAR_FLAG(hhcd
, USB_OTG_GINTSTS_IISOIXFR
);
483 if(__HAL_HCD_GET_FLAG(hhcd
, USB_OTG_GINTSTS_PTXFE
))
485 /* Incorrect mode, acknowledge the interrupt */
486 __HAL_HCD_CLEAR_FLAG(hhcd
, USB_OTG_GINTSTS_PTXFE
);
489 if(__HAL_HCD_GET_FLAG(hhcd
, USB_OTG_GINTSTS_MMIS
))
491 /* Incorrect mode, acknowledge the interrupt */
492 __HAL_HCD_CLEAR_FLAG(hhcd
, USB_OTG_GINTSTS_MMIS
);
495 /* Handle Host Disconnect Interrupts */
496 if(__HAL_HCD_GET_FLAG(hhcd
, USB_OTG_GINTSTS_DISCINT
))
500 USBx_HPRT0
&= ~(USB_OTG_HPRT_PENA
| USB_OTG_HPRT_PCDET
|\
501 USB_OTG_HPRT_PENCHNG
| USB_OTG_HPRT_POCCHNG
);
503 /* Handle Host Port Interrupts */
504 HAL_HCD_Disconnect_Callback(hhcd
);
505 USB_InitFSLSPClkSel(hhcd
->Instance
,HCFG_48_MHZ
);
506 __HAL_HCD_CLEAR_FLAG(hhcd
, USB_OTG_GINTSTS_DISCINT
);
509 /* Handle Host Port Interrupts */
510 if(__HAL_HCD_GET_FLAG(hhcd
, USB_OTG_GINTSTS_HPRTINT
))
512 HCD_Port_IRQHandler (hhcd
);
515 /* Handle Host SOF Interrupts */
516 if(__HAL_HCD_GET_FLAG(hhcd
, USB_OTG_GINTSTS_SOF
))
518 HAL_HCD_SOF_Callback(hhcd
);
519 __HAL_HCD_CLEAR_FLAG(hhcd
, USB_OTG_GINTSTS_SOF
);
522 /* Handle Host channel Interrupts */
523 if(__HAL_HCD_GET_FLAG(hhcd
, USB_OTG_GINTSTS_HCINT
))
525 interrupt
= USB_HC_ReadInterrupt(hhcd
->Instance
);
526 for (i
= 0U; i
< hhcd
->Init
.Host_channels
; i
++)
528 if (interrupt
& (1U << i
))
530 if ((USBx_HC(i
)->HCCHAR
) & USB_OTG_HCCHAR_EPDIR
)
532 HCD_HC_IN_IRQHandler(hhcd
, i
);
536 HCD_HC_OUT_IRQHandler (hhcd
, i
);
540 __HAL_HCD_CLEAR_FLAG(hhcd
, USB_OTG_GINTSTS_HCINT
);
543 /* Handle Rx Queue Level Interrupts */
544 if(__HAL_HCD_GET_FLAG(hhcd
, USB_OTG_GINTSTS_RXFLVL
))
546 USB_MASK_INTERRUPT(hhcd
->Instance
, USB_OTG_GINTSTS_RXFLVL
);
548 HCD_RXQLVL_IRQHandler (hhcd
);
550 USB_UNMASK_INTERRUPT(hhcd
->Instance
, USB_OTG_GINTSTS_RXFLVL
);
556 * @brief SOF callback.
557 * @param hhcd: HCD handle
560 __weak
void HAL_HCD_SOF_Callback(HCD_HandleTypeDef
*hhcd
)
562 /* Prevent unused argument(s) compilation warning */
564 /* NOTE : This function Should not be modified, when the callback is needed,
565 the HAL_HCD_SOF_Callback could be implemented in the user file
570 * @brief Connection Event callback.
571 * @param hhcd: HCD handle
574 __weak
void HAL_HCD_Connect_Callback(HCD_HandleTypeDef
*hhcd
)
576 /* Prevent unused argument(s) compilation warning */
578 /* NOTE : This function Should not be modified, when the callback is needed,
579 the HAL_HCD_Connect_Callback could be implemented in the user file
584 * @brief Disconnection Event callback.
585 * @param hhcd: HCD handle
588 __weak
void HAL_HCD_Disconnect_Callback(HCD_HandleTypeDef
*hhcd
)
590 /* Prevent unused argument(s) compilation warning */
592 /* NOTE : This function Should not be modified, when the callback is needed,
593 the HAL_HCD_Disconnect_Callback could be implemented in the user file
598 * @brief Notify URB state change callback.
599 * @param hhcd: HCD handle
600 * @param chnum: Channel number.
601 * This parameter can be a value from 1 to 15
603 * This parameter can be one of these values:
612 __weak
void HAL_HCD_HC_NotifyURBChange_Callback(HCD_HandleTypeDef
*hhcd
, uint8_t chnum
, HCD_URBStateTypeDef urb_state
)
614 /* Prevent unused argument(s) compilation warning */
618 /* NOTE : This function Should not be modified, when the callback is needed,
619 the HAL_HCD_HC_NotifyURBChange_Callback could be implemented in the user file
627 /** @defgroup HCD_Exported_Functions_Group3 Peripheral Control functions
628 * @brief Management functions
631 ===============================================================================
632 ##### Peripheral Control functions #####
633 ===============================================================================
635 This subsection provides a set of functions allowing to control the HCD data
643 * @brief Start the host driver.
644 * @param hhcd: HCD handle
647 HAL_StatusTypeDef
HAL_HCD_Start(HCD_HandleTypeDef
*hhcd
)
650 __HAL_HCD_ENABLE(hhcd
);
651 USB_DriveVbus(hhcd
->Instance
, 1U);
657 * @brief Stop the host driver.
658 * @param hhcd: HCD handle
662 HAL_StatusTypeDef
HAL_HCD_Stop(HCD_HandleTypeDef
*hhcd
)
665 USB_StopHost(hhcd
->Instance
);
671 * @brief Reset the host port.
672 * @param hhcd: HCD handle
675 HAL_StatusTypeDef
HAL_HCD_ResetPort(HCD_HandleTypeDef
*hhcd
)
677 return (USB_ResetPort(hhcd
->Instance
));
684 /** @defgroup HCD_Exported_Functions_Group4 Peripheral State functions
685 * @brief Peripheral State functions
688 ===============================================================================
689 ##### Peripheral State functions #####
690 ===============================================================================
692 This subsection permits to get in run-time the status of the peripheral
700 * @brief Return the HCD handle state.
701 * @param hhcd: HCD handle
704 HCD_StateTypeDef
HAL_HCD_GetState(HCD_HandleTypeDef
*hhcd
)
710 * @brief Return URB state for a channel.
711 * @param hhcd: HCD handle
712 * @param chnum: Channel number.
713 * This parameter can be a value from 1 to 15
715 * This parameter can be one of these values:
723 HCD_URBStateTypeDef
HAL_HCD_HC_GetURBState(HCD_HandleTypeDef
*hhcd
, uint8_t chnum
)
725 return hhcd
->hc
[chnum
].urb_state
;
730 * @brief Return the last host transfer size.
731 * @param hhcd: HCD handle
732 * @param chnum: Channel number.
733 * This parameter can be a value from 1 to 15
734 * @retval last transfer size in byte
736 uint32_t HAL_HCD_HC_GetXferCount(HCD_HandleTypeDef
*hhcd
, uint8_t chnum
)
738 return hhcd
->hc
[chnum
].xfer_count
;
742 * @brief Return the Host Channel state.
743 * @param hhcd: HCD handle
744 * @param chnum: Channel number.
745 * This parameter can be a value from 1 to 15
746 * @retval Host channel state
747 * This parameter can be one of these values:
758 HCD_HCStateTypeDef
HAL_HCD_HC_GetState(HCD_HandleTypeDef
*hhcd
, uint8_t chnum
)
760 return hhcd
->hc
[chnum
].state
;
764 * @brief Return the current Host frame number.
765 * @param hhcd: HCD handle
766 * @retval Current Host frame number
768 uint32_t HAL_HCD_GetCurrentFrame(HCD_HandleTypeDef
*hhcd
)
770 return (USB_GetCurrentFrame(hhcd
->Instance
));
774 * @brief Return the Host enumeration speed.
775 * @param hhcd: HCD handle
776 * @retval Enumeration speed
778 uint32_t HAL_HCD_GetCurrentSpeed(HCD_HandleTypeDef
*hhcd
)
780 return (USB_GetHostSpeed(hhcd
->Instance
));
791 /** @addtogroup HCD_Private_Functions
795 * @brief Handle Host Channel IN interrupt requests.
796 * @param hhcd: HCD handle
797 * @param chnum: Channel number.
798 * This parameter can be a value from 1 to 15
801 static void HCD_HC_IN_IRQHandler(HCD_HandleTypeDef
*hhcd
, uint8_t chnum
)
803 USB_OTG_GlobalTypeDef
*USBx
= hhcd
->Instance
;
804 uint32_t tmpreg
= 0U;
806 if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_AHBERR
)
808 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_AHBERR
);
809 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
811 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_ACK
)
813 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_ACK
);
816 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_STALL
)
818 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
819 hhcd
->hc
[chnum
].state
= HC_STALL
;
820 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_NAK
);
821 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_STALL
);
822 USB_HC_Halt(hhcd
->Instance
, chnum
);
824 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_DTERR
)
826 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
827 USB_HC_Halt(hhcd
->Instance
, chnum
);
828 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_NAK
);
829 hhcd
->hc
[chnum
].state
= HC_DATATGLERR
;
830 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_DTERR
);
833 if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_FRMOR
)
835 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
836 USB_HC_Halt(hhcd
->Instance
, chnum
);
837 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_FRMOR
);
840 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_XFRC
)
843 if (hhcd
->Init
.dma_enable
)
845 hhcd
->hc
[chnum
].xfer_count
= hhcd
->hc
[chnum
].xfer_len
- \
846 (USBx_HC(chnum
)->HCTSIZ
& USB_OTG_HCTSIZ_XFRSIZ
);
849 hhcd
->hc
[chnum
].state
= HC_XFRC
;
850 hhcd
->hc
[chnum
].ErrCnt
= 0U;
851 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_XFRC
);
854 if ((hhcd
->hc
[chnum
].ep_type
== EP_TYPE_CTRL
)||
855 (hhcd
->hc
[chnum
].ep_type
== EP_TYPE_BULK
))
857 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
858 USB_HC_Halt(hhcd
->Instance
, chnum
);
859 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_NAK
);
862 else if(hhcd
->hc
[chnum
].ep_type
== EP_TYPE_INTR
)
864 USBx_HC(chnum
)->HCCHAR
|= USB_OTG_HCCHAR_ODDFRM
;
865 hhcd
->hc
[chnum
].urb_state
= URB_DONE
;
866 HAL_HCD_HC_NotifyURBChange_Callback(hhcd
, chnum
, hhcd
->hc
[chnum
].urb_state
);
868 hhcd
->hc
[chnum
].toggle_in
^= 1U;
871 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_CHH
)
873 __HAL_HCD_MASK_HALT_HC_INT(chnum
);
875 if(hhcd
->hc
[chnum
].state
== HC_XFRC
)
877 hhcd
->hc
[chnum
].urb_state
= URB_DONE
;
880 else if (hhcd
->hc
[chnum
].state
== HC_STALL
)
882 hhcd
->hc
[chnum
].urb_state
= URB_STALL
;
885 else if((hhcd
->hc
[chnum
].state
== HC_XACTERR
) ||
886 (hhcd
->hc
[chnum
].state
== HC_DATATGLERR
))
888 if(hhcd
->hc
[chnum
].ErrCnt
++ > 3U)
890 hhcd
->hc
[chnum
].ErrCnt
= 0U;
891 hhcd
->hc
[chnum
].urb_state
= URB_ERROR
;
895 hhcd
->hc
[chnum
].urb_state
= URB_NOTREADY
;
898 /* re-activate the channel */
899 tmpreg
= USBx_HC(chnum
)->HCCHAR
;
900 tmpreg
&= ~USB_OTG_HCCHAR_CHDIS
;
901 tmpreg
|= USB_OTG_HCCHAR_CHENA
;
902 USBx_HC(chnum
)->HCCHAR
= tmpreg
;
904 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_CHH
);
905 HAL_HCD_HC_NotifyURBChange_Callback(hhcd
, chnum
, hhcd
->hc
[chnum
].urb_state
);
908 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_TXERR
)
910 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
911 hhcd
->hc
[chnum
].ErrCnt
++;
912 hhcd
->hc
[chnum
].state
= HC_XACTERR
;
913 USB_HC_Halt(hhcd
->Instance
, chnum
);
914 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_TXERR
);
916 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_NAK
)
918 if(hhcd
->hc
[chnum
].ep_type
== EP_TYPE_INTR
)
920 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
921 USB_HC_Halt(hhcd
->Instance
, chnum
);
924 /* Clear the NAK flag before re-enabling the channel for new IN request */
925 hhcd
->hc
[chnum
].state
= HC_NAK
;
926 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_NAK
);
928 if ((hhcd
->hc
[chnum
].ep_type
== EP_TYPE_CTRL
)||
929 (hhcd
->hc
[chnum
].ep_type
== EP_TYPE_BULK
))
931 /* re-activate the channel */
932 tmpreg
= USBx_HC(chnum
)->HCCHAR
;
933 tmpreg
&= ~USB_OTG_HCCHAR_CHDIS
;
934 tmpreg
|= USB_OTG_HCCHAR_CHENA
;
935 USBx_HC(chnum
)->HCCHAR
= tmpreg
;
941 * @brief Handle Host Channel OUT interrupt requests.
942 * @param hhcd: HCD handle
943 * @param chnum: Channel number.
944 * This parameter can be a value from 1 to 15
947 static void HCD_HC_OUT_IRQHandler (HCD_HandleTypeDef
*hhcd
, uint8_t chnum
)
949 USB_OTG_GlobalTypeDef
*USBx
= hhcd
->Instance
;
951 if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_AHBERR
)
953 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_AHBERR
);
954 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
956 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_ACK
)
958 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_ACK
);
960 if( hhcd
->hc
[chnum
].do_ping
== 1U)
962 hhcd
->hc
[chnum
].state
= HC_NYET
;
963 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
964 USB_HC_Halt(hhcd
->Instance
, chnum
);
965 hhcd
->hc
[chnum
].urb_state
= URB_NOTREADY
;
969 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_NYET
)
971 hhcd
->hc
[chnum
].state
= HC_NYET
;
972 hhcd
->hc
[chnum
].ErrCnt
= 0U;
973 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
974 USB_HC_Halt(hhcd
->Instance
, chnum
);
975 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_NYET
);
979 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_FRMOR
)
981 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
982 USB_HC_Halt(hhcd
->Instance
, chnum
);
983 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_FRMOR
);
986 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_XFRC
)
988 hhcd
->hc
[chnum
].ErrCnt
= 0U;
989 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
990 USB_HC_Halt(hhcd
->Instance
, chnum
);
991 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_XFRC
);
992 hhcd
->hc
[chnum
].state
= HC_XFRC
;
996 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_STALL
)
998 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_STALL
);
999 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
1000 USB_HC_Halt(hhcd
->Instance
, chnum
);
1001 hhcd
->hc
[chnum
].state
= HC_STALL
;
1004 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_NAK
)
1006 hhcd
->hc
[chnum
].ErrCnt
= 0U;
1007 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
1008 USB_HC_Halt(hhcd
->Instance
, chnum
);
1009 hhcd
->hc
[chnum
].state
= HC_NAK
;
1010 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_NAK
);
1013 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_TXERR
)
1015 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
1016 USB_HC_Halt(hhcd
->Instance
, chnum
);
1017 hhcd
->hc
[chnum
].state
= HC_XACTERR
;
1018 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_TXERR
);
1021 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_DTERR
)
1023 __HAL_HCD_UNMASK_HALT_HC_INT(chnum
);
1024 USB_HC_Halt(hhcd
->Instance
, chnum
);
1025 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_NAK
);
1026 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_DTERR
);
1027 hhcd
->hc
[chnum
].state
= HC_DATATGLERR
;
1031 else if ((USBx_HC(chnum
)->HCINT
) & USB_OTG_HCINT_CHH
)
1033 __HAL_HCD_MASK_HALT_HC_INT(chnum
);
1035 if(hhcd
->hc
[chnum
].state
== HC_XFRC
)
1037 hhcd
->hc
[chnum
].urb_state
= URB_DONE
;
1038 if (hhcd
->hc
[chnum
].ep_type
== EP_TYPE_BULK
)
1040 hhcd
->hc
[chnum
].toggle_out
^= 1U;
1043 else if (hhcd
->hc
[chnum
].state
== HC_NAK
)
1045 hhcd
->hc
[chnum
].urb_state
= URB_NOTREADY
;
1048 else if (hhcd
->hc
[chnum
].state
== HC_NYET
)
1050 hhcd
->hc
[chnum
].urb_state
= URB_NOTREADY
;
1051 hhcd
->hc
[chnum
].do_ping
= 0U;
1054 else if (hhcd
->hc
[chnum
].state
== HC_STALL
)
1056 hhcd
->hc
[chnum
].urb_state
= URB_STALL
;
1059 else if((hhcd
->hc
[chnum
].state
== HC_XACTERR
) ||
1060 (hhcd
->hc
[chnum
].state
== HC_DATATGLERR
))
1062 if(hhcd
->hc
[chnum
].ErrCnt
++ > 3U)
1064 hhcd
->hc
[chnum
].ErrCnt
= 0U;
1065 hhcd
->hc
[chnum
].urb_state
= URB_ERROR
;
1069 hhcd
->hc
[chnum
].urb_state
= URB_NOTREADY
;
1073 __HAL_HCD_CLEAR_HC_INT(chnum
, USB_OTG_HCINT_CHH
);
1074 HAL_HCD_HC_NotifyURBChange_Callback(hhcd
, chnum
, hhcd
->hc
[chnum
].urb_state
);
1079 * @brief Handle Rx Queue Level interrupt requests.
1080 * @param hhcd: HCD handle
1083 static void HCD_RXQLVL_IRQHandler(HCD_HandleTypeDef
*hhcd
)
1085 USB_OTG_GlobalTypeDef
*USBx
= hhcd
->Instance
;
1086 uint8_t channelnum
= 0;
1090 uint32_t tmpreg
= 0U;
1092 temp
= hhcd
->Instance
->GRXSTSP
;
1093 channelnum
= temp
& USB_OTG_GRXSTSP_EPNUM
;
1094 pktsts
= (temp
& USB_OTG_GRXSTSP_PKTSTS
) >> 17U;
1095 pktcnt
= (temp
& USB_OTG_GRXSTSP_BCNT
) >> 4U;
1099 case GRXSTS_PKTSTS_IN
:
1100 /* Read the data into the host buffer. */
1101 if ((pktcnt
> 0U) && (hhcd
->hc
[channelnum
].xfer_buff
!= (void *)0))
1104 USB_ReadPacket(hhcd
->Instance
, hhcd
->hc
[channelnum
].xfer_buff
, pktcnt
);
1106 /*manage multiple Xfer */
1107 hhcd
->hc
[channelnum
].xfer_buff
+= pktcnt
;
1108 hhcd
->hc
[channelnum
].xfer_count
+= pktcnt
;
1110 if((USBx_HC(channelnum
)->HCTSIZ
& USB_OTG_HCTSIZ_PKTCNT
) > 0)
1112 /* re-activate the channel when more packets are expected */
1113 tmpreg
= USBx_HC(channelnum
)->HCCHAR
;
1114 tmpreg
&= ~USB_OTG_HCCHAR_CHDIS
;
1115 tmpreg
|= USB_OTG_HCCHAR_CHENA
;
1116 USBx_HC(channelnum
)->HCCHAR
= tmpreg
;
1117 hhcd
->hc
[channelnum
].toggle_in
^= 1;
1122 case GRXSTS_PKTSTS_DATA_TOGGLE_ERR
:
1124 case GRXSTS_PKTSTS_IN_XFER_COMP
:
1125 case GRXSTS_PKTSTS_CH_HALTED
:
1132 * @brief Handle Host Port interrupt requests.
1133 * @param hhcd: HCD handle
1136 static void HCD_Port_IRQHandler (HCD_HandleTypeDef
*hhcd
)
1138 USB_OTG_GlobalTypeDef
*USBx
= hhcd
->Instance
;
1139 __IO
uint32_t hprt0
, hprt0_dup
;
1141 /* Handle Host Port Interrupts */
1143 hprt0_dup
= USBx_HPRT0
;
1145 hprt0_dup
&= ~(USB_OTG_HPRT_PENA
| USB_OTG_HPRT_PCDET
|\
1146 USB_OTG_HPRT_PENCHNG
| USB_OTG_HPRT_POCCHNG
);
1148 /* Check whether Port Connect Detected */
1149 if((hprt0
& USB_OTG_HPRT_PCDET
) == USB_OTG_HPRT_PCDET
)
1151 if((hprt0
& USB_OTG_HPRT_PCSTS
) == USB_OTG_HPRT_PCSTS
)
1153 USB_MASK_INTERRUPT(hhcd
->Instance
, USB_OTG_GINTSTS_DISCINT
);
1154 HAL_HCD_Connect_Callback(hhcd
);
1156 hprt0_dup
|= USB_OTG_HPRT_PCDET
;
1160 /* Check whether Port Enable Changed */
1161 if((hprt0
& USB_OTG_HPRT_PENCHNG
) == USB_OTG_HPRT_PENCHNG
)
1163 hprt0_dup
|= USB_OTG_HPRT_PENCHNG
;
1165 if((hprt0
& USB_OTG_HPRT_PENA
) == USB_OTG_HPRT_PENA
)
1167 if(hhcd
->Init
.phy_itface
== USB_OTG_EMBEDDED_PHY
)
1169 if ((hprt0
& USB_OTG_HPRT_PSPD
) == (HPRT0_PRTSPD_LOW_SPEED
<< 17U))
1171 USB_InitFSLSPClkSel(hhcd
->Instance
,HCFG_6_MHZ
);
1175 USB_InitFSLSPClkSel(hhcd
->Instance
,HCFG_48_MHZ
);
1180 if(hhcd
->Init
.speed
== HCD_SPEED_FULL
)
1182 USBx_HOST
->HFIR
= 60000U;
1186 HAL_HCD_Connect_Callback(hhcd
);
1191 USBx_HPRT0
&= ~(USB_OTG_HPRT_PENA
| USB_OTG_HPRT_PCDET
|\
1192 USB_OTG_HPRT_PENCHNG
| USB_OTG_HPRT_POCCHNG
);
1194 USB_UNMASK_INTERRUPT(hhcd
->Instance
, USB_OTG_GINTSTS_DISCINT
);
1198 /* Check for an over current */
1199 if((hprt0
& USB_OTG_HPRT_POCCHNG
) == USB_OTG_HPRT_POCCHNG
)
1201 hprt0_dup
|= USB_OTG_HPRT_POCCHNG
;
1204 /* Clear Port Interrupts */
1205 USBx_HPRT0
= hprt0_dup
;
1211 #endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx ||
1212 STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Rx ||
1213 STM32F412Vx || STM32F412Cx || defined(STM32F413xx) || defined(STM32F423xx) */
1214 #endif /* HAL_HCD_MODULE_ENABLED */
1223 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/