Merge pull request #11270 from haslinghuis/rename_attr
[betaflight.git] / lib / main / STM32H7 / Drivers / STM32H7xx_HAL_Driver / Inc / stm32h7xx_ll_usb.h
blob8970cfba2fcfd3ec3dc9108620da1139d0d3b9e4
1 /**
2 ******************************************************************************
3 * @file stm32h7xx_ll_usb.h
4 * @author MCD Application Team
5 * @brief Header file of USB Low Layer HAL module.
6 ******************************************************************************
7 * @attention
9 * <h2><center>&copy; Copyright (c) 2017 STMicroelectronics.
10 * All rights reserved.</center></h2>
12 * This software component is licensed by ST under BSD 3-Clause license,
13 * the "License"; You may not use this file except in compliance with the
14 * License. You may obtain a copy of the License at:
15 * opensource.org/licenses/BSD-3-Clause
17 ******************************************************************************
20 /* Define to prevent recursive inclusion -------------------------------------*/
21 #ifndef STM32H7xx_LL_USB_H
22 #define STM32H7xx_LL_USB_H
24 #ifdef __cplusplus
25 extern "C" {
26 #endif
28 /* Includes ------------------------------------------------------------------*/
29 #include "stm32h7xx_hal_def.h"
31 #if defined (USB_OTG_FS) || defined (USB_OTG_HS)
32 /** @addtogroup STM32H7xx_HAL_Driver
33 * @{
36 /** @addtogroup USB_LL
37 * @{
40 /* Exported types ------------------------------------------------------------*/
42 /**
43 * @brief USB Mode definition
45 #if defined (USB_OTG_FS) || defined (USB_OTG_HS)
47 typedef enum
49 USB_DEVICE_MODE = 0,
50 USB_HOST_MODE = 1,
51 USB_DRD_MODE = 2
52 } USB_OTG_ModeTypeDef;
54 /**
55 * @brief URB States definition
57 typedef enum
59 URB_IDLE = 0,
60 URB_DONE,
61 URB_NOTREADY,
62 URB_NYET,
63 URB_ERROR,
64 URB_STALL
65 } USB_OTG_URBStateTypeDef;
67 /**
68 * @brief Host channel States definition
70 typedef enum
72 HC_IDLE = 0,
73 HC_XFRC,
74 HC_HALTED,
75 HC_NAK,
76 HC_NYET,
77 HC_STALL,
78 HC_XACTERR,
79 HC_BBLERR,
80 HC_DATATGLERR
81 } USB_OTG_HCStateTypeDef;
83 /**
84 * @brief USB OTG Initialization Structure definition
86 typedef struct
88 uint32_t dev_endpoints; /*!< Device Endpoints number.
89 This parameter depends on the used USB core.
90 This parameter must be a number between Min_Data = 1 and Max_Data = 15 */
92 uint32_t Host_channels; /*!< Host Channels number.
93 This parameter Depends on the used USB core.
94 This parameter must be a number between Min_Data = 1 and Max_Data = 15 */
96 uint32_t speed; /*!< USB Core speed.
97 This parameter can be any value of @ref USB_Core_Speed_ */
99 uint32_t dma_enable; /*!< Enable or disable of the USB embedded DMA used only for OTG HS. */
101 uint32_t ep0_mps; /*!< Set the Endpoint 0 Max Packet size. */
103 uint32_t phy_itface; /*!< Select the used PHY interface.
104 This parameter can be any value of @ref USB_Core_PHY_ */
106 uint32_t Sof_enable; /*!< Enable or disable the output of the SOF signal. */
108 uint32_t low_power_enable; /*!< Enable or disable the low power mode. */
110 uint32_t lpm_enable; /*!< Enable or disable Link Power Management. */
112 uint32_t battery_charging_enable; /*!< Enable or disable Battery charging. */
114 uint32_t vbus_sensing_enable; /*!< Enable or disable the VBUS Sensing feature. */
116 uint32_t use_dedicated_ep1; /*!< Enable or disable the use of the dedicated EP1 interrupt. */
118 uint32_t use_external_vbus; /*!< Enable or disable the use of the external VBUS. */
119 } USB_OTG_CfgTypeDef;
121 typedef struct
123 uint8_t num; /*!< Endpoint number
124 This parameter must be a number between Min_Data = 1 and Max_Data = 15 */
126 uint8_t is_in; /*!< Endpoint direction
127 This parameter must be a number between Min_Data = 0 and Max_Data = 1 */
129 uint8_t is_stall; /*!< Endpoint stall condition
130 This parameter must be a number between Min_Data = 0 and Max_Data = 1 */
132 uint8_t type; /*!< Endpoint type
133 This parameter can be any value of @ref USB_EP_Type_ */
135 uint8_t data_pid_start; /*!< Initial data PID
136 This parameter must be a number between Min_Data = 0 and Max_Data = 1 */
138 uint8_t even_odd_frame; /*!< IFrame parity
139 This parameter must be a number between Min_Data = 0 and Max_Data = 1 */
141 uint16_t tx_fifo_num; /*!< Transmission FIFO number
142 This parameter must be a number between Min_Data = 1 and Max_Data = 15 */
144 uint32_t maxpacket; /*!< Endpoint Max packet size
145 This parameter must be a number between Min_Data = 0 and Max_Data = 64KB */
147 uint8_t *xfer_buff; /*!< Pointer to transfer buffer */
149 uint32_t dma_addr; /*!< 32 bits aligned transfer buffer address */
151 uint32_t xfer_len; /*!< Current transfer length */
153 uint32_t xfer_count; /*!< Partial transfer length in case of multi packet transfer */
154 } USB_OTG_EPTypeDef;
156 typedef struct
158 uint8_t dev_addr; /*!< USB device address.
159 This parameter must be a number between Min_Data = 1 and Max_Data = 255 */
161 uint8_t ch_num; /*!< Host channel number.
162 This parameter must be a number between Min_Data = 1 and Max_Data = 15 */
164 uint8_t ep_num; /*!< Endpoint number.
165 This parameter must be a number between Min_Data = 1 and Max_Data = 15 */
167 uint8_t ep_is_in; /*!< Endpoint direction
168 This parameter must be a number between Min_Data = 0 and Max_Data = 1 */
170 uint8_t speed; /*!< USB Host speed.
171 This parameter can be any value of @ref USB_Core_Speed_ */
173 uint8_t do_ping; /*!< Enable or disable the use of the PING protocol for HS mode. */
175 uint8_t process_ping; /*!< Execute the PING protocol for HS mode. */
177 uint8_t ep_type; /*!< Endpoint Type.
178 This parameter can be any value of @ref USB_EP_Type_ */
180 uint16_t max_packet; /*!< Endpoint Max packet size.
181 This parameter must be a number between Min_Data = 0 and Max_Data = 64KB */
183 uint8_t data_pid; /*!< Initial data PID.
184 This parameter must be a number between Min_Data = 0 and Max_Data = 1 */
186 uint8_t *xfer_buff; /*!< Pointer to transfer buffer. */
188 uint32_t xfer_len; /*!< Current transfer length. */
190 uint32_t xfer_count; /*!< Partial transfer length in case of multi packet transfer. */
192 uint8_t toggle_in; /*!< IN transfer current toggle flag.
193 This parameter must be a number between Min_Data = 0 and Max_Data = 1 */
195 uint8_t toggle_out; /*!< OUT transfer current toggle flag
196 This parameter must be a number between Min_Data = 0 and Max_Data = 1 */
198 uint32_t dma_addr; /*!< 32 bits aligned transfer buffer address. */
200 uint32_t ErrCnt; /*!< Host channel error count.*/
202 USB_OTG_URBStateTypeDef urb_state; /*!< URB state.
203 This parameter can be any value of @ref USB_OTG_URBStateTypeDef */
205 USB_OTG_HCStateTypeDef state; /*!< Host Channel state.
206 This parameter can be any value of @ref USB_OTG_HCStateTypeDef */
207 } USB_OTG_HCTypeDef;
208 #endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */
211 /* Exported constants --------------------------------------------------------*/
213 /** @defgroup PCD_Exported_Constants PCD Exported Constants
214 * @{
217 #if defined (USB_OTG_FS) || defined (USB_OTG_HS)
218 /** @defgroup USB_OTG_CORE VERSION ID
219 * @{
221 #define USB_OTG_CORE_ID_300A 0x4F54300AU
222 #define USB_OTG_CORE_ID_310A 0x4F54310AU
224 * @}
227 /** @defgroup USB_Core_Mode_ USB Core Mode
228 * @{
230 #define USB_OTG_MODE_DEVICE 0U
231 #define USB_OTG_MODE_HOST 1U
232 #define USB_OTG_MODE_DRD 2U
234 * @}
237 /** @defgroup USB_LL Device Speed
238 * @{
240 #define USBD_HS_SPEED 0U
241 #define USBD_HSINFS_SPEED 1U
242 #define USBH_HS_SPEED 0U
243 #define USBD_FS_SPEED 2U
244 #define USBH_FSLS_SPEED 1U
246 * @}
249 /** @defgroup USB_LL_Core_Speed USB Low Layer Core Speed
250 * @{
252 #define USB_OTG_SPEED_HIGH 0U
253 #define USB_OTG_SPEED_HIGH_IN_FULL 1U
254 #define USB_OTG_SPEED_FULL 3U
256 * @}
259 /** @defgroup USB_LL_Core_PHY USB Low Layer Core PHY
260 * @{
262 #define USB_OTG_ULPI_PHY 1U
263 #define USB_OTG_EMBEDDED_PHY 2U
265 * @}
268 /** @defgroup USB_LL_Turnaround_Timeout Turnaround Timeout Value
269 * @{
271 #ifndef USBD_HS_TRDT_VALUE
272 #define USBD_HS_TRDT_VALUE 9U
273 #endif /* USBD_HS_TRDT_VALUE */
274 #ifndef USBD_FS_TRDT_VALUE
275 #define USBD_FS_TRDT_VALUE 5U
276 #define USBD_DEFAULT_TRDT_VALUE 9U
277 #endif /* USBD_HS_TRDT_VALUE */
279 * @}
282 /** @defgroup USB_LL_Core_MPS USB Low Layer Core MPS
283 * @{
285 #define USB_OTG_HS_MAX_PACKET_SIZE 512U
286 #define USB_OTG_FS_MAX_PACKET_SIZE 64U
287 #define USB_OTG_MAX_EP0_SIZE 64U
289 * @}
292 /** @defgroup USB_LL_Core_PHY_Frequency USB Low Layer Core PHY Frequency
293 * @{
295 #define DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ (0U << 1)
296 #define DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ (1U << 1)
297 #define DSTS_ENUMSPD_FS_PHY_48MHZ (3U << 1)
299 * @}
302 /** @defgroup USB_LL_CORE_Frame_Interval USB Low Layer Core Frame Interval
303 * @{
305 #define DCFG_FRAME_INTERVAL_80 0U
306 #define DCFG_FRAME_INTERVAL_85 1U
307 #define DCFG_FRAME_INTERVAL_90 2U
308 #define DCFG_FRAME_INTERVAL_95 3U
310 * @}
313 /** @defgroup USB_LL_EP0_MPS USB Low Layer EP0 MPS
314 * @{
316 #define DEP0CTL_MPS_64 0U
317 #define DEP0CTL_MPS_32 1U
318 #define DEP0CTL_MPS_16 2U
319 #define DEP0CTL_MPS_8 3U
321 * @}
324 /** @defgroup USB_LL_EP_Speed USB Low Layer EP Speed
325 * @{
327 #define EP_SPEED_LOW 0U
328 #define EP_SPEED_FULL 1U
329 #define EP_SPEED_HIGH 2U
331 * @}
334 /** @defgroup USB_LL_EP_Type USB Low Layer EP Type
335 * @{
337 #define EP_TYPE_CTRL 0U
338 #define EP_TYPE_ISOC 1U
339 #define EP_TYPE_BULK 2U
340 #define EP_TYPE_INTR 3U
341 #define EP_TYPE_MSK 3U
343 * @}
346 /** @defgroup USB_LL_STS_Defines USB Low Layer STS Defines
347 * @{
349 #define STS_GOUT_NAK 1U
350 #define STS_DATA_UPDT 2U
351 #define STS_XFER_COMP 3U
352 #define STS_SETUP_COMP 4U
353 #define STS_SETUP_UPDT 6U
355 * @}
358 /** @defgroup USB_LL_HCFG_SPEED_Defines USB Low Layer HCFG Speed Defines
359 * @{
361 #define HCFG_30_60_MHZ 0U
362 #define HCFG_48_MHZ 1U
363 #define HCFG_6_MHZ 2U
365 * @}
368 /** @defgroup USB_LL_HPRT0_PRTSPD_SPEED_Defines USB Low Layer HPRT0 PRTSPD Speed Defines
369 * @{
371 #define HPRT0_PRTSPD_HIGH_SPEED 0U
372 #define HPRT0_PRTSPD_FULL_SPEED 1U
373 #define HPRT0_PRTSPD_LOW_SPEED 2U
375 * @}
378 #define HCCHAR_CTRL 0U
379 #define HCCHAR_ISOC 1U
380 #define HCCHAR_BULK 2U
381 #define HCCHAR_INTR 3U
383 #define HC_PID_DATA0 0U
384 #define HC_PID_DATA2 1U
385 #define HC_PID_DATA1 2U
386 #define HC_PID_SETUP 3U
388 #define GRXSTS_PKTSTS_IN 2U
389 #define GRXSTS_PKTSTS_IN_XFER_COMP 3U
390 #define GRXSTS_PKTSTS_DATA_TOGGLE_ERR 5U
391 #define GRXSTS_PKTSTS_CH_HALTED 7U
393 #define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx_BASE + USB_OTG_PCGCCTL_BASE)
394 #define USBx_HPRT0 *(__IO uint32_t *)((uint32_t)USBx_BASE + USB_OTG_HOST_PORT_BASE)
396 #define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)(USBx_BASE + USB_OTG_DEVICE_BASE))
397 #define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)(USBx_BASE + USB_OTG_IN_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE)))
398 #define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)(USBx_BASE + USB_OTG_OUT_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE)))
399 #define USBx_DFIFO(i) *(__IO uint32_t *)(USBx_BASE + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE))
401 #define USBx_HOST ((USB_OTG_HostTypeDef *)(USBx_BASE + USB_OTG_HOST_BASE))
402 #define USBx_HC(i) ((USB_OTG_HostChannelTypeDef *)(USBx_BASE + USB_OTG_HOST_CHANNEL_BASE + ((i) * USB_OTG_HOST_CHANNEL_SIZE)))
403 #endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */
405 #define EP_ADDR_MSK 0xFU
407 * @}
410 /* Exported macro ------------------------------------------------------------*/
411 /** @defgroup USB_LL_Exported_Macros USB Low Layer Exported Macros
412 * @{
414 #if defined (USB_OTG_FS) || defined (USB_OTG_HS)
415 #define USB_MASK_INTERRUPT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->GINTMSK &= ~(__INTERRUPT__))
416 #define USB_UNMASK_INTERRUPT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->GINTMSK |= (__INTERRUPT__))
418 #define CLEAR_IN_EP_INTR(__EPNUM__, __INTERRUPT__) (USBx_INEP(__EPNUM__)->DIEPINT = (__INTERRUPT__))
419 #define CLEAR_OUT_EP_INTR(__EPNUM__, __INTERRUPT__) (USBx_OUTEP(__EPNUM__)->DOEPINT = (__INTERRUPT__))
420 #endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */
422 * @}
425 /* Exported functions --------------------------------------------------------*/
426 /** @addtogroup USB_LL_Exported_Functions USB Low Layer Exported Functions
427 * @{
429 #if defined (USB_OTG_FS) || defined (USB_OTG_HS)
430 HAL_StatusTypeDef USB_CoreInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg);
431 HAL_StatusTypeDef USB_DevInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg);
432 HAL_StatusTypeDef USB_EnableGlobalInt(USB_OTG_GlobalTypeDef *USBx);
433 HAL_StatusTypeDef USB_DisableGlobalInt(USB_OTG_GlobalTypeDef *USBx);
434 HAL_StatusTypeDef USB_SetTurnaroundTime(USB_OTG_GlobalTypeDef *USBx, uint32_t hclk, uint8_t speed);
435 HAL_StatusTypeDef USB_SetCurrentMode(USB_OTG_GlobalTypeDef *USBx, USB_OTG_ModeTypeDef mode);
436 HAL_StatusTypeDef USB_SetDevSpeed(USB_OTG_GlobalTypeDef *USBx, uint8_t speed);
437 HAL_StatusTypeDef USB_FlushRxFifo(USB_OTG_GlobalTypeDef *USBx);
438 HAL_StatusTypeDef USB_FlushTxFifo(USB_OTG_GlobalTypeDef *USBx, uint32_t num);
439 HAL_StatusTypeDef USB_ActivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep);
440 HAL_StatusTypeDef USB_DeactivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep);
441 HAL_StatusTypeDef USB_ActivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep);
442 HAL_StatusTypeDef USB_DeactivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep);
443 HAL_StatusTypeDef USB_EPStartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma);
444 HAL_StatusTypeDef USB_EP0StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma);
445 HAL_StatusTypeDef USB_WritePacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *src, uint8_t ch_ep_num, uint16_t len, uint8_t dma);
446 void *USB_ReadPacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *dest, uint16_t len);
447 HAL_StatusTypeDef USB_EPSetStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep);
448 HAL_StatusTypeDef USB_EPClearStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep);
449 HAL_StatusTypeDef USB_SetDevAddress(USB_OTG_GlobalTypeDef *USBx, uint8_t address);
450 HAL_StatusTypeDef USB_DevConnect(USB_OTG_GlobalTypeDef *USBx);
451 HAL_StatusTypeDef USB_DevDisconnect(USB_OTG_GlobalTypeDef *USBx);
452 HAL_StatusTypeDef USB_StopDevice(USB_OTG_GlobalTypeDef *USBx);
453 HAL_StatusTypeDef USB_ActivateSetup(USB_OTG_GlobalTypeDef *USBx);
454 HAL_StatusTypeDef USB_EP0_OutStart(USB_OTG_GlobalTypeDef *USBx, uint8_t dma, uint8_t *psetup);
455 uint8_t USB_GetDevSpeed(USB_OTG_GlobalTypeDef *USBx);
456 uint32_t USB_GetMode(USB_OTG_GlobalTypeDef *USBx);
457 uint32_t USB_ReadInterrupts(USB_OTG_GlobalTypeDef *USBx);
458 uint32_t USB_ReadDevAllOutEpInterrupt(USB_OTG_GlobalTypeDef *USBx);
459 uint32_t USB_ReadDevOutEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum);
460 uint32_t USB_ReadDevAllInEpInterrupt(USB_OTG_GlobalTypeDef *USBx);
461 uint32_t USB_ReadDevInEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum);
462 void USB_ClearInterrupts(USB_OTG_GlobalTypeDef *USBx, uint32_t interrupt);
464 HAL_StatusTypeDef USB_HostInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg);
465 HAL_StatusTypeDef USB_InitFSLSPClkSel(USB_OTG_GlobalTypeDef *USBx, uint8_t freq);
466 HAL_StatusTypeDef USB_ResetPort(USB_OTG_GlobalTypeDef *USBx);
467 HAL_StatusTypeDef USB_DriveVbus(USB_OTG_GlobalTypeDef *USBx, uint8_t state);
468 uint32_t USB_GetHostSpeed(USB_OTG_GlobalTypeDef *USBx);
469 uint32_t USB_GetCurrentFrame(USB_OTG_GlobalTypeDef *USBx);
470 HAL_StatusTypeDef USB_HC_Init(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num,
471 uint8_t epnum, uint8_t dev_address, uint8_t speed,
472 uint8_t ep_type, uint16_t mps);
473 HAL_StatusTypeDef USB_HC_StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_HCTypeDef *hc, uint8_t dma);
474 uint32_t USB_HC_ReadInterrupt(USB_OTG_GlobalTypeDef *USBx);
475 HAL_StatusTypeDef USB_HC_Halt(USB_OTG_GlobalTypeDef *USBx, uint8_t hc_num);
476 HAL_StatusTypeDef USB_DoPing(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num);
477 HAL_StatusTypeDef USB_StopHost(USB_OTG_GlobalTypeDef *USBx);
478 HAL_StatusTypeDef USB_ActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx);
479 HAL_StatusTypeDef USB_DeActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx);
480 #endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */
483 * @}
487 * @}
491 * @}
495 * @}
497 #endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */
499 #ifdef __cplusplus
501 #endif
504 #endif /* STM32H7xx_LL_USB_H */
506 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/